From 0b1ee23a554b12f1a30aff91c817d0534f5ca570 Mon Sep 17 00:00:00 2001 From: Mallory Date: Tue, 19 Feb 2013 15:46:32 -0800 Subject: [PATCH 01/26] initial commit --- ArmPlannerPR2.py | 87 +++++ IKPlannerFunctions.py | 229 ++++++++++++ TrajectoryPlayback.py | 62 ++++ brett2/mtf_trajectories.py | 140 ++++++++ joint_states_listener/CMakeLists.txt | 30 ++ joint_states_listener/Makefile | 1 + joint_states_listener/mainpage.dox | 14 + joint_states_listener/manifest.xml | 14 + .../nodes/joint_states_listener.py | 93 +++++ .../nodes/joint_states_trajectory_recorder.py | 109 ++++++ .../joint_states_trajectory_recorder2.py | 111 ++++++ .../src/joint_states_listener/__init__.py | 1 + .../srv/_ReturnJointStates.py | 330 ++++++++++++++++++ .../src/joint_states_listener/srv/__init__.py | 1 + .../srv/ReturnJointStates.srv | 6 + .../joint_states_listener/ReturnJointStates.h | 304 ++++++++++++++++ joint_states_listener/srv_gen/generated | 1 + .../srv_gen/lisp/ReturnJointStates.lisp | 310 ++++++++++++++++ .../srv_gen/lisp/_package.lisp | 10 + .../lisp/_package_ReturnJointStates.lisp | 12 + .../lisp/joint_states_listener-srv.asd | 9 + launch.py | 6 + 22 files changed, 1880 insertions(+) create mode 100644 ArmPlannerPR2.py create mode 100644 IKPlannerFunctions.py create mode 100644 TrajectoryPlayback.py create mode 100644 brett2/mtf_trajectories.py create mode 100644 joint_states_listener/CMakeLists.txt create mode 100644 joint_states_listener/Makefile create mode 100644 joint_states_listener/mainpage.dox create mode 100644 joint_states_listener/manifest.xml create mode 100755 joint_states_listener/nodes/joint_states_listener.py create mode 100755 joint_states_listener/nodes/joint_states_trajectory_recorder.py create mode 100755 joint_states_listener/nodes/joint_states_trajectory_recorder2.py create mode 100644 joint_states_listener/src/joint_states_listener/__init__.py create mode 100644 joint_states_listener/src/joint_states_listener/srv/_ReturnJointStates.py create mode 100644 joint_states_listener/src/joint_states_listener/srv/__init__.py create mode 100644 joint_states_listener/srv/ReturnJointStates.srv create mode 100644 joint_states_listener/srv_gen/cpp/include/joint_states_listener/ReturnJointStates.h create mode 100644 joint_states_listener/srv_gen/generated create mode 100644 joint_states_listener/srv_gen/lisp/ReturnJointStates.lisp create mode 100644 joint_states_listener/srv_gen/lisp/_package.lisp create mode 100644 joint_states_listener/srv_gen/lisp/_package_ReturnJointStates.lisp create mode 100644 joint_states_listener/srv_gen/lisp/joint_states_listener-srv.asd create mode 100644 launch.py diff --git a/ArmPlannerPR2.py b/ArmPlannerPR2.py new file mode 100644 index 0000000..2e1f7c1 --- /dev/null +++ b/ArmPlannerPR2.py @@ -0,0 +1,87 @@ +from IKPlannerFunctions import IKInterpolationPlanner +from brett2.PR2 import PR2, Arm, IKFail + +class PlannerArm(Arm): + """ + Planner class for the Arm. + """ + def __init__ (self, pr2, rl): + Arm.__init__(self, pr2, rl) + self.planner = IKInterpolationPlanner(self, self.lr) + + def goInDirection (self, d, dist, steps=10): + """ + Moves the tool tip in the specified direction in the gripper frame. + + Direction of movement -> d + f -> forward (along the tip of the gripper) + b -> backward + u -> up + d -> down + l -> left + r -> right + Distance traveled by tool tip -> dist + Number of points of linear interpolation -> steps + """ + self.pr2.update_rave() + trajectory = self.planner.goInDirection(d, dist, steps) + + if trajectory: + self.follow_joint_trajectory (trajectory) + else: raise IKFail + + + def goInWorldDirection (self, d, dist, steps=10): + """ + Moves the tool tip in the specified direction in the base_link frame. + + Direction of movement -> d + f -> forward + b -> backward + u -> up + d -> down + l -> left + r -> right + Distance traveled by tool tip -> dist + Number of points of linear interpolation -> steps + """ + self.pr2.update_rave() + trajectory = self.planner.goInWorldDirection(d, dist, steps) + + if trajectory: + self.follow_joint_trajectory (trajectory) + else: raise IKFail + + + def circleAroundRadius (self, d, rad, finAng, steps=10): + """ + Moves the gripper in a circle. + + Direction of circle (either inner or outer) -> d + Radius of circle -> rad + Final angle covered by circle -> finAng + Number of points of linear interpolation of angle -> steps + """ + self.pr2.update_rave() + trajectory = self.planner.circleAroundRadius (d, rad, finAng) + + if trajectory: + self.follow_joint_trajectory (trajectory) + else: raise IKFail + + + +class PlannerPR2 (PR2): + """ + Planner class for PR2 with planning arms. + """ + def __init__ (self): + PR2.__init__(self) + self.rarm = PlannerArm(self,'r') + self.larm = PlannerArm(self, 'l') + + def gotoArmPosture (self, pos): + self.larm.goto_posture(pos) + self.rarm.goto_posture(pos) + self.update_rave() + diff --git a/IKPlannerFunctions.py b/IKPlannerFunctions.py new file mode 100644 index 0000000..6a0c2a5 --- /dev/null +++ b/IKPlannerFunctions.py @@ -0,0 +1,229 @@ +from brett2.PR2 import Arm +import kinematics.kinematics_utils as ku + +import rospy + +import numpy as np +from numpy.linalg import norm + + +class IKInterpolationPlanner(object): + """ + Class which plans based on OpenRAVE's IK solver + """ + def __init__(self, _arm, _rl, _filter_options=0): + self.rl = _rl + #If useful + self.rl_long = {'l':'left', 'r':'right'}[self.rl] + self.arm = _arm + self.filter_options = _filter_options + + + def setFilterOptions (self, filter_options): + """ + Filter options indicate basic options while planning: + + IKFO_CheckEnvCollisions = 1 + IKFO_IgnoreSelfCollisions = 2 + IKFO_IgnoreJointLimits = 4 + IKFO_IgnoreCustomFilters = 8 + IKFO_IgnoreEndEffectorCollisions = 16 + """ + self.filter_options = filter_options + + + + def plan(self, transforms): + """ + Basic plan function which just solves the IK for each transform given. + + List of transforms along path -> transforms + """ + if len(transforms) < 1: + rospy.ERROR('Not enough transforms!') + + if len(transforms) == 1: + firstTransform = self.arm.manip.GetEndEffectorTransform() + transforms = [firstTransform, transforms[0]] + + trajectory = [] + + for transform in transforms: + joints = self.arm.manip.FindIKSolution(transform, self.filter_options) + + if joints is None: + rospy.logwarn('IK Failed on ' + self.rl_long + 'arm.') + return joints + + trajectory.append(joints) + + return trajectory + + + #Assuming all the Joint DOFs are numpy arrays + def smoothPlan(self, transforms): + """ + Smooth plan function which solves for all IK solutions for each transform given. + It then chooses the joint DOF values which are closest to current DOF values. + + List of transforms along path -> transforms + """ + if len(transforms) < 1: + rospy.ERROR('Not enough transforms!') + + if len(transforms) == 1: + initTransform = self.arm.manip.GetEndEffectorTransform() + transforms = [initTransform, transforms[0]] + + trajectory = [] + + #armIndices = self.arm.manip.GetJointIndices() + #currJoints = self.pr2.robot.GetDOFValues(armIndices) + currJoints = self.arm.get_joint_positions() + + for transform in transforms: + allJoints = self.arm.manip.FindIKSolutions(transform, self.filter_options) + + if not allJoints.size: + rospy.logwarn('IK Failed on ' + self.rl_long + 'arm.') + return None + + allJoints = [ku.closer_joint_angles(joints, currJoints) for joints in allJoints] + normDifferences = [norm(currJoints-joints,2) for joints in allJoints] + minIndex = normDifferences.index(min(normDifferences)) + + trajectory.append(allJoints[minIndex]) + + return trajectory + + + #Not sure about scale here. Treating everything as meters. + #I don't think I need to worry about scale here anyway + def goInDirection (self, d, dist, steps=10): + """ + Moves the tool tip in the specified direction in the gripper frame. + + Direction of movement -> d + f -> forward (along the tip of the gripper) + b -> backward + u -> up + d -> down + l -> left + r -> right + Distance traveled by tool tip -> dist + Number of points of linear interpolation -> steps + """ + initTransform = self.arm.manip.GetEndEffectorTransform() + initOrigin = initTransform[0:3,3] + + if d == 'f': + dirVec = initTransform[0:3,2] + elif d == 'b': + dirVec = -1*initTransform[0:3,2] + elif d == 'u': + dirVec = initTransform[0:3,1] + elif d == 'd': + dirVec = -1*initTransform[0:3,1] + elif d == 'l': + dirVec = initTransform[0:3,0] + elif d == 'r': + dirVec = -1*initTransform[0:3,0] + else: + rospy.ERROR("Invalid direction: " + d) + + endOffset = dirVec*float(dist) + + transforms = [] + + for step in range(steps+1): + currVec = initOrigin + float(step)/steps*endOffset + + newTfm = initTransform.copy() + newTfm[0:3,3] = np.unwrap(currVec) + + transforms.append(newTfm) + + return self.smoothPlan(transforms) + + + + #Not sure about scale here. Treating everything as meters. + #I don't think I need to worry about scale here anyway + def goInWorldDirection (self, d, dist, steps=10): + """ + Moves the tool tip in the specified direction in the base_link frame. + + Direction of movement -> d + f -> forward + b -> backward + u -> up + d -> down + l -> left + r -> right + Distance traveled by tool tip -> dist + Number of points of linear interpolation -> steps + """ + initTransform = self.arm.manip.GetEndEffectorTransform() + initOrigin = initTransform[0:3,3] + baseTransform = self.arm.pr2.robot.GetLink('base_link').GetTransform() + + if d == 'u': + dirVec = baseTransform[0:3,2] + elif d == 'd': + dirVec = -1*baseTransform[0:3,2] + elif d == 'l': + dirVec = baseTransform[0:3,1] + elif d == 'r': + dirVec = -1*baseTransform[0:3,1] + elif d == 'f': + dirVec = baseTransform[0:3,0] + elif d == 'b': + dirVec = -1*baseTransform[0:3,0] + else: + rospy.ERROR("Invalid direction: " + d) + + endOffset = dirVec*float(dist) + + transforms = [] + + for step in range(steps+1): + currVec = initOrigin + endOffset*(float(step)/steps) + + newTfm = initTransform.copy() + newTfm[0:3,3] = np.unwrap(currVec) + + transforms.append(newTfm) + + return self.smoothPlan(transforms) + + + def circleAroundRadius (self, d, rad, finAng, steps=10): + """ + Moves the gripper in a circle. + + Direction of circle (either inner or outer) -> d + Radius of circle -> rad + Final angle covered by circle -> finAng + Number of points of linear interpolation of angle -> steps + """ + WorldFromEETfm = self.arm.manip.GetEndEffectorTransform() + + initTfm = np.eye(4) + initOrigin = d*rad*np.array([0,1,0]) + initTfm[0:3,3] = np.unwrap(initOrigin) + transforms = [] + + for step in range(steps+1): + ang = float(finAng)*step/steps + + rotMat = np.eye(4) + rotMat[0,0] = np.cos(d*ang) + rotMat[0,1] = -np.sin(d*ang) + rotMat[1,0] = np.sin(d*ang) + rotMat[1,1] = np.cos(d*ang) + rotMat[0:3,3] = np.unwrap(-1*initOrigin) + print rotMat + + transforms.append(WorldFromEETfm.dot(rotMat.dot(initTfm))) + + return self.smoothPlan(transforms) diff --git a/TrajectoryPlayback.py b/TrajectoryPlayback.py new file mode 100644 index 0000000..95c148c --- /dev/null +++ b/TrajectoryPlayback.py @@ -0,0 +1,62 @@ +import rospy +import numpy as np +import brett2.trajectories as tj +from brett2.PR2 import PR2 +import trajectory_msgs.msg as tm + +if __name__ == "__main__": + rospy.init_node("trajectory_playback") + p = PR2 () + + traj_file_path = '/home/mallory/fuerte_workspace/sandbox/suturing/pr2_suturing/joint_states_listener/trajectories' + traj_name = [] + ## Trajectory Options + #traj_name.append('/full_running_suture/pt1') #pierce both flaps and pull through + #traj_name.append('/full_running_suture/pt2') #tie right 2 loop knot + #traj_name.append('/full_running_suture/pt3') #tie left 1 loop knot + #traj_name.append('/full_running_suture/pt4') #tie right 1 loop knot + #traj_name.append('/full_running_suture/pt5') #tie left 1 loop knot + #traj_name.append('/full_running_suture/pt6') #first stitch of running suture + #traj_name.append('/full_running_suture/pt7') #second stitch of running suture + #traj_name.append('/full_running_suture/pt8') #third stitch of running suture + #traj_name.append('/full_running_suture/pt9') #final stitch of running suture + #traj_name.append('/full_running_suture/pt10') #final knot pt1 + #traj_name.append('/full_running_suture/pt11') #final knot pt2 --- thread was approx 11.5 feet long + + traj_name.append('/full_interrupted_suture/pt1') #stitch 1, pierce both flaps and pull through + traj_name.append('/full_interrupted_suture/pt2') #tie right 2 loop knot + traj_name.append('/full_interrupted_suture/pt3') #tie left 1 loop knot + traj_name.append('/full_interrupted_suture/pt4') #tie right 1 loop knot + traj_name.append('/full_interrupted_suture/pt5') #tie left 1 loop knot + traj_name.append('/full_interrupted_suture/pt6') #cut tails off + traj_name.append('/full_interrupted_suture/pt7') #stitch 2, pierce both flaps and pull through + traj_name.append('/full_interrupted_suture/pt8') #tie right 2 loop knot + traj_name.append('/full_interrupted_suture/pt9') #tie left 1 loop knot --- weird smoothing at the end + traj_name.append('/full_interrupted_suture/pt10') #tie right 1 loop knot + traj_name.append('/full_interrupted_suture/pt11') #tie left 1 loop knot + traj_name.append('/full_interrupted_suture/pt12') #cut tails off + + ## Load Trajectory + for i in range(1): + i=11 + larm_traj = np.load(traj_file_path + traj_name[i] + '_tj_larm.npy') + rarm_traj = np.load(traj_file_path + traj_name[i] + '_tj_rarm.npy') + lgrip_traj = np.load(traj_file_path + traj_name[i] + '_tj_lgrip.npy') + rgrip_traj = np.load(traj_file_path + traj_name[i] + '_tj_rgrip.npy') + + print 'loaded', traj_name[i], 'trajectory' + + length = len(larm_traj) + + full_traj = np.zeros(length, + dtype=[('r_arm', '7float64'), ('l_arm', '7float64'), ('r_gripper', 'float64'), ('l_gripper', 'float64')]) + + full_traj['r_arm'] = rarm_traj + full_traj['l_arm'] = larm_traj + full_traj['r_gripper'] = rgrip_traj + full_traj['l_gripper'] = lgrip_traj + + raw_input("Confirm trajectory type, press ENTER to start playback ...") + + tj.follow_body_traj(p, full_traj, r_arm = True, l_arm = True, r_gripper = True, l_gripper = True) + diff --git a/brett2/mtf_trajectories.py b/brett2/mtf_trajectories.py new file mode 100644 index 0000000..da04a1e --- /dev/null +++ b/brett2/mtf_trajectories.py @@ -0,0 +1,140 @@ +#import roslib; +#roslib.load_manifest('rospy') +import rospy +import numpy as np +from brett2 import PR2 +import jds_utils.conversions as conv +import jds_utils.math_utils as mu +from kinematics import retiming +import scipy.interpolate as si + +BodyState = np.dtype([ + ("r_arm", float, 7), + ("l_arm", float, 7), + ("r_gripper", float, 1), + ("l_gripper", float, 1), + ("head", float, 2), + ("base", float, 3) +]) + + +def make_joint_traj(xyzs, quats, manip, ref_frame, targ_frame, filter_options = 0): + "do ik and then fill in the points where ik failed" + + n = len(xyzs) + assert len(quats) == n + + robot = manip.GetRobot() + joint_inds = manip.GetArmJoints() + robot.SetActiveDOFs(joint_inds) + orig_joint = robot.GetActiveDOFValues() + + joints = [] + inds = [] + + for i in xrange(0,n): + mat4 = conv.trans_rot_to_hmat(xyzs[i], quats[i]) + joint = PR2.cart_to_joint(manip, mat4, ref_frame, targ_frame, filter_options) + if joint is not None: + joints.append(joint) + inds.append(i) + robot.SetActiveDOFValues(joint) + + + robot.SetActiveDOFValues(orig_joint) + + + rospy.loginfo("found ik soln for %i of %i points",len(inds), n) + if len(inds) > 2: + joints2 = mu.interp2d(np.arange(n), inds, joints) + return joints2, inds + else: + return np.zeros((n, len(joints))), [] + + +def flatten_compound_dtype(compound_array): + arrays = [] + for desc in compound_array.dtype.descr: + field = desc[0] + arr = compound_array[field] + if arr.ndim == 1: + float_arr = arr[:,None].astype('float') + elif arr.ndim == 2: + float_arr = arr.astype('float') + else: + raise Exception("subarray with field %s must be 1d or 2d"%field) + arrays.append(float_arr) + + return np.concatenate(arrays, axis=1) + + +def follow_body_traj(pr2, traj, times=None, r_arm = False, l_arm = False, r_gripper = False, l_gripper = False, head = False, base = False): + + assert isinstance(pr2, PR2.PR2) + pr2.update_rave() + + # originally 0.2 + vel_mult = 0.4 + + s = 0.3 + vel_l = [] + vel_r = [] + + vel_limits = np.r_[pr2.rarm.vel_limits*vel_mult, pr2.larm.vel_limits*vel_mult, pr2.rgrip.vel_limits, pr2.lgrip.vel_limits] + acc_limits = np.r_[pr2.rarm.acc_limits, pr2.larm.acc_limits, np.inf, np.inf] + + times, inds = retiming.retime(flatten_compound_dtype(traj), vel_limits, acc_limits) + + traj = traj[inds] + smooth_traj = traj + + n = len(traj['r_arm']) + + (r_tck, _) = si.splprep(traj['r_arm'].T, s=s, u=times, k=3) + smooth_traj['r_arm'] = np.r_[si.splev(times, r_tck, der=0)].T + vel_r = np.r_[si.splev(times, r_tck, der=1)].T + + (l_tck, _) = si.splprep(traj['l_arm'].T, s=s, u=times, k=3) + smooth_traj['l_arm'] = np.r_[si.splev(times, l_tck, der=0)].T + vel_l = np.r_[si.splev(times, l_tck, der=1)].T + + # make sure gripper closes all the way + for i in range(n): + if smooth_traj['r_gripper'][i] < 0.005: + smooth_traj['r_gripper'][i] = -0.01 + if smooth_traj['l_gripper'][i] < 0.005: + smooth_traj['l_gripper'][i] = -0.01 + + if r_arm: + pr2.rarm.goto_joint_positions(smooth_traj['r_arm'][0]) + if l_arm: + pr2.larm.goto_joint_positions(smooth_traj['l_arm'][0]) + if r_gripper: + pr2.rgrip.set_angle(smooth_traj['r_gripper'][0]) + if l_gripper: + pr2.lgrip.set_angle(smooth_traj['l_gripper'][0]) + if head or base: + raise NotImplementedError + + pr2.join_all() + + rospy.sleep(5.0) + + if r_gripper: + pr2.rgrip.follow_timed_trajectory(times, smooth_traj['r_gripper']) + if l_gripper: + pr2.lgrip.follow_timed_trajectory(times, smooth_traj['l_gripper']) + + rospy.sleep(0.5) + + if r_arm: + pr2.rarm.follow_timed_joint_trajectory(smooth_traj['r_arm'], vel_r, times) + if l_arm: + pr2.larm.follow_timed_joint_trajectory(smooth_traj['l_arm'], vel_l, times) + if head: + pr2.head.follow_timed_trajectory(times, traj['head']) + if base: + pr2.base.follow_timed_trajectory(times, traj['base'], frame_id = '/map') + + pr2.join_all() + diff --git a/joint_states_listener/CMakeLists.txt b/joint_states_listener/CMakeLists.txt new file mode 100644 index 0000000..853165b --- /dev/null +++ b/joint_states_listener/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/joint_states_listener/Makefile b/joint_states_listener/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/joint_states_listener/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/joint_states_listener/mainpage.dox b/joint_states_listener/mainpage.dox new file mode 100644 index 0000000..7198267 --- /dev/null +++ b/joint_states_listener/mainpage.dox @@ -0,0 +1,14 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b joint_states_listener + + + +--> + + +*/ diff --git a/joint_states_listener/manifest.xml b/joint_states_listener/manifest.xml new file mode 100644 index 0000000..d4b42f1 --- /dev/null +++ b/joint_states_listener/manifest.xml @@ -0,0 +1,14 @@ + + + + joint_states_listener + + + Mallory + BSD + + http://ros.org/wiki/joint_states_listener + + + + diff --git a/joint_states_listener/nodes/joint_states_listener.py b/joint_states_listener/nodes/joint_states_listener.py new file mode 100755 index 0000000..265330d --- /dev/null +++ b/joint_states_listener/nodes/joint_states_listener.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python +#spins off a thread to listen for joint_states messages +#and provides the same information (or subsets of) as a service + +import roslib +roslib.load_manifest('joint_states_listener') +import rospy +from joint_states_listener.srv import * +from sensor_msgs.msg import JointState +import threading + + +#holds the latest states obtained from joint_states messages +class LatestJointStates: + + def __init__(self): + rospy.init_node('joint_states_listener') + self.lock = threading.Lock() + self.name = [] + self.position = [] + self.velocity = [] + self.effort = [] + self.thread = threading.Thread(target=self.joint_states_listener) + self.thread.start() + + s = rospy.Service('return_joint_states', ReturnJointStates, self.return_joint_states) + + + #thread function: listen for joint_states messages + def joint_states_listener(self): + rospy.Subscriber('joint_states', JointState, self.joint_states_callback) + rospy.spin() + + + #callback function: when a joint_states message arrives, save the values + def joint_states_callback(self, msg): + self.lock.acquire() + self.name = msg.name + self.position = msg.position + self.velocity = msg.velocity + self.effort = msg.effort + self.lock.release() + + + #returns (found, position, velocity, effort) for the joint joint_name + #(found is 1 if found, 0 otherwise) + def return_joint_state(self, joint_name): + + #no messages yet + if self.name == []: + rospy.logerr("No robot_state messages received!\n") + return (0, 0., 0., 0.) + + #return info for this joint + self.lock.acquire() + if joint_name in self.name: + index = self.name.index(joint_name) + position = self.position[index] + velocity = self.velocity[index] + effort = self.effort[index] + + #unless it's not found + else: + rospy.logerr("Joint %s not found!", (joint_name,)) + self.lock.release() + return (0, 0., 0., 0.) + self.lock.release() + return (1, position, velocity, effort) + + + #server callback: returns arrays of position, velocity, and effort + #for a list of joints specified by name + def return_joint_states(self, req): + joints_found = [] + positions = [] + velocities = [] + efforts = [] + for joint_name in req.name: + (found, position, velocity, effort) = self.return_joint_state(joint_name) + joints_found.append(found) + positions.append(position) + velocities.append(velocity) + efforts.append(effort) + return ReturnJointStatesResponse(joints_found, positions, velocities, efforts) + + +#run the server +if __name__ == "__main__": + + latestjointstates = LatestJointStates() + + print "joints_states_listener server started, waiting for queries" + rospy.spin() diff --git a/joint_states_listener/nodes/joint_states_trajectory_recorder.py b/joint_states_listener/nodes/joint_states_trajectory_recorder.py new file mode 100755 index 0000000..6a8fc6d --- /dev/null +++ b/joint_states_listener/nodes/joint_states_trajectory_recorder.py @@ -0,0 +1,109 @@ +#!/usr/bin/env python +#test client for joint_states_listener + +import roslib +roslib.load_manifest('joint_states_listener') +import rospy +import rosbag +from joint_states_listener.srv import ReturnJointStates +import sys +import numpy as np + +def call_return_joint_states(joint_names): + rospy.wait_for_service("return_joint_states") + try: + s = rospy.ServiceProxy("return_joint_states", ReturnJointStates) + resp = s(joint_names) + except rospy.ServiceException, e: + print "error when calling return_joint_states: %s"%e + sys.exit(1) + for (ind, joint_name) in enumerate(joint_names): + if(not resp.found[ind]): + print "joint %s not found!"%joint_name + return (resp.position, resp.velocity, resp.effort) + + +## Pretty-print list to string +def pplist(list): + return ' '.join(['%2.3f'%x for x in list]) + + +## Record arm and gripper trajectories +if __name__ == "__main__": + rospy.init_node('joint_states_trajectory_recorder') + + traj_file_path = '/home/mallory/fuerte_workspace/sandbox/suturing/pr2_suturing/joint_states_listener/trajectories' + + record_time = rospy.Duration.from_sec(300.0) #pt 1, 2 + #record_time = rospy.Duration.from_sec(240.0) #pt 3, 4, 5 + + traj_larm = [] + traj_rarm = [] + traj_lgrip = [] + traj_rgrip = [] + + joint_names = ["l_shoulder_pan_joint", + "l_shoulder_lift_joint", + "l_upper_arm_roll_joint", + "l_elbow_flex_joint", + "l_forearm_roll_joint", + "l_wrist_flex_joint", + "l_wrist_roll_joint", + "r_shoulder_pan_joint", + "r_shoulder_lift_joint", + "r_upper_arm_roll_joint", + "r_elbow_flex_joint", + "r_forearm_roll_joint", + "r_wrist_flex_joint", + "r_wrist_roll_joint", + "l_gripper_joint", + "r_gripper_joint"] + + while(1): + if rospy.Time.now().secs > 0: + break + else: + continue + + print 'record_time:', record_time.secs + start_time = rospy.Time.now().secs + + while((rospy.Time.now().secs - start_time) < record_time.secs): + + if (rospy.Time.now().secs - start_time) % 5 == 0: + print 'time left:', record_time.secs - (rospy.Time.now().secs - start_time) + + (position, velocity, effort) = call_return_joint_states(joint_names) + + #print "position:", pplist(position) + #print "velocity:", pplist(velocity) + #print "effort: ", pplist(effort) + + traj_larm.append(position[0:7]) + traj_rarm.append(position[7:14]) + traj_lgrip.append(position[14]) + traj_rgrip.append(position[15]) + + print 'end_time:', rospy.Time.now().secs + print 'finished recording' + + ## Save suture trajectories to file + np.save(traj_file_path + '/full_running_suture/pt1_tj_larm.npy', np.array(traj_larm)) + np.save(traj_file_path + '/full_running_suture/pt1_tj_rarm.npy', np.array(traj_rarm)) + np.save(traj_file_path + '/full_running_suture/pt1_tj_lgrip.npy', np.array(traj_lgrip)) + np.save(traj_file_path + '/full_running_suture/pt1_tj_rgrip.npy', np.array(traj_rgrip)) + +## running suture: +## height: 3rd bolt from the bottom on the side of the bot is level with bottom of foam +## pt1: pierce both flaps, pull twice with right hand, pass needle to right hand, pull with left hand until through, +## put needle in stand, end in 'side' +## pt2: left 2 loop knot (needle not perfectly in stand at end) +## pt3: right 1 loop knot +## pt4: left 1 loop knot +## pt5: right 1 loop knot +## pt6: needle through both flaps, pull twice with right hand, pass needle to right hand, pull twice with left hand, +## put needle in stand, end in 'side' +## ... + + + diff --git a/joint_states_listener/nodes/joint_states_trajectory_recorder2.py b/joint_states_listener/nodes/joint_states_trajectory_recorder2.py new file mode 100755 index 0000000..9ad4b5a --- /dev/null +++ b/joint_states_listener/nodes/joint_states_trajectory_recorder2.py @@ -0,0 +1,111 @@ +#!/usr/bin/env python +#test client for joint_states_listener + +import roslib +roslib.load_manifest('joint_states_listener') +import rospy +import rosbag +from joint_states_listener.srv import ReturnJointStates +import sys +import numpy as np +import threading as th + + +def call_return_joint_states(joint_names): + rospy.wait_for_service("return_joint_states") + try: + s = rospy.ServiceProxy("return_joint_states", ReturnJointStates) + resp = s(joint_names) + except rospy.ServiceException, e: + print "error when calling return_joint_states: %s"%e + sys.exit(1) + for (ind, joint_name) in enumerate(joint_names): + if(not resp.found[ind]): + print "joint %s not found!"%joint_name + return (resp.position, resp.velocity, resp.effort) + + +## Pretty-print list to string +def pplist(list): + return ' '.join(['%2.3f'%x for x in list]) + + +## Class to signal when to stop recording +class AskDone(th.Thread): + + def __init__(self): + th.Thread.__init__(self) + self.done = False + + def run(self): + y = raw_input('Press any key to stop recording') + self.done = True + + +## Record arm and gripper trajectories +if __name__ == "__main__": + rospy.init_node('joint_states_trajectory_recorder') + + traj_file_path = '/home/mallory/fuerte_workspace/sandbox/suturing/pr2_suturing/joint_states_listener/trajectories' + traj_name = '/full_interrupted_suture/pt12' + + traj_larm = [] + traj_rarm = [] + traj_lgrip = [] + traj_rgrip = [] + + joint_names = ["l_shoulder_pan_joint", + "l_shoulder_lift_joint", + "l_upper_arm_roll_joint", + "l_elbow_flex_joint", + "l_forearm_roll_joint", + "l_wrist_flex_joint", + "l_wrist_roll_joint", + "r_shoulder_pan_joint", + "r_shoulder_lift_joint", + "r_upper_arm_roll_joint", + "r_elbow_flex_joint", + "r_forearm_roll_joint", + "r_wrist_flex_joint", + "r_wrist_roll_joint", + "l_gripper_joint", + "r_gripper_joint"] + + while(1): + if rospy.Time.now().secs > 0: + break + else: + continue + + start_time = rospy.Time.now().secs + print 'Start Time:', start_time + + print 'Recording ...' + ask_done = AskDone() + ask_done.start() + + while (not ask_done.done): + + (position, velocity, effort) = call_return_joint_states(joint_names) + + traj_larm.append(position[0:7]) + traj_rarm.append(position[7:14]) + traj_lgrip.append(position[14]) + traj_rgrip.append(position[15]) + + print 'End Time:', rospy.Time.now().secs + print 'Recording Duration:', rospy.Time.now().secs - start_time + + ask_done.join() + + print 'Finished recording' + + ## Save trajectories to file + np.save(traj_file_path + traj_name + '_tj_larm.npy' , np.array(traj_larm)) + np.save(traj_file_path + traj_name + '_tj_rarm.npy' , np.array(traj_rarm)) + np.save(traj_file_path + traj_name + '_tj_lgrip.npy', np.array(traj_lgrip)) + np.save(traj_file_path + traj_name + '_tj_rgrip.npy', np.array(traj_rgrip)) + + print 'Trajectories saved to file' + + diff --git a/joint_states_listener/src/joint_states_listener/__init__.py b/joint_states_listener/src/joint_states_listener/__init__.py new file mode 100644 index 0000000..b23e43d --- /dev/null +++ b/joint_states_listener/src/joint_states_listener/__init__.py @@ -0,0 +1 @@ +#autogenerated by ROS python message generators \ No newline at end of file diff --git a/joint_states_listener/src/joint_states_listener/srv/_ReturnJointStates.py b/joint_states_listener/src/joint_states_listener/srv/_ReturnJointStates.py new file mode 100644 index 0000000..51325ff --- /dev/null +++ b/joint_states_listener/src/joint_states_listener/srv/_ReturnJointStates.py @@ -0,0 +1,330 @@ +"""autogenerated by genpy from joint_states_listener/ReturnJointStatesRequest.msg. Do not edit.""" +import sys +python3 = True if sys.hexversion > 0x03000000 else False +import genpy +import struct + + +class ReturnJointStatesRequest(genpy.Message): + _md5sum = "3f2d21c30868b92dc41a0431bacd47b2" + _type = "joint_states_listener/ReturnJointStatesRequest" + _has_header = False #flag to mark the presence of a Header object + _full_text = """string[] name + +""" + __slots__ = ['name'] + _slot_types = ['string[]'] + + def __init__(self, *args, **kwds): + """ + Constructor. Any message fields that are implicitly/explicitly + set to None will be assigned a default value. The recommend + use is keyword arguments as this is more robust to future message + changes. You cannot mix in-order arguments and keyword arguments. + + The available fields are: + name + + :param args: complete set of field values, in .msg order + :param kwds: use keyword arguments corresponding to message field names + to set specific fields. + """ + if args or kwds: + super(ReturnJointStatesRequest, self).__init__(*args, **kwds) + #message fields cannot be None, assign default values for those that are + if self.name is None: + self.name = [] + else: + self.name = [] + + def _get_types(self): + """ + internal API method + """ + return self._slot_types + + def serialize(self, buff): + """ + serialize message into buffer + :param buff: buffer, ``StringIO`` + """ + try: + length = len(self.name) + buff.write(_struct_I.pack(length)) + for val1 in self.name: + length = len(val1) + if python3 or type(val1) == unicode: + val1 = val1.encode('utf-8') + length = len(val1) + buff.write(struct.pack(' 0x03000000 else False +import genpy +import struct + + +class ReturnJointStatesResponse(genpy.Message): + _md5sum = "3a36649f5b1439b638a41d18af93e9a4" + _type = "joint_states_listener/ReturnJointStatesResponse" + _has_header = False #flag to mark the presence of a Header object + _full_text = """uint32[] found +float64[] position +float64[] velocity +float64[] effort + + +""" + __slots__ = ['found','position','velocity','effort'] + _slot_types = ['uint32[]','float64[]','float64[]','float64[]'] + + def __init__(self, *args, **kwds): + """ + Constructor. Any message fields that are implicitly/explicitly + set to None will be assigned a default value. The recommend + use is keyword arguments as this is more robust to future message + changes. You cannot mix in-order arguments and keyword arguments. + + The available fields are: + found,position,velocity,effort + + :param args: complete set of field values, in .msg order + :param kwds: use keyword arguments corresponding to message field names + to set specific fields. + """ + if args or kwds: + super(ReturnJointStatesResponse, self).__init__(*args, **kwds) + #message fields cannot be None, assign default values for those that are + if self.found is None: + self.found = [] + if self.position is None: + self.position = [] + if self.velocity is None: + self.velocity = [] + if self.effort is None: + self.effort = [] + else: + self.found = [] + self.position = [] + self.velocity = [] + self.effort = [] + + def _get_types(self): + """ + internal API method + """ + return self._slot_types + + def serialize(self, buff): + """ + serialize message into buffer + :param buff: buffer, ``StringIO`` + """ + try: + length = len(self.found) + buff.write(_struct_I.pack(length)) + pattern = '<%sI'%length + buff.write(struct.pack(pattern, *self.found)) + length = len(self.position) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(struct.pack(pattern, *self.position)) + length = len(self.velocity) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(struct.pack(pattern, *self.velocity)) + length = len(self.effort) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(struct.pack(pattern, *self.effort)) + except struct.error as se: self._check_types(se) + except TypeError as te: self._check_types(te) + + def deserialize(self, str): + """ + unpack serialized message in str into this message instance + :param str: byte array of serialized message, ``str`` + """ + try: + end = 0 + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sI'%length + start = end + end += struct.calcsize(pattern) + self.found = struct.unpack(pattern, str[start:end]) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.position = struct.unpack(pattern, str[start:end]) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.velocity = struct.unpack(pattern, str[start:end]) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.effort = struct.unpack(pattern, str[start:end]) + return self + except struct.error as e: + raise genpy.DeserializationError(e) #most likely buffer underfill + + + def serialize_numpy(self, buff, numpy): + """ + serialize message with numpy array types into buffer + :param buff: buffer, ``StringIO`` + :param numpy: numpy python module + """ + try: + length = len(self.found) + buff.write(_struct_I.pack(length)) + pattern = '<%sI'%length + buff.write(self.found.tostring()) + length = len(self.position) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(self.position.tostring()) + length = len(self.velocity) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(self.velocity.tostring()) + length = len(self.effort) + buff.write(_struct_I.pack(length)) + pattern = '<%sd'%length + buff.write(self.effort.tostring()) + except struct.error as se: self._check_types(se) + except TypeError as te: self._check_types(te) + + def deserialize_numpy(self, str, numpy): + """ + unpack serialized message in str into this message instance using numpy for array types + :param str: byte array of serialized message, ``str`` + :param numpy: numpy python module + """ + try: + end = 0 + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sI'%length + start = end + end += struct.calcsize(pattern) + self.found = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) + start = end + end += 4 + (length,) = _struct_I.unpack(str[start:end]) + pattern = '<%sd'%length + start = end + end += struct.calcsize(pattern) + self.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) + return self + except struct.error as e: + raise genpy.DeserializationError(e) #most likely buffer underfill + +_struct_I = genpy.struct_I +class ReturnJointStates(object): + _type = 'joint_states_listener/ReturnJointStates' + _md5sum = 'ce9bd2b56c904b190a782a08482fb4e9' + _request_class = ReturnJointStatesRequest + _response_class = ReturnJointStatesResponse diff --git a/joint_states_listener/src/joint_states_listener/srv/__init__.py b/joint_states_listener/src/joint_states_listener/srv/__init__.py new file mode 100644 index 0000000..93a9d72 --- /dev/null +++ b/joint_states_listener/src/joint_states_listener/srv/__init__.py @@ -0,0 +1 @@ +from ._ReturnJointStates import * diff --git a/joint_states_listener/srv/ReturnJointStates.srv b/joint_states_listener/srv/ReturnJointStates.srv new file mode 100644 index 0000000..b827353 --- /dev/null +++ b/joint_states_listener/srv/ReturnJointStates.srv @@ -0,0 +1,6 @@ +string[] name +--- +uint32[] found +float64[] position +float64[] velocity +float64[] effort diff --git a/joint_states_listener/srv_gen/cpp/include/joint_states_listener/ReturnJointStates.h b/joint_states_listener/srv_gen/cpp/include/joint_states_listener/ReturnJointStates.h new file mode 100644 index 0000000..1d32d3d --- /dev/null +++ b/joint_states_listener/srv_gen/cpp/include/joint_states_listener/ReturnJointStates.h @@ -0,0 +1,304 @@ +/* Auto-generated by genmsg_cpp for file /home/mallory/fuerte_workspace/sandbox/suturing/python/joint_states_listener/srv/ReturnJointStates.srv */ +#ifndef JOINT_STATES_LISTENER_SERVICE_RETURNJOINTSTATES_H +#define JOINT_STATES_LISTENER_SERVICE_RETURNJOINTSTATES_H +#include +#include +#include +#include +#include "ros/serialization.h" +#include "ros/builtin_message_traits.h" +#include "ros/message_operations.h" +#include "ros/time.h" + +#include "ros/macros.h" + +#include "ros/assert.h" + +#include "ros/service_traits.h" + + + + +namespace joint_states_listener +{ +template +struct ReturnJointStatesRequest_ { + typedef ReturnJointStatesRequest_ Type; + + ReturnJointStatesRequest_() + : name() + { + } + + ReturnJointStatesRequest_(const ContainerAllocator& _alloc) + : name(_alloc) + { + } + + typedef std::vector, typename ContainerAllocator::template rebind::other > , typename ContainerAllocator::template rebind, typename ContainerAllocator::template rebind::other > >::other > _name_type; + std::vector, typename ContainerAllocator::template rebind::other > , typename ContainerAllocator::template rebind, typename ContainerAllocator::template rebind::other > >::other > name; + + + typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesRequest_ > Ptr; + typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesRequest_ const> ConstPtr; + boost::shared_ptr > __connection_header; +}; // struct ReturnJointStatesRequest +typedef ::joint_states_listener::ReturnJointStatesRequest_ > ReturnJointStatesRequest; + +typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesRequest> ReturnJointStatesRequestPtr; +typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesRequest const> ReturnJointStatesRequestConstPtr; + + +template +struct ReturnJointStatesResponse_ { + typedef ReturnJointStatesResponse_ Type; + + ReturnJointStatesResponse_() + : found() + , position() + , velocity() + , effort() + { + } + + ReturnJointStatesResponse_(const ContainerAllocator& _alloc) + : found(_alloc) + , position(_alloc) + , velocity(_alloc) + , effort(_alloc) + { + } + + typedef std::vector::other > _found_type; + std::vector::other > found; + + typedef std::vector::other > _position_type; + std::vector::other > position; + + typedef std::vector::other > _velocity_type; + std::vector::other > velocity; + + typedef std::vector::other > _effort_type; + std::vector::other > effort; + + + typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesResponse_ > Ptr; + typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesResponse_ const> ConstPtr; + boost::shared_ptr > __connection_header; +}; // struct ReturnJointStatesResponse +typedef ::joint_states_listener::ReturnJointStatesResponse_ > ReturnJointStatesResponse; + +typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesResponse> ReturnJointStatesResponsePtr; +typedef boost::shared_ptr< ::joint_states_listener::ReturnJointStatesResponse const> ReturnJointStatesResponseConstPtr; + +struct ReturnJointStates +{ + +typedef ReturnJointStatesRequest Request; +typedef ReturnJointStatesResponse Response; +Request request; +Response response; + +typedef Request RequestType; +typedef Response ResponseType; +}; // struct ReturnJointStates +} // namespace joint_states_listener + +namespace ros +{ +namespace message_traits +{ +template struct IsMessage< ::joint_states_listener::ReturnJointStatesRequest_ > : public TrueType {}; +template struct IsMessage< ::joint_states_listener::ReturnJointStatesRequest_ const> : public TrueType {}; +template +struct MD5Sum< ::joint_states_listener::ReturnJointStatesRequest_ > { + static const char* value() + { + return "3f2d21c30868b92dc41a0431bacd47b2"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesRequest_ &) { return value(); } + static const uint64_t static_value1 = 0x3f2d21c30868b92dULL; + static const uint64_t static_value2 = 0xc41a0431bacd47b2ULL; +}; + +template +struct DataType< ::joint_states_listener::ReturnJointStatesRequest_ > { + static const char* value() + { + return "joint_states_listener/ReturnJointStatesRequest"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesRequest_ &) { return value(); } +}; + +template +struct Definition< ::joint_states_listener::ReturnJointStatesRequest_ > { + static const char* value() + { + return "string[] name\n\ +\n\ +"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesRequest_ &) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + + +namespace ros +{ +namespace message_traits +{ +template struct IsMessage< ::joint_states_listener::ReturnJointStatesResponse_ > : public TrueType {}; +template struct IsMessage< ::joint_states_listener::ReturnJointStatesResponse_ const> : public TrueType {}; +template +struct MD5Sum< ::joint_states_listener::ReturnJointStatesResponse_ > { + static const char* value() + { + return "3a36649f5b1439b638a41d18af93e9a4"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesResponse_ &) { return value(); } + static const uint64_t static_value1 = 0x3a36649f5b1439b6ULL; + static const uint64_t static_value2 = 0x38a41d18af93e9a4ULL; +}; + +template +struct DataType< ::joint_states_listener::ReturnJointStatesResponse_ > { + static const char* value() + { + return "joint_states_listener/ReturnJointStatesResponse"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesResponse_ &) { return value(); } +}; + +template +struct Definition< ::joint_states_listener::ReturnJointStatesResponse_ > { + static const char* value() + { + return "uint32[] found\n\ +float64[] position\n\ +float64[] velocity\n\ +float64[] effort\n\ +\n\ +\n\ +"; + } + + static const char* value(const ::joint_states_listener::ReturnJointStatesResponse_ &) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + +template struct Serializer< ::joint_states_listener::ReturnJointStatesRequest_ > +{ + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.name); + } + + ROS_DECLARE_ALLINONE_SERIALIZER; +}; // struct ReturnJointStatesRequest_ +} // namespace serialization +} // namespace ros + + +namespace ros +{ +namespace serialization +{ + +template struct Serializer< ::joint_states_listener::ReturnJointStatesResponse_ > +{ + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.found); + stream.next(m.position); + stream.next(m.velocity); + stream.next(m.effort); + } + + ROS_DECLARE_ALLINONE_SERIALIZER; +}; // struct ReturnJointStatesResponse_ +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace service_traits +{ +template<> +struct MD5Sum { + static const char* value() + { + return "ce9bd2b56c904b190a782a08482fb4e9"; + } + + static const char* value(const joint_states_listener::ReturnJointStates&) { return value(); } +}; + +template<> +struct DataType { + static const char* value() + { + return "joint_states_listener/ReturnJointStates"; + } + + static const char* value(const joint_states_listener::ReturnJointStates&) { return value(); } +}; + +template +struct MD5Sum > { + static const char* value() + { + return "ce9bd2b56c904b190a782a08482fb4e9"; + } + + static const char* value(const joint_states_listener::ReturnJointStatesRequest_ &) { return value(); } +}; + +template +struct DataType > { + static const char* value() + { + return "joint_states_listener/ReturnJointStates"; + } + + static const char* value(const joint_states_listener::ReturnJointStatesRequest_ &) { return value(); } +}; + +template +struct MD5Sum > { + static const char* value() + { + return "ce9bd2b56c904b190a782a08482fb4e9"; + } + + static const char* value(const joint_states_listener::ReturnJointStatesResponse_ &) { return value(); } +}; + +template +struct DataType > { + static const char* value() + { + return "joint_states_listener/ReturnJointStates"; + } + + static const char* value(const joint_states_listener::ReturnJointStatesResponse_ &) { return value(); } +}; + +} // namespace service_traits +} // namespace ros + +#endif // JOINT_STATES_LISTENER_SERVICE_RETURNJOINTSTATES_H + diff --git a/joint_states_listener/srv_gen/generated b/joint_states_listener/srv_gen/generated new file mode 100644 index 0000000..396a0ba --- /dev/null +++ b/joint_states_listener/srv_gen/generated @@ -0,0 +1 @@ +yes \ No newline at end of file diff --git a/joint_states_listener/srv_gen/lisp/ReturnJointStates.lisp b/joint_states_listener/srv_gen/lisp/ReturnJointStates.lisp new file mode 100644 index 0000000..c80318f --- /dev/null +++ b/joint_states_listener/srv_gen/lisp/ReturnJointStates.lisp @@ -0,0 +1,310 @@ +; Auto-generated. Do not edit! + + +(cl:in-package joint_states_listener-srv) + + +;//! \htmlinclude ReturnJointStates-request.msg.html + +(cl:defclass (roslisp-msg-protocol:ros-message) + ((name + :reader name + :initarg :name + :type (cl:vector cl:string) + :initform (cl:make-array 0 :element-type 'cl:string :initial-element ""))) +) + +(cl:defclass ReturnJointStates-request () + ()) + +(cl:defmethod cl:initialize-instance :after ((m ) cl:&rest args) + (cl:declare (cl:ignorable args)) + (cl:unless (cl:typep m 'ReturnJointStates-request) + (roslisp-msg-protocol:msg-deprecation-warning "using old message class name joint_states_listener-srv: is deprecated: use joint_states_listener-srv:ReturnJointStates-request instead."))) + +(cl:ensure-generic-function 'name-val :lambda-list '(m)) +(cl:defmethod name-val ((m )) + (roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader joint_states_listener-srv:name-val is deprecated. Use joint_states_listener-srv:name instead.") + (name m)) +(cl:defmethod roslisp-msg-protocol:serialize ((msg ) ostream) + "Serializes a message object of type '" + (cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'name)))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream)) + (cl:map cl:nil #'(cl:lambda (ele) (cl:let ((__ros_str_len (cl:length ele))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_str_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_str_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_str_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_str_len) ostream)) + (cl:map cl:nil #'(cl:lambda (c) (cl:write-byte (cl:char-code c) ostream)) ele)) + (cl:slot-value msg 'name)) +) +(cl:defmethod roslisp-msg-protocol:deserialize ((msg ) istream) + "Deserializes a message object of type '" + (cl:let ((__ros_arr_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:slot-value msg 'name) (cl:make-array __ros_arr_len)) + (cl:let ((vals (cl:slot-value msg 'name))) + (cl:dotimes (i __ros_arr_len) + (cl:let ((__ros_str_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_str_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_str_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_str_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_str_len) (cl:read-byte istream)) + (cl:setf (cl:aref vals i) (cl:make-string __ros_str_len)) + (cl:dotimes (__ros_str_idx __ros_str_len msg) + (cl:setf (cl:char (cl:aref vals i) __ros_str_idx) (cl:code-char (cl:read-byte istream)))))))) + msg +) +(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql '))) + "Returns string type for a service object of type '" + "joint_states_listener/ReturnJointStatesRequest") +(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql 'ReturnJointStates-request))) + "Returns string type for a service object of type 'ReturnJointStates-request" + "joint_states_listener/ReturnJointStatesRequest") +(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql '))) + "Returns md5sum for a message object of type '" + "ce9bd2b56c904b190a782a08482fb4e9") +(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql 'ReturnJointStates-request))) + "Returns md5sum for a message object of type 'ReturnJointStates-request" + "ce9bd2b56c904b190a782a08482fb4e9") +(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql '))) + "Returns full string definition for message of type '" + (cl:format cl:nil "string[] name~%~%~%")) +(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql 'ReturnJointStates-request))) + "Returns full string definition for message of type 'ReturnJointStates-request" + (cl:format cl:nil "string[] name~%~%~%")) +(cl:defmethod roslisp-msg-protocol:serialization-length ((msg )) + (cl:+ 0 + 4 (cl:reduce #'cl:+ (cl:slot-value msg 'name) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ 4 (cl:length ele)))) +)) +(cl:defmethod roslisp-msg-protocol:ros-message-to-list ((msg )) + "Converts a ROS message object to a list" + (cl:list 'ReturnJointStates-request + (cl:cons ':name (name msg)) +)) +;//! \htmlinclude ReturnJointStates-response.msg.html + +(cl:defclass (roslisp-msg-protocol:ros-message) + ((found + :reader found + :initarg :found + :type (cl:vector cl:integer) + :initform (cl:make-array 0 :element-type 'cl:integer :initial-element 0)) + (position + :reader position + :initarg :position + :type (cl:vector cl:float) + :initform (cl:make-array 0 :element-type 'cl:float :initial-element 0.0)) + (velocity + :reader velocity + :initarg :velocity + :type (cl:vector cl:float) + :initform (cl:make-array 0 :element-type 'cl:float :initial-element 0.0)) + (effort + :reader effort + :initarg :effort + :type (cl:vector cl:float) + :initform (cl:make-array 0 :element-type 'cl:float :initial-element 0.0))) +) + +(cl:defclass ReturnJointStates-response () + ()) + +(cl:defmethod cl:initialize-instance :after ((m ) cl:&rest args) + (cl:declare (cl:ignorable args)) + (cl:unless (cl:typep m 'ReturnJointStates-response) + (roslisp-msg-protocol:msg-deprecation-warning "using old message class name joint_states_listener-srv: is deprecated: use joint_states_listener-srv:ReturnJointStates-response instead."))) + +(cl:ensure-generic-function 'found-val :lambda-list '(m)) +(cl:defmethod found-val ((m )) + (roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader joint_states_listener-srv:found-val is deprecated. Use joint_states_listener-srv:found instead.") + (found m)) + +(cl:ensure-generic-function 'position-val :lambda-list '(m)) +(cl:defmethod position-val ((m )) + (roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader joint_states_listener-srv:position-val is deprecated. Use joint_states_listener-srv:position instead.") + (position m)) + +(cl:ensure-generic-function 'velocity-val :lambda-list '(m)) +(cl:defmethod velocity-val ((m )) + (roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader joint_states_listener-srv:velocity-val is deprecated. Use joint_states_listener-srv:velocity instead.") + (velocity m)) + +(cl:ensure-generic-function 'effort-val :lambda-list '(m)) +(cl:defmethod effort-val ((m )) + (roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader joint_states_listener-srv:effort-val is deprecated. Use joint_states_listener-srv:effort instead.") + (effort m)) +(cl:defmethod roslisp-msg-protocol:serialize ((msg ) ostream) + "Serializes a message object of type '" + (cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'found)))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream)) + (cl:map cl:nil #'(cl:lambda (ele) (cl:write-byte (cl:ldb (cl:byte 8 0) ele) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) ele) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) ele) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) ele) ostream)) + (cl:slot-value msg 'found)) + (cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'position)))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream)) + (cl:map cl:nil #'(cl:lambda (ele) (cl:let ((bits (roslisp-utils:encode-double-float-bits ele))) + (cl:write-byte (cl:ldb (cl:byte 8 0) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 32) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 40) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 48) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 56) bits) ostream))) + (cl:slot-value msg 'position)) + (cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'velocity)))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream)) + (cl:map cl:nil #'(cl:lambda (ele) (cl:let ((bits (roslisp-utils:encode-double-float-bits ele))) + (cl:write-byte (cl:ldb (cl:byte 8 0) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 32) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 40) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 48) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 56) bits) ostream))) + (cl:slot-value msg 'velocity)) + (cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'effort)))) + (cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream)) + (cl:map cl:nil #'(cl:lambda (ele) (cl:let ((bits (roslisp-utils:encode-double-float-bits ele))) + (cl:write-byte (cl:ldb (cl:byte 8 0) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 8) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 16) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 24) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 32) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 40) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 48) bits) ostream) + (cl:write-byte (cl:ldb (cl:byte 8 56) bits) ostream))) + (cl:slot-value msg 'effort)) +) +(cl:defmethod roslisp-msg-protocol:deserialize ((msg ) istream) + "Deserializes a message object of type '" + (cl:let ((__ros_arr_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:slot-value msg 'found) (cl:make-array __ros_arr_len)) + (cl:let ((vals (cl:slot-value msg 'found))) + (cl:dotimes (i __ros_arr_len) + (cl:setf (cl:ldb (cl:byte 8 0) (cl:aref vals i)) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) (cl:aref vals i)) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) (cl:aref vals i)) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) (cl:aref vals i)) (cl:read-byte istream))))) + (cl:let ((__ros_arr_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:slot-value msg 'position) (cl:make-array __ros_arr_len)) + (cl:let ((vals (cl:slot-value msg 'position))) + (cl:dotimes (i __ros_arr_len) + (cl:let ((bits 0)) + (cl:setf (cl:ldb (cl:byte 8 0) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 32) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 40) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 48) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 56) bits) (cl:read-byte istream)) + (cl:setf (cl:aref vals i) (roslisp-utils:decode-double-float-bits bits)))))) + (cl:let ((__ros_arr_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:slot-value msg 'velocity) (cl:make-array __ros_arr_len)) + (cl:let ((vals (cl:slot-value msg 'velocity))) + (cl:dotimes (i __ros_arr_len) + (cl:let ((bits 0)) + (cl:setf (cl:ldb (cl:byte 8 0) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 32) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 40) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 48) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 56) bits) (cl:read-byte istream)) + (cl:setf (cl:aref vals i) (roslisp-utils:decode-double-float-bits bits)))))) + (cl:let ((__ros_arr_len 0)) + (cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream)) + (cl:setf (cl:slot-value msg 'effort) (cl:make-array __ros_arr_len)) + (cl:let ((vals (cl:slot-value msg 'effort))) + (cl:dotimes (i __ros_arr_len) + (cl:let ((bits 0)) + (cl:setf (cl:ldb (cl:byte 8 0) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 8) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 16) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 24) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 32) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 40) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 48) bits) (cl:read-byte istream)) + (cl:setf (cl:ldb (cl:byte 8 56) bits) (cl:read-byte istream)) + (cl:setf (cl:aref vals i) (roslisp-utils:decode-double-float-bits bits)))))) + msg +) +(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql '))) + "Returns string type for a service object of type '" + "joint_states_listener/ReturnJointStatesResponse") +(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql 'ReturnJointStates-response))) + "Returns string type for a service object of type 'ReturnJointStates-response" + "joint_states_listener/ReturnJointStatesResponse") +(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql '))) + "Returns md5sum for a message object of type '" + "ce9bd2b56c904b190a782a08482fb4e9") +(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql 'ReturnJointStates-response))) + "Returns md5sum for a message object of type 'ReturnJointStates-response" + "ce9bd2b56c904b190a782a08482fb4e9") +(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql '))) + "Returns full string definition for message of type '" + (cl:format cl:nil "uint32[] found~%float64[] position~%float64[] velocity~%float64[] effort~%~%~%~%")) +(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql 'ReturnJointStates-response))) + "Returns full string definition for message of type 'ReturnJointStates-response" + (cl:format cl:nil "uint32[] found~%float64[] position~%float64[] velocity~%float64[] effort~%~%~%~%")) +(cl:defmethod roslisp-msg-protocol:serialization-length ((msg )) + (cl:+ 0 + 4 (cl:reduce #'cl:+ (cl:slot-value msg 'found) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ 4))) + 4 (cl:reduce #'cl:+ (cl:slot-value msg 'position) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ 8))) + 4 (cl:reduce #'cl:+ (cl:slot-value msg 'velocity) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ 8))) + 4 (cl:reduce #'cl:+ (cl:slot-value msg 'effort) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ 8))) +)) +(cl:defmethod roslisp-msg-protocol:ros-message-to-list ((msg )) + "Converts a ROS message object to a list" + (cl:list 'ReturnJointStates-response + (cl:cons ':found (found msg)) + (cl:cons ':position (position msg)) + (cl:cons ':velocity (velocity msg)) + (cl:cons ':effort (effort msg)) +)) +(cl:defmethod roslisp-msg-protocol:service-request-type ((msg (cl:eql 'ReturnJointStates))) + 'ReturnJointStates-request) +(cl:defmethod roslisp-msg-protocol:service-response-type ((msg (cl:eql 'ReturnJointStates))) + 'ReturnJointStates-response) +(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql 'ReturnJointStates))) + "Returns string type for a service object of type '" + "joint_states_listener/ReturnJointStates") \ No newline at end of file diff --git a/joint_states_listener/srv_gen/lisp/_package.lisp b/joint_states_listener/srv_gen/lisp/_package.lisp new file mode 100644 index 0000000..5d7257b --- /dev/null +++ b/joint_states_listener/srv_gen/lisp/_package.lisp @@ -0,0 +1,10 @@ +(cl:defpackage joint_states_listener-srv + (:use ) + (:export + "RETURNJOINTSTATES" + "" + "RETURNJOINTSTATES-REQUEST" + "" + "RETURNJOINTSTATES-RESPONSE" + )) + diff --git a/joint_states_listener/srv_gen/lisp/_package_ReturnJointStates.lisp b/joint_states_listener/srv_gen/lisp/_package_ReturnJointStates.lisp new file mode 100644 index 0000000..372b076 --- /dev/null +++ b/joint_states_listener/srv_gen/lisp/_package_ReturnJointStates.lisp @@ -0,0 +1,12 @@ +(cl:in-package joint_states_listener-srv) +(cl:export '(NAME-VAL + NAME + FOUND-VAL + FOUND + POSITION-VAL + POSITION + VELOCITY-VAL + VELOCITY + EFFORT-VAL + EFFORT +)) \ No newline at end of file diff --git a/joint_states_listener/srv_gen/lisp/joint_states_listener-srv.asd b/joint_states_listener/srv_gen/lisp/joint_states_listener-srv.asd new file mode 100644 index 0000000..7cb8121 --- /dev/null +++ b/joint_states_listener/srv_gen/lisp/joint_states_listener-srv.asd @@ -0,0 +1,9 @@ + +(cl:in-package :asdf) + +(defsystem "joint_states_listener-srv" + :depends-on (:roslisp-msg-protocol :roslisp-utils ) + :components ((:file "_package") + (:file "ReturnJointStates" :depends-on ("_package_ReturnJointStates")) + (:file "_package_ReturnJointStates" :depends-on ("_package")) + )) \ No newline at end of file diff --git a/launch.py b/launch.py new file mode 100644 index 0000000..2e77dfc --- /dev/null +++ b/launch.py @@ -0,0 +1,6 @@ +import rospy +from ArmPlannerPR2 import PlannerPR2 + +if __name__ == "__main__": + rospy.init_node("Test_Planning") + p = PlannerPR2 () From ffa4dbc7a72071a8df07a9a0ba91119cc10a437e Mon Sep 17 00:00:00 2001 From: John Schulman Date: Wed, 20 Feb 2013 13:11:17 -0800 Subject: [PATCH 02/26] iros dir --- brett2/PR2.py | 30 +- ArmPlannerPR2.py => iros/ArmPlannerPR2.py | 0 .../IKPlannerFunctions.py | 0 .../TrajectoryPlayback.py | 0 iros/follow_pose_traj.py | 297 ++++++++++++++++++ launch.py => iros/launch.py | 0 notes.txt => iros/notes.txt | 0 7 files changed, 312 insertions(+), 15 deletions(-) rename ArmPlannerPR2.py => iros/ArmPlannerPR2.py (100%) rename IKPlannerFunctions.py => iros/IKPlannerFunctions.py (100%) rename TrajectoryPlayback.py => iros/TrajectoryPlayback.py (100%) create mode 100644 iros/follow_pose_traj.py rename launch.py => iros/launch.py (100%) rename notes.txt => iros/notes.txt (100%) diff --git a/brett2/PR2.py b/brett2/PR2.py index 18ebf79..4d22355 100644 --- a/brett2/PR2.py +++ b/brett2/PR2.py @@ -114,21 +114,21 @@ def __init__(self, rave_only=False): self.torso = Torso(self) self.base = Base(self) - # make the joint limits match the PR2 soft limits - low_limits, high_limits = self.robot.GetDOFLimits() - rarm_low_limits = [-2.1353981634, -0.3536, -3.75, -2.1213, None, -2.0, None] - rarm_high_limits = [0.564601836603, 1.2963, 0.65, -0.15, None, -0.1, None] - for rarm_index, low, high in zip(self.robot.GetManipulator("rightarm").GetArmIndices(), rarm_low_limits, rarm_high_limits): - if low is not None and high is not None: - low_limits[rarm_index] = low - high_limits[rarm_index] = high - larm_low_limits = [-0.564601836603, -0.3536, -0.65, -2.1213, None, -2.0, None] - larm_high_limits = [2.1353981634, 1.2963, 3.75, -0.15, None, -0.1, None] - for larm_index, low, high in zip(self.robot.GetManipulator("leftarm").GetArmIndices(), larm_low_limits, larm_high_limits): - if low is not None and high is not None: - low_limits[larm_index] = low - high_limits[larm_index] = high - self.robot.SetDOFLimits(low_limits, high_limits) + ## make the joint limits match the PR2 soft limits + #low_limits, high_limits = self.robot.GetDOFLimits() + #rarm_low_limits = [-2.1353981634, -0.3536, -3.75, -2.1213, None, -2.0, None] + #rarm_high_limits = [0.564601836603, 1.2963, 0.65, -0.15, None, -0.1, None] + #for rarm_index, low, high in zip(self.robot.GetManipulator("rightarm").GetArmIndices(), rarm_low_limits, rarm_high_limits): + #if low is not None and high is not None: + #low_limits[rarm_index] = low + #high_limits[rarm_index] = high + #larm_low_limits = [-0.564601836603, -0.3536, -0.65, -2.1213, None, -2.0, None] + #larm_high_limits = [2.1353981634, 1.2963, 3.75, -0.15, None, -0.1, None] + #for larm_index, low, high in zip(self.robot.GetManipulator("leftarm").GetArmIndices(), larm_low_limits, larm_high_limits): + #if low is not None and high is not None: + #low_limits[larm_index] = low + #high_limits[larm_index] = high + #self.robot.SetDOFLimits(low_limits, high_limits) rospy.on_shutdown(self.stop_all) diff --git a/ArmPlannerPR2.py b/iros/ArmPlannerPR2.py similarity index 100% rename from ArmPlannerPR2.py rename to iros/ArmPlannerPR2.py diff --git a/IKPlannerFunctions.py b/iros/IKPlannerFunctions.py similarity index 100% rename from IKPlannerFunctions.py rename to iros/IKPlannerFunctions.py diff --git a/TrajectoryPlayback.py b/iros/TrajectoryPlayback.py similarity index 100% rename from TrajectoryPlayback.py rename to iros/TrajectoryPlayback.py diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py new file mode 100644 index 0000000..f467fc3 --- /dev/null +++ b/iros/follow_pose_traj.py @@ -0,0 +1,297 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("mode", choices=["openrave", "gazebo", "reality"]) +args = parser.parse_args() + +import trajoptpy +import openravepy +import numpy as np +import json +import trajoptpy.math_utils as mu +import trajoptpy.kin_utils as ku +import trajoptpy.make_kinbodies as mk + +import functools as ft + +import os +import os.path as osp +from glob import glob + +######################### +## Set up +######################### + +if args.mode == "openrave": + env = openravepy.Environment() + env.StopSimulation() + env.Load("robots/pr2-beta-static.zae") + import lfd + env.Load(osp.join(osp.dirname(lfd.__file__), "data/table2.xml")) + robot = env.GetRobots()[0] + torso_joint = robot.GetJoint("torso_lift_joint") + robot.SetDOFValues(torso_joint.GetLimits()[1], [torso_joint.GetDOFIndex()]) +else: + import rospy + from brett2.PR2 import PR2 + rospy.init_node("follow_pose_traj",disable_signals=True) + brett = PR2() + env = brett.env + robot = brett.robot + if args.mode == "gazebo": + brett.torso.go_up() + rospy.sleep(1) + brett.update_rave() + + if False:#args.mode == "reality": + table_bounds = map(float, rospy.get_param("table_bounds").split()) + mk.create_box_from_bounds(env,table_bounds, name="table") + else: + import lfd + env.Load(osp.join(osp.dirname(lfd.__file__), "data/table2.xml")) + +####################### + + + +def adaptive_resample(x, tol, max_change=None, min_steps=3): + """ + resample original signal it with a small number of waypoints so that the the sparsely sampled function, when linearly interpolated, + deviates from the original function by less than tol at every time + + input: + x: 2D array in R^(t x k) where t is the number of timesteps + tol: tolerance. either a single scalar or a vector of length k + max_change: max change in the sparsely sampled signal at each timestep + min_steps: minimum number of timesteps in the new trajectory. (usually irrelevant) + + output: + new_times, new_x + + assuming that the old signal has times 0,1,2,...,len(x)-1 + this gives the new times, and the new signal + """ + x = np.asarray(x) + assert x.ndim == 2 + + if np.isscalar(tol): + tol = np.ones(x.shape[1])*tol + else: + tol = np.asarray(tol) + assert tol.ndim == 1 and tol.shape[0] == x.shape[1] + + times = np.arange(x.shape[0]) + + if max_change is None: + max_change = np.ones(x.shape[1]) * np.inf + elif np.isscalar(max_change): + max_change = np.ones(x.shape[1]) * max_change + else: + max_change = np.asarray(max_change) + assert max_change.ndim == 1 and max_change.shape[0] == x.shape[1] + + dl = mu.norms(x[1:] - x[:-1],1) + l = np.cumsum(np.r_[0,dl]) + + def bad_inds(x1, t1): + ibad = np.flatnonzero( (np.abs(mu.interp2d(l, l1, x1) - x) > tol).any(axis=1) ) + jbad1 = np.flatnonzero((np.abs(x1[1:] - x1[:-1]) > max_change[None,:]).any(axis=1)) + if len(ibad) == 0 and len(jbad1) == 0: return [] + else: + lbad = l[ibad] + jbad = np.unique(np.searchsorted(l1, lbad)) - 1 + jbad = np.union1d(jbad, jbad1) + return jbad + + + l1 = np.linspace(0,l[-1],min_steps) + for _ in xrange(20): + x1 = mu.interp2d(l1, l, x) + bi = bad_inds(x1, l1) + if len(bi) == 0: + return np.interp(l1, l, times), x1 + else: + l1 = np.union1d(l1, (l1[bi] + l1[bi+1]) / 2 ) + + + raise Exception("couldn't subdivide enough. something funny is going on. check oyur input data") + + +################################### +###### Load demonstration files +################################### + + +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") +def keyfunc(fname): return int(osp.basename(fname).split("_")[0][2:]) # sort files with names like pt1_larm.npy +lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(osp.join(IROS_DATA_DIR, "InterruptedSutureTrajectories/pt*%s.npy"%partname)), + key = keyfunc) + for partname in ("lgrip", "rgrip", "larm", "rarm")] + + +###################################### + +from collections import namedtuple +TrajSegment = namedtuple("TrajSegment", "larm_traj rarm_traj lgrip_angle rgrip_angle") # class to describe trajectory segments + + + +OPEN_ANGLE = .08 +CLOSED_ANGLE = 0 + + +def segment_trajectory(larm, rarm, lgrip, rgrip): + + thresh = .04 # open/close threshold + + n_steps = len(larm) + assert len(rarm)==n_steps + assert len(lgrip)==n_steps + assert len(rgrip)==n_steps + + # indices BEFORE transition occurs + l_openings = np.flatnonzero((lgrip[1:] >= thresh) & (lgrip[:-1] < thresh)) + r_openings = np.flatnonzero((rgrip[1:] >= thresh) & (rgrip[:-1] < thresh)) + l_closings = np.flatnonzero((lgrip[1:] < thresh) & (lgrip[:-1] >= thresh)) + r_closings = np.flatnonzero((rgrip[1:] < thresh) & (rgrip[:-1] >= thresh)) + + before_transitions = np.r_[l_openings, r_openings, l_closings, r_closings] + after_transitions = before_transitions+1 + seg_starts = np.unique1d(np.r_[0, after_transitions]) + seg_ends = np.unique1d(np.r_[before_transitions, n_steps]) + + + + def binarize_gripper(angle): + if angle > thresh: return OPEN_ANGLE + else: return CLOSED_ANGLE + + traj_segments = [] + for (i_start, i_end) in zip(seg_starts, seg_ends): + l_angle = binarize_gripper(lgrip[i_start]) + r_angle = binarize_gripper(rgrip[i_start]) + traj_segments.append(TrajSegment( larm[i_start:i_end], rarm[i_start:i_end], l_angle, r_angle)) + #import IPython + #IPython.embed() + return traj_segments + +PARTNUM = 0 +segments = segment_trajectory( + np.load(larm_files[PARTNUM]), + np.load(rarm_files[PARTNUM]), + np.load(lgrip_files[PARTNUM]), + np.load(rgrip_files[PARTNUM])) + +print "trajectory broken into %i segments by gripper transitions"%len(segments) + +for (i,segment) in enumerate(segments): + print "trajectory segment %i"%i + + full_traj = np.c_[segment.larm_traj, segment.rarm_traj] + full_traj = mu.remove_duplicate_rows(full_traj) + orig_times = np.arange(len(full_traj)) + ds_times, ds_traj = adaptive_resample(full_traj, tol=.025, max_change=.1) # about 2.5 degrees, 10 degrees + n_steps = len(ds_traj) + + + #################### + ### This part just gets the cartesian trajectory + #################### + + robot.SetActiveDOFs(np.r_[robot.GetManipulator("leftarm").GetArmIndices(), robot.GetManipulator("rightarm").GetArmIndices()]) + # let's get cartesian trajectory + left_hmats = [] + right_hmats = [] + for row in ds_traj: + robot.SetActiveDOFValues(row) + left_hmats.append(robot.GetLink("l_gripper_tool_frame").GetTransform()) + right_hmats.append(robot.GetLink("r_gripper_tool_frame").GetTransform()) + + + # now let's shift it a little + for i in xrange(n_steps): + left_hmats[i][0,3] -= 0 + right_hmats[i][0,3] -= 0 + + ################### + + + POSTURE_COEFF = 1 + + def nodecost(manip, joints, step): + robot = manip.GetRobot() + saver = openravepy.Robot.RobotStateSaver(robot) + robot.SetDOFValues(joints, manip.GetArmJoints(), False) + old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] + joint_diff = old_joints - joints + for i in [2,4,6]: + joint_diff[i] %= 2*np.pi + if joint_diff[i] > np.pi: joint_diff[i] -= np.pi + return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) + def left_ikfunc(hmat): + return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) # env collisions, no self / ee collisions + def unwrapped_squared_dist(x_nk,y_mk): + "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" + diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) + diffs_nmk[:,:,[2,4,6]] %= 2*np.pi + return (diffs_nmk**2).sum(axis=2) + + + left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, + ikfunc = left_ikfunc, + nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), + edgecost = unwrapped_squared_dist) + + print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) + best_left_path_before_interp = left_paths[np.argmin(left_costs)] + + if len(timesteps) < n_steps: + print "linearly interpolating the points with no soln" + best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) + else: best_left_path = best_left_path_before_interp + + + def right_ikfunc(hmat): + return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) # env collisions + self collisions + + + right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, + ikfunc = right_ikfunc, + nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), + edgecost = unwrapped_squared_dist) + + print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) + best_right_path_before_interp = right_paths[np.argmin(right_costs)] + if len(timesteps) < n_steps: + print "linearly interpolating the points with no soln" + best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) + else: best_right_path = best_right_path_before_interp + + + + + ################################## + #### Now view/execute the trajectory + ################################## + + if args.mode == "openrave": + viewer = trajoptpy.GetViewer(env) + joint_traj = np.c_[best_left_path, best_right_path] + # *5 factor is due to an openrave oddity + robot.SetDOFValues([segment.lgrip_angle*5, segment.rgrip_angle*5], [robot.GetJoint("l_gripper_l_finger_joint").GetDOFIndex(), robot.GetJoint("r_gripper_l_finger_joint").GetDOFIndex()], False) + for (i,row) in enumerate(ds_traj): + print "step",i + robot.SetActiveDOFValues(row) + lhandle = env.drawarrow(robot.GetLink("l_gripper_tool_frame").GetTransform()[:3,3], left_hmats[i][:3,3]) + rhandle = env.drawarrow(robot.GetLink("r_gripper_tool_frame").GetTransform()[:3,3], right_hmats[i][:3,3]) + viewer.Idle() + else: + from brett2 import trajectories + #def follow_body_traj2(pr2, bodypart2traj, times=None, wait=True, base_frame = "/base_footprint"): + bodypart2traj = {} + brett.lgrip.set_angle(segment.lgrip_angle) + brett.rgrip.set_angle(segment.rgrip_angle) + brett.join_all() + bodypart2traj["l_arm"] = segment.larm_traj + bodypart2traj["r_arm"] = segment.rarm_traj + trajectories.follow_body_traj2(brett, bodypart2traj) + diff --git a/launch.py b/iros/launch.py similarity index 100% rename from launch.py rename to iros/launch.py diff --git a/notes.txt b/iros/notes.txt similarity index 100% rename from notes.txt rename to iros/notes.txt From 70fd35cb0143671ff74b195ac6711025c831ce0e Mon Sep 17 00:00:00 2001 From: John Schulman Date: Thu, 21 Feb 2013 15:23:12 -0800 Subject: [PATCH 03/26] image gui --- iros/__init__.py | 0 iros/image_gui.py | 96 +++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 96 insertions(+) create mode 100644 iros/__init__.py create mode 100644 iros/image_gui.py diff --git a/iros/__init__.py b/iros/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/iros/image_gui.py b/iros/image_gui.py new file mode 100644 index 0000000..79fdbfe --- /dev/null +++ b/iros/image_gui.py @@ -0,0 +1,96 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("--mode",choices=["live","test"],default="live") +parser.add_argument("--cloud_topic", default="/drop/points") +parser.add_argument("--plot3d", action="store_true") +args = parser.parse_args() + +""" +# how to get a pcd file +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("pr2_suture_scene.pcd") +""" + +import cv2 +import numpy as np + + +if args.mode == "test": + from jds_image_proc.pcd_io import load_xyzrgb + xyz, rgb = load_xyzrgb("pr2_suture_scene.pcd") + import openravepy + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + xyz1 = np.c_[xyz.reshape(-1,3), np.ones((xyz.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf = xyz1_tf[:,:3].reshape(xyz.shape) +elif args.mode == "live": + import brett2.ros_utils as ru + import rospy + import sensor_msgs.msg as sm + rospy.init_node("image_gui",disable_signals = True) + listener = ru.get_tf_listener() + print "waiting for message on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got it!" + xyz, rgb = ru.pc2xyzrgb(msg) + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") +xyz_tf[np.isnan(xyz_tf)] = -2 +rgb_plot = rgb.copy() +depth_plot = xyz_tf[:,:,2].astype('float') +depth_plot[np.isnan(depth_plot)] = 0 +depth_plot -= depth_plot.min() +depth_plot = (depth_plot * (255 / depth_plot.max())).astype('uint8') +class GetClick: + xy = None + done = False + def callback(self,event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True +cv2.namedWindow("rgb") +rect_corners = [] +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0,255, 0)) + +# extract rectangle +colmin, rowmin = xy_tl +colmax, rowmax = xy_br +z_rectangle = xyz_tf[rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectnalge +row_needle, col_needle = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) +col_needle += colmin ## since these indices are from small rectangle +row_needle += rowmin +cv2.circle(rgb_plot, (col_needle, row_needle), 3, (255,0,0), 2) + + +if args.plot3d: + from mayavi import mlab + x,y,z = xyz_tf[~np.isnan(xyz_tf[:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + xneedle,yneedle,zneedle = xyz_tf[row_needle, col_needle] + print xneedle,yneedle,zneedle + mlab.points3d([xneedle], [yneedle], [zneedle], color=(0,1,0), mode="sphere",scale_factor=.04,opacity=.2) + mlab.show() +else: + + while True: + cv2.imshow("rgb",rgb_plot) + #cv2.imshow("depth", depth_plot) + cv2.waitKey(10) \ No newline at end of file From 59b3e9868105248f8e28e942563699167afdc082 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Tue, 5 Mar 2013 17:52:09 -0800 Subject: [PATCH 04/26] suturing stuff --- iros/execute_suture_traj.py | 500 ++++++++++++++++++++++++++++++++++++ iros/follow_pose_traj.py | 189 +++++++++----- iros/image_gui.py | 37 +-- iros/image_gui2.py | 187 ++++++++++++++ iros/make_suture_library.py | 50 ++++ iros/process_suture_bag.py | 266 +++++++++++++++++++ iros/simple_clicker.py | 305 ++++++++++++++++++++++ iros/simple_clicker_dev.py | 293 +++++++++++++++++++++ 8 files changed, 1751 insertions(+), 76 deletions(-) create mode 100644 iros/execute_suture_traj.py create mode 100755 iros/image_gui2.py create mode 100644 iros/make_suture_library.py create mode 100644 iros/process_suture_bag.py create mode 100644 iros/simple_clicker.py create mode 100644 iros/simple_clicker_dev.py diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py new file mode 100644 index 0000000..c4b0beb --- /dev/null +++ b/iros/execute_suture_traj.py @@ -0,0 +1,500 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("mode", choices=["openrave", "gazebo", "reality"]) +parser.add_argument("cloud_topic", default="/drop/points") +parser.add_argument("task") +parser.add_argument("part_name") +args = parser.parse_args() + +import numpy as np +import trajoptpy +import lfd +import openravepy +import json +import trajoptpy.math_utils as mu +import trajoptpy.kin_utils as ku +import trajoptpy.make_kinbodies as mk +import brett2.ros_utils as ru +from jds_utils.colorize import colorize +from jds_utils import conversions +from brett2 import mytf +import yaml +import cv2 + +import functools as ft +import simple_clicker as sc +import os +import os.path as osp +from glob import glob +import subprocess, sys +import sensor_msgs.msg as sm + + + +window_name = "Find Keypoints" +cv2.namedWindow(window_name) + +######################### +###### Set up +######################### + +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") + +task_file = osp.join(IROS_DATA_DIR, "suture_demos.yaml") + +with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: + task_info = yaml.load(fh) + +jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) +kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) +pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) + +if args.mode == "openrave": + env = openravepy.Environment() + env.StopSimulation() + env.Load("robots/pr2-beta-static.zae") + env.Load(osp.join(osp.dirname(lfd.__file__), "data/table2.xml")) + robot = env.GetRobots()[0] + torso_joint = robot.GetJoint("torso_lift_joint") + robot.SetDOFValues(torso_joint.GetLimits()[1], [torso_joint.GetDOFIndex()]) + +else: + import rospy + from brett2.PR2 import PR2 + if rospy.get_name() == "/unnamed": rospy.init_node("follow_pose_traj", disable_signals=True) + rviz = ru.RvizWrapper() + brett = PR2() + env = brett.env + robot = brett.robot + if args.mode == "gazebo": + brett.torso.go_up() + rospy.sleep(1) + brett.update_rave() + + if False:#args.mode == "reality": + table_bounds = map(float, rospy.get_param("table_bounds").split()) + mk.create_box_from_bounds(env,table_bounds, name="table") + else: + import lfd + env.Load(osp.join(osp.dirname(lfd.__file__), "data/table2.xml")) + +####################### + +from collections import namedtuple +TrajSegment = namedtuple("TrajSegment", "larm_traj rarm_traj lgrip_angle rgrip_angle") # class to describe trajectory segments + +PARTNUM = task_info[args.task][args.part_name]["pt_num"] +SEGNUM = task_info[args.task][args.part_name]["seg_num"] +OPEN_ANGLE = .08 +CLOSED_ANGLE = 0 + + +def call_and_print(cmd,color='green'): + print colorize(cmd, color, bold=True) + subprocess.check_call(cmd, shell=True) + + +def transform_hmats(f, hmats): + hmats = np.array(hmats) + oldpts_md = hmats[:,:3,3] + oldrots_mad = hmats[:,:3,:3] + newpts_mg, newrots_mgd = f.transform_frames(oldpts_md, oldrots_mad) + tf_hmats = hmats.copy() + tf_hmats[:,:3,:3] = newrots_mgd + tf_hmats[:,:3,3] = newpts_mg + return tf_hmats + +def adaptive_resample(x, tol, max_change=None, min_steps=3): + """ + resample original signal with a small number of waypoints so that the the sparsely sampled function, + when linearly interpolated, deviates from the original function by less than tol at every time + + input: + x: 2D array in R^(t x k) where t is the number of timesteps + tol: tolerance. either a single scalar or a vector of length k + max_change: max change in the sparsely sampled signal at each timestep + min_steps: minimum number of timesteps in the new trajectory. (usually irrelevant) + + output: + new_times, new_x + + assuming that the old signal has times 0,1,2,...,len(x)-1 + this gives the new times, and the new signal + """ + x = np.asarray(x) + assert x.ndim == 2 + + if np.isscalar(tol): + tol = np.ones(x.shape[1])*tol + else: + tol = np.asarray(tol) + assert tol.ndim == 1 and tol.shape[0] == x.shape[1] + + times = np.arange(x.shape[0]) + + if max_change is None: + max_change = np.ones(x.shape[1]) * np.inf + elif np.isscalar(max_change): + max_change = np.ones(x.shape[1]) * max_change + else: + max_change = np.asarray(max_change) + assert max_change.ndim == 1 and max_change.shape[0] == x.shape[1] + + dl = mu.norms(x[1:] - x[:-1],1) + l = np.cumsum(np.r_[0,dl]) + + def bad_inds(x1, t1): + ibad = np.flatnonzero( (np.abs(mu.interp2d(l, l1, x1) - x) > tol).any(axis=1) ) + jbad1 = np.flatnonzero((np.abs(x1[1:] - x1[:-1]) > max_change[None,:]).any(axis=1)) + if len(ibad) == 0 and len(jbad1) == 0: return [] + else: + lbad = l[ibad] + jbad = np.unique(np.searchsorted(l1, lbad)) - 1 + jbad = np.union1d(jbad, jbad1) + return jbad + + l1 = np.linspace(0,l[-1],min_steps) + for _ in xrange(20): + x1 = mu.interp2d(l1, l, x) + bi = bad_inds(x1, l1) + if len(bi) == 0: + return np.interp(l1, l, times), x1 + else: + l1 = np.union1d(l1, (l1[bi] + l1[bi+1]) / 2 ) + + + raise Exception("couldn't subdivide enough. something funny is going on. check your input data") + + +def segment_trajectory(larm, rarm, lgrip, rgrip): + + thresh = .04 # open/close threshold + + n_steps = len(larm) + assert len(rarm)==n_steps + assert len(lgrip)==n_steps + assert len(rgrip)==n_steps + + # indices BEFORE transition occurs + l_openings = np.flatnonzero((lgrip[1:] >= thresh) & (lgrip[:-1] < thresh)) + r_openings = np.flatnonzero((rgrip[1:] >= thresh) & (rgrip[:-1] < thresh)) + l_closings = np.flatnonzero((lgrip[1:] < thresh) & (lgrip[:-1] >= thresh)) + r_closings = np.flatnonzero((rgrip[1:] < thresh) & (rgrip[:-1] >= thresh)) + + before_transitions = np.r_[l_openings, r_openings, l_closings, r_closings] + after_transitions = before_transitions+1 + seg_starts = np.unique(np.r_[0, after_transitions]) + seg_ends = np.unique(np.r_[before_transitions, n_steps]) + + + def binarize_gripper(angle): + if angle > thresh: return OPEN_ANGLE + else: return CLOSED_ANGLE + + traj_segments = [] + for (i_start, i_end) in zip(seg_starts, seg_ends): + l_angle = binarize_gripper(lgrip[i_start]) + r_angle = binarize_gripper(rgrip[i_start]) + traj_segments.append(TrajSegment( larm[i_start:i_end], rarm[i_start:i_end], l_angle, r_angle )) + + return traj_segments + +def get_holes_cut_cloud(listener): + print colorize("Key points from demo are: Holes and Cut. Looking for Holes and Cut now...", 'green', bold=True) + + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg!" + xyz, rgb = ru.pc2xyzrgb(msg) + + #import matplotlib.pyplot as plt + #plt.imshow(xyz[:,:,2]) + #plt.title("xyz") + #plt.show() + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf[np.isnan(xyz_tf)] = -2 + rgb_plot = rgb.copy() + + #import matplotlib.pyplot as plt + #plt.imshow(xyz_tf[:,:,2]) + #plt.title("xyz_tf") + #plt.show() + + + return xyz_tf, rgb_plot + +def get_needle_clouds(listener): + print colorize("Key points from demo are: Needle. Looking for Needle now...", 'green', bold=True) + + xyz_tfs = [] + rgb_plots = [] + num_clouds = 30 + + if args.cloud_topic == 'test': num_clouds = 5 + + for i in range(num_clouds): + + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg %s!"%i + xyz, rgb = ru.pc2xyzrgb(msg) + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf[np.isnan(xyz_tf)] = -2 + + xyz_tfs.append(xyz_tf) + rgb_plots.append(rgb) + + return xyz_tfs, rgb_plots + + +####################################### +###### Load demo from np files +####################################### + +demo_keypts = np.load(osp.join(IROS_DATA_DIR, kpf + "_keypoints.npy")) +demo_keypts_names = np.load(osp.join(IROS_DATA_DIR, kpf + "_keypoints_names.npy")) +demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf + "_needle_world_loc.npy")) + +def keyfunc(fname): + return int(osp.basename(fname).split("_")[0][6:]) # sort files with names like pt1_larm.npy + +lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(jtf + "seg*%s.npy"%partname), + key = keyfunc) + for partname in ("lgrip", "rgrip", "larm", "rarm")] + +mini_segments = [] + +for s in range(SEGNUM): + mini_segments.append( segment_trajectory( np.load(larm_files[s]), + np.load(rarm_files[s]), + np.load(lgrip_files[s]), + np.load(rgrip_files[s]))) + + print "trajectory segment", str(s), "broken into %i mini-segment(s) by gripper transitions"%len(mini_segments[s]) + +raw_input("press enter to execute") +####################################### + +### iterate through each 'look' segment; for each segment: +### click on key points +### compare to key points from demonstration, do registration, find warping function +### iterate through each mini-segment +### downsample +### find cartestian coordinates for trajectory +### transform cartestian trajectory according to warping function +### do ik to find new joint space trajectory (left arm first, then right arm) +### execute new trajectory + +listener = ru.get_tf_listener() + +handles = [] + +for s in range(SEGNUM): + print "trajectory segment %i"%s + + num_kps = len(demo_keypts_names[s]) + exec_keypts = [] + + if num_kps != 1: + print 'number of keypoints yet not supported! aborting...' + sys.exit(1) + + for k in range(num_kps): + if demo_keypts_names[s][k] == 'holes_and_cut': + if args.cloud_topic == 'test': + xyz_tf = np.load(pcf + 'seg%s_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_rgb_plot.npy'%s) + else: + xyz_tf, rgb_plot = get_holes_cut_cloud(listener) + + hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc = sc.find_holes_cut(xyz_tf, rgb_plot, window_name) + + exec_keypts.append(hole1_loc) + exec_keypts.append(hole2_loc) + exec_keypts.append(tcut_loc) + exec_keypts.append(mcut_loc) + exec_keypts.append(bcut_loc) + + elif demo_keypts_names[s][k] == 'needle_end': + if args.cloud_topic == 'test': + xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + else: + xyz_tfs, rgb_plots = get_needle_clouds(listener) + nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + exec_keypts.append(nl) + + elif demo_keypts_names[s][k] == 'needle_tip': + if args.cloud_topic == 'test': + xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + else: + xyz_tfs, rgb_plots = get_needle_clouds(listener) + nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) + exec_keypts.append(nl) + + elif demo_keypts_names[s][k] == 'empty': + if args.cloud_topic == 'test': + xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + else: + xyz_tfs, rgb_plots = get_needle_clouds(listener) + exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) + exec_keypts.append((0,0,0)) + + + #print 'exec_keypts', exec_keypts + + demopoints_m3 = np.array(demo_keypts[s]) + newpoints_m3 = np.array(exec_keypts) + if args.mode in ["gazebo", "reality"]: + handles = [] + pose_array = conversions.array_to_pose_array(demopoints_m3, '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.02,type=ru.Marker.CUBE_LIST)) + pose_array = conversions.array_to_pose_array(newpoints_m3, '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.02,type=ru.Marker.CUBE_LIST)) + + del exec_keypts + + from lfd import registration + f = registration.ThinPlateSpline() + #f.fit(demopoints_m3, newpoints_m3, 10,10) + f.fit(demopoints_m3, newpoints_m3, bend_coef=10,rot_coef=.01) + + + for (i,mini_segment) in enumerate(mini_segments[s]): + print "mini-segment %i"%i + + full_traj = np.c_[mini_segment.larm_traj, mini_segment.rarm_traj] + full_traj = mu.remove_duplicate_rows(full_traj) + orig_times = np.arange(len(full_traj)) + + ### downsample the trajectory + ds_times, ds_traj = adaptive_resample(full_traj, tol=.025, max_change=.1) # about 2.5 degrees, 10 degrees + n_steps = len(ds_traj) + + ################################################ + ### This part gets the cartesian trajectory + ################################################ + + robot.SetActiveDOFs(np.r_[robot.GetManipulator("leftarm").GetArmIndices(), robot.GetManipulator("rightarm").GetArmIndices()]) + # let's get cartesian trajectory + left_hmats = [] + right_hmats = [] + + for row in ds_traj: + robot.SetActiveDOFValues(row) + left_hmats.append(robot.GetLink("l_gripper_tool_frame").GetTransform()) + right_hmats.append(robot.GetLink("r_gripper_tool_frame").GetTransform()) + + left_hmats_old = left_hmats + left_hmats = transform_hmats(f, left_hmats) + right_hmats_old = right_hmats + right_hmats = transform_hmats(f, right_hmats) + + + if args.mode in ["gazebo", "reality"]: + pose_array = conversions.array_to_pose_array(np.array(left_hmats_old)[:,:3,3], '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) + pose_array = conversions.array_to_pose_array(np.array(right_hmats_old)[:,:3,3], '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) + + pose_array = conversions.array_to_pose_array(np.array(left_hmats)[:,:3,3], '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) + pose_array = conversions.array_to_pose_array(np.array(right_hmats)[:,:3,3], '/base_footprint') + handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) + + + ################################################ + + + POSTURE_COEFF = 1 + + def nodecost(manip, joints, step): + robot = manip.GetRobot() + saver = openravepy.RobotStateSaver(robot) + robot.SetDOFValues(joints, manip.GetArmJoints(), False) + old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] + joint_diff = old_joints - joints + for i in [2,4,6]: + joint_diff[i] %= 2*np.pi + if joint_diff[i] > np.pi: joint_diff[i] -= np.pi + return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) + + from lfd import registration + + def left_ikfunc(hmat): + return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) + # env collisions, no self / ee collisions + + def unwrapped_squared_dist(x_nk,y_mk): + "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" + diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) + diffs_nmk[:,:,[2,4,6]] %= 2*np.pi + return (diffs_nmk**2).sum(axis=2) + + left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, + ikfunc = left_ikfunc, + nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), + edgecost = unwrapped_squared_dist) + + print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) + best_left_path_before_interp = left_paths[np.argmin(left_costs)] + + if len(timesteps) < n_steps: + print "linearly interpolating the points with no soln" + best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) + else: best_left_path = best_left_path_before_interp + + + def right_ikfunc(hmat): + return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) + # env collisions + self collisions + + right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, + ikfunc = right_ikfunc, + nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), + edgecost = unwrapped_squared_dist) + + print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) + best_right_path_before_interp = right_paths[np.argmin(right_costs)] + + if len(timesteps) < n_steps: + print "linearly interpolating the points with no soln" + best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) + else: best_right_path = best_right_path_before_interp + + + raw_input(colorize("look at markers in rviz. red=demo, blue=new. press enter to continue","red")) + + ###################################### + ### Now view/execute the trajectory + ###################################### + + if args.mode == "openrave": + viewer = trajoptpy.GetViewer(env) + joint_traj = np.c_[best_left_path, best_right_path] + # *5 factor is due to an openrave oddity + robot.SetDOFValues([mini_segment.lgrip_angle*5, mini_segment.rgrip_angle*5], [robot.GetJoint("l_gripper_l_finger_joint").GetDOFIndex(), robot.GetJoint("r_gripper_l_finger_joint").GetDOFIndex()], False) + for (i,row) in enumerate(joint_traj): + print "step",i + robot.SetActiveDOFValues(row) + lhandle = env.drawarrow(robot.GetLink("l_gripper_tool_frame").GetTransform()[:3,3], left_hmats[i][:3,3]) + rhandle = env.drawarrow(robot.GetLink("r_gripper_tool_frame").GetTransform()[:3,3], right_hmats[i][:3,3]) + viewer.Idle() + else: + from brett2 import trajectories + #def follow_body_traj2(pr2, bodypart2traj, times=None, wait=True, base_frame = "/base_footprint"): + bodypart2traj = {} + brett.lgrip.set_angle(mini_segment.lgrip_angle) + brett.rgrip.set_angle(mini_segment.rgrip_angle) + brett.join_all() + bodypart2traj["l_arm"] = best_left_path + bodypart2traj["r_arm"] = best_right_path + trajectories.follow_body_traj2(brett, bodypart2traj) diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py index f467fc3..0d87202 100644 --- a/iros/follow_pose_traj.py +++ b/iros/follow_pose_traj.py @@ -4,21 +4,31 @@ args = parser.parse_args() import trajoptpy +from lfd import bag_proc as bp import openravepy import numpy as np import json import trajoptpy.math_utils as mu import trajoptpy.kin_utils as ku import trajoptpy.make_kinbodies as mk +from jds_utils.colorize import colorize import functools as ft import os import os.path as osp -from glob import glob +from glob import glob +import subprocess, sys + +import rosbag +import geometry_msgs.msg as gm +import sensor_msgs.msg as sm + +import roslib; roslib.load_manifest('filter_cloud_color') +from filter_cloud_color.srv import PointDir ######################### -## Set up +###### Set up ######################### if args.mode == "openrave": @@ -33,7 +43,7 @@ else: import rospy from brett2.PR2 import PR2 - rospy.init_node("follow_pose_traj",disable_signals=True) + rospy.init_node("follow_pose_traj", disable_signals=True) brett = PR2() env = brett.env robot = brett.robot @@ -51,12 +61,23 @@ ####################### +from collections import namedtuple +TrajSegment = namedtuple("TrajSegment", "larm_traj rarm_traj lgrip_angle rgrip_angle") # class to describe trajectory segments + +PARTNUM = 0 +OPEN_ANGLE = .08 +CLOSED_ANGLE = 0 + + +def call_and_print(cmd,color='green'): + print colorize(cmd, color, bold=True) + subprocess.check_call(cmd, shell=True) def adaptive_resample(x, tol, max_change=None, min_steps=3): """ - resample original signal it with a small number of waypoints so that the the sparsely sampled function, when linearly interpolated, - deviates from the original function by less than tol at every time + resample original signal with a small number of waypoints so that the the sparsely sampled function, + when linearly interpolated, deviates from the original function by less than tol at every time input: x: 2D array in R^(t x k) where t is the number of timesteps @@ -113,34 +134,11 @@ def bad_inds(x1, t1): l1 = np.union1d(l1, (l1[bi] + l1[bi+1]) / 2 ) - raise Exception("couldn't subdivide enough. something funny is going on. check oyur input data") + raise Exception("couldn't subdivide enough. something funny is going on. check your input data") - -################################### -###### Load demonstration files -################################### - - -IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") -def keyfunc(fname): return int(osp.basename(fname).split("_")[0][2:]) # sort files with names like pt1_larm.npy -lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(osp.join(IROS_DATA_DIR, "InterruptedSutureTrajectories/pt*%s.npy"%partname)), - key = keyfunc) - for partname in ("lgrip", "rgrip", "larm", "rarm")] - - -###################################### - -from collections import namedtuple -TrajSegment = namedtuple("TrajSegment", "larm_traj rarm_traj lgrip_angle rgrip_angle") # class to describe trajectory segments - - - -OPEN_ANGLE = .08 -CLOSED_ANGLE = 0 - def segment_trajectory(larm, rarm, lgrip, rgrip): - + thresh = .04 # open/close threshold n_steps = len(larm) @@ -154,13 +152,14 @@ def segment_trajectory(larm, rarm, lgrip, rgrip): l_closings = np.flatnonzero((lgrip[1:] < thresh) & (lgrip[:-1] >= thresh)) r_closings = np.flatnonzero((rgrip[1:] < thresh) & (rgrip[:-1] >= thresh)) + #raw_input("Press enter to continue...") + before_transitions = np.r_[l_openings, r_openings, l_closings, r_closings] after_transitions = before_transitions+1 - seg_starts = np.unique1d(np.r_[0, after_transitions]) - seg_ends = np.unique1d(np.r_[before_transitions, n_steps]) - - + seg_starts = np.unique(np.r_[0, after_transitions]) + seg_ends = np.unique(np.r_[before_transitions, n_steps]) + def binarize_gripper(angle): if angle > thresh: return OPEN_ANGLE else: return CLOSED_ANGLE @@ -169,50 +168,116 @@ def binarize_gripper(angle): for (i_start, i_end) in zip(seg_starts, seg_ends): l_angle = binarize_gripper(lgrip[i_start]) r_angle = binarize_gripper(rgrip[i_start]) - traj_segments.append(TrajSegment( larm[i_start:i_end], rarm[i_start:i_end], l_angle, r_angle)) - #import IPython - #IPython.embed() + traj_segments.append(TrajSegment( larm[i_start:i_end], rarm[i_start:i_end], l_angle, r_angle )) + return traj_segments + + +####################################### +###### Load demo from np files +####################################### + + +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") +traj_data_dir = IROS_DATA_DIR + "/joint_trajectories" + +def keyfunc(fname): + return int(osp.basename(fname).split("_")[0][2:]) # sort files with names like pt1_larm.npy + +lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(osp.join(traj_data_dir, "InterruptedSuture2/pt*%s.npy"%partname)), + key = keyfunc) + for partname in ("lgrip", "rgrip", "larm", "rarm")] + + +segments = segment_trajectory( np.load(larm_files[PARTNUM]), + np.load(rarm_files[PARTNUM]), + np.load(lgrip_files[PARTNUM]), + np.load(rgrip_files[PARTNUM])) + + +######################################## -PARTNUM = 0 -segments = segment_trajectory( - np.load(larm_files[PARTNUM]), - np.load(rarm_files[PARTNUM]), - np.load(lgrip_files[PARTNUM]), - np.load(rgrip_files[PARTNUM])) print "trajectory broken into %i segments by gripper transitions"%len(segments) +### iterate through each segment in the trajectory; for each segment: +### downsample +### find cartestian coordinates for trajectory +### transform cartestian trajectory +### do ik to find new joint space trajectory (left arm first, then right arm) +### execute new trajectory + +imaging = False +find_needle = False + +if imaging: + print 'waiting for service' + # find line + rospy.wait_for_service("/getCutLine") + print 'found service getCutLine' + + try: + cutline = rospy.ServiceProxy("/getCutLine", PointDir) + flapLoc = cutline(1) + except rospy.ServiceException, e: + print "error when calling getCutLine: %s"%e + sys.exit(1) + + print 'getCutLine flap location point', flapLoc.point + print 'getCutLine flap location dir', flapLoc.dir + + # find holes + rospy.wait_for_service("/getHoleNormal") + print 'found service getHoleNormal' + + try: + hole = rospy.ServiceProxy("/getHoleNormal", PointDir) + hole1Loc = hole(1) + hole2Loc = hole(2) + except rospy.ServiceException, e: + print "error when calling getHoleNormal: %s"%e + sys.exit(1) + + print 'getHoleNormal hole1 location point', hole1Loc.point + print 'getHoleNormal hole1 location dir', hole1Loc.dir + + print 'getHoleNormal hole2 location point', hole2Loc.point + print 'getHoleNormal hole2 location dir', hole2Loc.dir + + raw_input("press enter to continue") + + for (i,segment) in enumerate(segments): print "trajectory segment %i"%i full_traj = np.c_[segment.larm_traj, segment.rarm_traj] full_traj = mu.remove_duplicate_rows(full_traj) orig_times = np.arange(len(full_traj)) + + ### downsample the trajectory ds_times, ds_traj = adaptive_resample(full_traj, tol=.025, max_change=.1) # about 2.5 degrees, 10 degrees n_steps = len(ds_traj) - - #################### - ### This part just gets the cartesian trajectory - #################### + ################################################ + ### This part gets the cartesian trajectory + ################################################ robot.SetActiveDOFs(np.r_[robot.GetManipulator("leftarm").GetArmIndices(), robot.GetManipulator("rightarm").GetArmIndices()]) # let's get cartesian trajectory left_hmats = [] right_hmats = [] + for row in ds_traj: robot.SetActiveDOFValues(row) left_hmats.append(robot.GetLink("l_gripper_tool_frame").GetTransform()) right_hmats.append(robot.GetLink("r_gripper_tool_frame").GetTransform()) - - + # now let's shift it a little for i in xrange(n_steps): left_hmats[i][0,3] -= 0 right_hmats[i][0,3] -= 0 - ################### + ################################################ POSTURE_COEFF = 1 @@ -227,15 +292,17 @@ def nodecost(manip, joints, step): joint_diff[i] %= 2*np.pi if joint_diff[i] > np.pi: joint_diff[i] -= np.pi return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) + def left_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) # env collisions, no self / ee collisions + return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) + # env collisions, no self / ee collisions + def unwrapped_squared_dist(x_nk,y_mk): "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) diffs_nmk[:,:,[2,4,6]] %= 2*np.pi return (diffs_nmk**2).sum(axis=2) - - + left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, ikfunc = left_ikfunc, nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), @@ -251,9 +318,9 @@ def unwrapped_squared_dist(x_nk,y_mk): def right_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) # env collisions + self collisions - - + return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) + # env collisions + self collisions + right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, ikfunc = right_ikfunc, nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), @@ -261,17 +328,17 @@ def right_ikfunc(hmat): print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) best_right_path_before_interp = right_paths[np.argmin(right_costs)] + if len(timesteps) < n_steps: print "linearly interpolating the points with no soln" best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) else: best_right_path = best_right_path_before_interp + - - - ################################## - #### Now view/execute the trajectory - ################################## + ###################################### + ### Now view/execute the trajectory + ###################################### if args.mode == "openrave": viewer = trajoptpy.GetViewer(env) diff --git a/iros/image_gui.py b/iros/image_gui.py index 79fdbfe..3906b8f 100644 --- a/iros/image_gui.py +++ b/iros/image_gui.py @@ -1,6 +1,6 @@ import argparse parser = argparse.ArgumentParser() -parser.add_argument("--mode",choices=["live","test"],default="live") +parser.add_argument("--mode", choices=["live","test"], default="live") parser.add_argument("--cloud_topic", default="/drop/points") parser.add_argument("--plot3d", action="store_true") args = parser.parse_args() @@ -19,8 +19,9 @@ if args.mode == "test": from jds_image_proc.pcd_io import load_xyzrgb - xyz, rgb = load_xyzrgb("pr2_suture_scene.pcd") import openravepy + + xyz, rgb = load_xyzrgb("pr2_suture_scene.pcd") env = openravepy.Environment() env.Load("robots/pr2-beta-static.zae") robot = env.GetRobots()[0] @@ -29,11 +30,13 @@ xyz1 = np.c_[xyz.reshape(-1,3), np.ones((xyz.size/3,1))] xyz1_tf = np.dot(xyz1, hmat.T) xyz_tf = xyz1_tf[:,:3].reshape(xyz.shape) + elif args.mode == "live": import brett2.ros_utils as ru import rospy import sensor_msgs.msg as sm - rospy.init_node("image_gui",disable_signals = True) + + rospy.init_node("image_gui", disable_signals = True) listener = ru.get_tf_listener() print "waiting for message on cloud topic %s"%args.cloud_topic msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) @@ -41,21 +44,24 @@ xyz, rgb = ru.pc2xyzrgb(msg) if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf[np.isnan(xyz_tf)] = -2 rgb_plot = rgb.copy() depth_plot = xyz_tf[:,:,2].astype('float') depth_plot[np.isnan(depth_plot)] = 0 depth_plot -= depth_plot.min() depth_plot = (depth_plot * (255 / depth_plot.max())).astype('uint8') + class GetClick: xy = None done = False - def callback(self,event, x, y, flags, param): + def callback(self, event, x, y, flags, param): if self.done: return elif event == cv2.EVENT_LBUTTONDOWN: self.xy = (x,y) self.done = True + cv2.namedWindow("rgb") rect_corners = [] for i in xrange(2): @@ -68,29 +74,30 @@ def callback(self,event, x, y, flags, param): xy_tl = np.array(rect_corners).min(axis=0) xy_br = np.array(rect_corners).max(axis=0) -cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0,255, 0)) +cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) ## this doesn't seem to be working... -# extract rectangle +# extract depths from drawn rectangle ##ADD STUFF HERE to make this work better colmin, rowmin = xy_tl colmax, rowmax = xy_br -z_rectangle = xyz_tf[rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectnalge + +z_rectangle = xyz_tf[rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle, col_needle = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) -col_needle += colmin ## since these indices are from small rectangle +col_needle += colmin # since these indices are from small rectangle row_needle += rowmin -cv2.circle(rgb_plot, (col_needle, row_needle), 3, (255,0,0), 2) +cv2.circle(rgb_plot, (col_needle, row_needle), 3, (255, 0, 0), 2) ## this doesn't seem to be working... - +# plot the point cloud with a circle around "highest" point if args.plot3d: from mayavi import mlab x,y,z = xyz_tf[~np.isnan(xyz_tf[:,:,0])].T mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") xneedle,yneedle,zneedle = xyz_tf[row_needle, col_needle] - print xneedle,yneedle,zneedle - mlab.points3d([xneedle], [yneedle], [zneedle], color=(0,1,0), mode="sphere",scale_factor=.04,opacity=.2) + print "xyz needle point", xneedle, yneedle, zneedle + mlab.points3d([xneedle], [yneedle], [zneedle], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) mlab.show() -else: - +else: while True: cv2.imshow("rgb",rgb_plot) #cv2.imshow("depth", depth_plot) - cv2.waitKey(10) \ No newline at end of file + cv2.waitKey(10) diff --git a/iros/image_gui2.py b/iros/image_gui2.py new file mode 100755 index 0000000..0104b8c --- /dev/null +++ b/iros/image_gui2.py @@ -0,0 +1,187 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("--mode", choices=["live","test"], default="live") +parser.add_argument("--cloud_topic", default="/drop/points") +parser.add_argument("--plot3d", action="store_true") +args = parser.parse_args() + +""" +# how to get a pcd file +# plug asus into local computer +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("pr2_suture_scene.pcd") +""" + +import cv2 +import numpy as np +import rospy +import geometry_msgs.msg as gm +import sensor_msgs.msg as sm +import sys + +#rospy.init_node("image_gui", disable_signals = True) +rospy.init_node("image_gui") + +xyz = [] +xyz_tf = [] +rgb = [] + + +if args.mode == "test": + from jds_image_proc.pcd_io import load_xyzrgb + import openravepy + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + for i in range(5): + + xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene%s.pcd"%i) + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + #print 'xyz[0]', xyz[0] + #print 'xyz_tf[0]', xyz_tf[0] + +elif args.mode == "live": + import brett2.ros_utils as ru + + listener = ru.get_tf_listener() + + for i in range(5): + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg %s!"%i + + xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + xyz_tf.append(xyz_tf_temp) + #print 'xyz_temp', xyz_temp + + del xyz_temp + del rgb_temp + + rospy.sleep(1.0) + + #print 'xyz_tf[0]', xyz_tf[0] + +#raw_input("Press enter to continue...") + +rgb_plot = rgb[0].copy() + +#depth_plot = xyz_tf[:,:,2].astype('float') +#depth_plot[np.isnan(depth_plot)] = 0 +#depth_plot -= depth_plot.min() +#depth_plot = (depth_plot * (255 / depth_plot.max())).astype('uint8') + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +cv2.namedWindow("rgb") +rect_corners = [] +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) ## this doesn't seem to be working... + +colmin, rowmin = xy_tl +colmax, rowmax = xy_br + +row_needle = [] +col_needle = [] + +# extract depths from drawn rectangle +for i in range(5): + z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + col_needle_temp += colmin # since these indices are from small rectangle + row_needle_temp += rowmin + + row_needle.append(row_needle_temp) + col_needle.append(col_needle_temp) + + del z_rectangle + del col_needle_temp + del row_needle_temp + + +xneedle = np.zeros((5)) +yneedle = np.zeros((5)) +zneedle = np.zeros((5)) + +for i in range(5): + xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + +print "xyz needle point %s"%i, xneedle, yneedle, zneedle + +ind = np.argmax(zneedle) + +max_needle = [] +max_needle.append(xneedle[ind]) +max_needle.append(yneedle[ind]) +max_needle.append(zneedle[ind]) + +#rgb_plot_best = rgb[ind].copy() +#cv2.namedWindow("best_rgb") +#cv2.imshow("best_rgb", rgb_plot_best) + +cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) ## this doesn't seem to be working... + +save needle location to np file +np.save('/home/mallory/mallory_workspace/suturing/python/iros/needleLoc.npy', np.array(max_needle)) +print 'needle location saved!' + + +# plot the point cloud with a circle around "highest" point +if args.plot3d: + from mayavi import mlab + x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + mlab.show() +#else: + #rospy.sleep(1) + #sys.exit() + #while True: + # cv2.imshow("rgb",rgb_plot) + # cv2.imshow("depth", depth_plot) + # cv2.waitKey(10) + +raw_input("press enter when done") +#rospy.spin() diff --git a/iros/make_suture_library.py b/iros/make_suture_library.py new file mode 100644 index 0000000..8efc9e0 --- /dev/null +++ b/iros/make_suture_library.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python + +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("task") +parser.add_argument("part_name") +args = parser.parse_args() + + +import lfd +from lfd import bag_proc as bp +import rosbag +import os.path as osp +from jds_utils.yes_or_no import yes_or_no +import os, sys +import yaml +import h5py + +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") +task_file = osp.join(IROS_DATA_DIR, "suture_demos2.yaml") +with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: + task_info = yaml.load(fh) + + +db_file = osp.join(IROS_DATA_DIR, task_info[args.task][args.part_name]["db_file"]) +print 'Writing to', db_file +if osp.exists(db_file): + if yes_or_no(db_file + ' already exists. Overwrite?'): + os.remove(db_file) + else: + print 'Aborting.' + sys.exit(1) + +task_lib = h5py.File(db_file, mode="w") +link_names = ["r_gripper_tool_frame", "l_gripper_tool_frame"] + +for (i_demo,bag_file) in enumerate(task_info[args.task][args.part_name]["demo_bag"]): + bag = rosbag.Bag(bag_file) + demo_segs = bp.create_segments(bag, link_names) + + for (i_seg,demo_seg) in enumerate(demo_segs): + #if demo_seg["done"]: + # path = "%.2i.done"%i_demo + #else: + path = "%.2i.%.2i"%(i_demo, i_seg) + demo_seg["demo_index"] = i_demo + demo_seg["seg_index"] = i_seg + bp.dict_to_hdf(task_lib, demo_seg, path) + + diff --git a/iros/process_suture_bag.py b/iros/process_suture_bag.py new file mode 100644 index 0000000..d1da7cc --- /dev/null +++ b/iros/process_suture_bag.py @@ -0,0 +1,266 @@ +#!/usr/bin/env python + +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("task") +parser.add_argument("part_name") +args = parser.parse_args() + + +import lfd +import iros +from lfd import bag_proc as bp +import rosbag +import rospy +import os.path as osp +from jds_utils.yes_or_no import yes_or_no +import brett2.ros_utils as ru +from jds_utils.colorize import colorize +import os, sys +import yaml +import h5py +import numpy as np +import cv2 +import simple_clicker as sc + +# find data files, files to save to +SAVE_TRAJ = False +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") + +task_file = osp.join(IROS_DATA_DIR, "suture_demos.yaml") + +with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: + task_info = yaml.load(fh) + +bag = task_info[args.task][args.part_name]["demo_bag"] +bag = rosbag.Bag(bag) + +jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) +kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) +pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) + +### extract kinematics info from bag +def extract_kinematics(np_file, info): + + for i in range(len(info)): + savefile = np_file + 'seg%s'%i + print 'Writing to', savefile + + if osp.exists(savefile + '_larm.npy'): + if yes_or_no(savefile + ' already exists. Overwrite?'): + os.remove(savefile + '_larm.npy') + os.remove(savefile + '_rarm.npy') + os.remove(savefile + '_lgrip.npy') + os.remove(savefile + '_rgrip.npy') + else: + print 'Aborting...' + sys.exit(1) + + larm = info[i]["leftarm"] + rarm = info[i]["rightarm"] + lgrip = info[i]["l_gripper_joint"] + rgrip = info[i]["r_gripper_joint"] + + np.save(savefile + '_larm.npy' , np.array(larm)) + np.save(savefile + '_rarm.npy' , np.array(rarm)) + np.save(savefile + '_lgrip.npy' , np.array(lgrip)) + np.save(savefile + '_rgrip.npy' , np.array(rgrip)) + + print 'saved all' + + +# creates the text for the yaml file for the demo +def get_new_demo_entry_text(segment, hole1, hole2, tcut, mcut, bcut, needle): + + new_entry_text = """ + segment%(seg_num)s: + hole1 center: %(hole1)s + hole2 center: %(hole2)s + top of cut: %(tcut)s + middle of cut: %(mcut)s + bottom of cut: %(bcut)s + needle tip: %(needle)s +""" % dict( + seg_num = segment, + hole1 = hole1, + hole2 = hole2, + tcut = tcut, + mcut = mcut, + bcut = bcut, + needle = needle, + ) + + return new_entry_text + + +# appends the entry text to the yaml file +def add_new_entry_to_yaml_file(data_dir, new_entry_text): + demofile = open(data_dir + "/suture_demos.yaml", "a") + demofile.write(new_entry_text) + demofile.flush() + os.fsync(demofile.fileno()) + demofile.close() + +print 'getting bag info...' + +button_presses = bp.get_button_presses(bag) +all_times = bp.read_button_presses(button_presses) +start_times = [t for t, action in all_times if action == 'start'] +stop_times = [t for t, action in all_times if action == 'stop'] +look_times = [t for t, action in all_times if action == 'look'] + +assert len(start_times) == len(stop_times) +SEGNUM = len(look_times) + + +if SAVE_TRAJ == True: + raw_input("press enter to extract kinematics info from bag file") + + link_names = ["r_gripper_tool_frame", "l_gripper_tool_frame"] + kinematics_info = bp.extract_kinematics_from_bag(bag, link_names) + times = kinematics_info["time"] + + start_inds = np.searchsorted(times, start_times) + stop_inds = np.searchsorted(times, stop_times) + + forced_segs_info = [] + for start_ind, stop_ind in zip(start_inds, stop_inds): + seg = bp.extract_segment(kinematics_info, start_ind, stop_ind) + forced_segs_info.append(seg) + + extract_kinematics(jtf, forced_segs_info) + + raw_input("extracted segments. press enter to continue") + +# determine which keypoints matter for each segment based on user input +print 'getting all look_time point clouds...' +look_clouds = bp.get_transformed_clouds(bag, look_times) +print 'saving look_time point clouds...' +import cloudprocpy +#grabber=cloudprocpy.CloudGrabber() +#for i in range(SEGNUM): + #xyzrgb = look_clouds[i].getXYZRGB() + #look_clouds[i].save("suture_scene(look_cloud%s).pcd"%i) +#raw_input("saved point clouds. press enter to continue") + +window_name = "Find Keypoints" + +keypoints_locations = [] +keypoints_names = [] + +for s in range(SEGNUM): + print 'look time for segment %s'%s + keypt_names = [] + keypt_locs = [] + + while (True): + sc.show_pointclouds(look_clouds[s], window_name) + kp = raw_input('which key points are important for this segment? choices are: {hc, ne, nt, ntt}. (please only enter one key point at a time): ') + + if kp not in ['hc', 'ne', 'nt', 'ntt']: + print 'incorrect input. try again!' + continue + + elif kp == 'hc': + look_for_holecut_times = [] + look_for_holecut_times.append(look_times[s]) + print colorize("Looking for Holes and Cut...", 'green', bold=True) + + xyz_tf = look_clouds[s][0].copy() + rgb_plot = look_clouds[s][1].copy() + np.save(pcf + 'seg%s_xyz_tf.npy'%s, xyz_tf) + np.save(pcf + 'seg%s_rgb_plot.npy'%s, rgb_plot) + + hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc = sc.find_holes_cut(xyz_tf, rgb_plot, window_name) + keypt_locs.append(hole1_loc) + keypt_locs.append(hole2_loc) + keypt_locs.append(tcut_loc) + keypt_locs.append(mcut_loc) + keypt_locs.append(bcut_loc) + keypt_names.append('holes_and_cut') + + del look_for_holecut_times + + elif kp == 'ne': + xyz_tfs = [] + rgb_plots = [] + look_for_needle_times = [] + num_clouds = 15 + + for t in range(num_clouds): + look_for_needle_times.append(look_times[s] + t) + + print colorize("Looking for Needle End...", 'green', bold=True) + print 'getting the needle point clouds...' + needle_clouds = bp.get_transformed_clouds(bag, look_for_needle_times) + + for i in range(num_clouds): + xyz_tfs.append(needle_clouds[i][0].copy()) + rgb_plots.append(needle_clouds[i][1].copy()) + np.save(pcf + 'seg%s_xyz_tfs.npy'%s, xyz_tfs) + np.save(pcf + 'seg%s_rgb_plots.npy'%s, rgb_plots) + + needle_loc = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + + keypt_locs.append(needle_loc) + keypt_names.append('needle_end') + + del look_for_needle_times + del xyz_tfs + del rgb_plots + + elif kp in ['nt', 'ntt']: + xyz_tfs = [] + rgb_plots = [] + look_for_needle_times = [] + num_clouds = 10 + + for t in range(num_clouds): + look_for_needle_times.append(look_times[s] + t) + + print colorize("Looking for Needle Tip...", 'green', bold=True) + print 'getting the needle point clouds...' + needle_clouds = bp.get_transformed_clouds(bag, look_for_needle_times) + + for i in range(num_clouds): + xyz_tfs.append(needle_clouds[i][0].copy()) + rgb_plots.append(needle_clouds[i][1].copy()) + np.save(pcf + 'seg%s_xyz_tfs.npy'%s, xyz_tfs) + np.save(pcf + 'seg%s_rgb_plots.npy'%s, rgb_plots) + + needle_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) + + if kp == 'nt': + keypt_locs.append(needle_loc) + keypt_names.append('needle_tip') + else: + keypt_locs.append((0,0,0)) + keypt_names.append('empty') + np.save(kpf + '_needle_world_loc.npy', needle_loc) + + del look_for_needle_times + del xyz_tfs + del rgb_plots + + if yes_or_no('Key point %s saved for this segment. Is there another key point for this segment?'%kp): + continue + else: + keypoints_locations.append(keypt_locs) + keypoints_names.append(keypt_names) + print 'keypoints_names', keypoints_names + del keypt_locs + del keypt_names + break + + +raw_input("Finished processing point clouds. Press enter to save key points to numpy file") +np.save(kpf + '_keypoints.npy', keypoints_locations) +np.save(kpf + '_keypoints_names.npy', keypoints_names) + + +#raw_input("press enter to add new entry to yaml file") + +#entry = get_new_demo_entry_text(i, hole1_tracker[i], hole2_tracker[i], tcut_tracker[i], mcut_tracker[i], bcut_tracker[i], needle_tracker[i]) +#add_new_entry_to_yaml_file(IROS_DATA_DIR, str(SEGNUM)) + +raw_input("press enter to finish") diff --git a/iros/simple_clicker.py b/iros/simple_clicker.py new file mode 100644 index 0000000..c4095fa --- /dev/null +++ b/iros/simple_clicker.py @@ -0,0 +1,305 @@ + +import cv2 +import numpy as np +import sys + +from jds_utils.colorize import colorize + + +def show_pointclouds(clouds, window_name): + nc = len(clouds) + + if nc == 2: + rgb_plot = clouds[1].copy() + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + else: + rgb_plot_multi = [] + for i in range(nc): + rgb_plot_multi.append(clouds[i][1].copy()) + cv2.imshow(window_name, rgb_plot_multi[i]) + cv2.waitKey(100) + +######################################### +### find holes and cut +######################################### +def find_holes_cut(xyz_tf, rgb_plot, window_name): + ### clicking set-up + class GetClick: + x = None + y = None + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.x = x + self.y = y + self.xy = (x,y) + self.done = True + + + hole1_center = [] + hole2_center = [] + xy_t = [] + xy_m = [] + xy_b = [] + + print colorize("click on the centers of the two relevant holes", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + if i == 1: + hole1_center.append(gc.x) + hole1_center.append(gc.y) + else: + hole2_center.append(gc.x) + hole2_center.append(gc.y) + + cv2.circle(rgb_plot, (hole1_center[0], hole1_center[1]), 5, (0, 0, 255), -1) + cv2.circle(rgb_plot, (hole2_center[0], hole2_center[1]), 5, (0, 0, 255), -1) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + + x_hole1, y_hole1, z_hole1 = xyz_tf[hole1_center[1], hole1_center[0]] + x_hole2, y_hole2, z_hole2 = xyz_tf[hole2_center[1], hole2_center[0]] + + print 'hole1 3d location', x_hole1, y_hole1, z_hole1 + print 'hole2 3d location', x_hole2, y_hole2, z_hole2 + + hole1_loc = (x_hole1, y_hole1, z_hole1) + hole2_loc = (x_hole2, y_hole2, z_hole2) + + + ### find cut + print colorize("click at the top of the cut line", 'red', bold=True) + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + xy_t.append(gc.x) + xy_t.append(gc.y) + + print colorize("now click the middle of the cut line", 'red', bold=True) + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + xy_m.append(gc.x) + xy_m.append(gc.y) + + print colorize("now click the bottom of the cut line", 'red', bold=True) + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + xy_b.append(gc.x) + xy_b.append(gc.y) + + x_tcut, y_tcut, z_tcut = xyz_tf[xy_t[1], xy_t[0]] + x_mcut, y_mcut, z_mcut = xyz_tf[xy_m[1], xy_m[0]] + x_bcut, y_bcut, z_bcut = xyz_tf[xy_b[1], xy_b[0]] + tcut_loc = (x_tcut, y_tcut, z_tcut) + mcut_loc = (x_mcut, y_mcut, z_mcut) + bcut_loc = (x_bcut, y_bcut, z_bcut) + + cv2.line(rgb_plot, tuple(xy_t), tuple(xy_m), (0, 255, 0), 2) + cv2.line(rgb_plot, tuple(xy_m), tuple(xy_b), (0, 255, 0), 2) + + cv2.circle(rgb_plot, (xy_t[0], xy_t[1]), 5, (0, 0, 255), -1) + cv2.circle(rgb_plot, (xy_m[0], xy_m[1]), 5, (0, 0, 255), -1) + cv2.circle(rgb_plot, (xy_b[0], xy_b[1]), 5, (0, 0, 255), -1) + + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + + print 'cut top 3d location', x_tcut, y_tcut, z_tcut + print 'cut middle cut 3d location', x_mcut, y_mcut, z_mcut + print 'cut bottom 3d location', x_bcut, y_bcut, z_bcut + + return hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc + + +######################################### +### find needle +######################################### +def find_needle_tip(xyz_tfs, rgb_plots, window_name): + + ### clicking set-up + class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + + #cv2.namedWindow(window_name) + + needle_rect_corners = [] + nc = len(xyz_tfs) + rgb_plot = rgb_plots[0].copy() + + print colorize("click at the corners of a rectangle which encompasses the needle tip", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + needle_rect_corners.append(gc.xy) + + xy_tl = np.array(needle_rect_corners).min(axis=0) + xy_br = np.array(needle_rect_corners).max(axis=0) + + cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + + colmin, rowmin = xy_tl + colmax, rowmax = xy_br + + row_needle = [] + col_needle = [] + + xneedle = np.zeros((nc)) + yneedle = np.zeros((nc)) + zneedle = np.zeros((nc)) + + # extract depths from drawn rectangle + for i in range(nc): + + z_rectangle = xyz_tfs[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + col_needle_temp += colmin # since these indices are from small rectangle + row_needle_temp += rowmin + + col_needle.append(col_needle_temp) + row_needle.append(row_needle_temp) + + xneedle[i], yneedle[i], zneedle[i] = xyz_tfs[i][row_needle_temp, col_needle_temp] + + del z_rectangle + + ind = np.argmax(zneedle) + + max_needle = [] + max_needle.append(xneedle[ind]) + max_needle.append(yneedle[ind]) + max_needle.append(zneedle[ind]) + + rgb_plot_best = rgb_plots[ind].copy() + cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + + print 'needle tip 3d location', max_needle + + # plot the point cloud with a circle around "highest" point + #from mayavi import mlab + #x,y,z = clouds[ind][0][~np.isnan(clouds[ind][0][:,:,0])].T + #mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + #mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + #mlab.show() + + #raw_input("press enter when done looking") + + return max_needle + +######################################### +### find needle +######################################### +def find_needle_end(xyz_tfs, rgbs, window_name): + + ### clicking set-up + class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + + needle_rect_corners = [] + nc = len(xyz_tfs) + rgb_plot = rgbs[0].copy() + print colorize("click at the corners of a rectangle which encompasses the end of the needle", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback(window_name, gc.callback) + while not gc.done: + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(10) + needle_rect_corners.append(gc.xy) + + xy_tl = np.array(needle_rect_corners).min(axis=0) + xy_br = np.array(needle_rect_corners).max(axis=0) + + cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + + colmin, rowmin = xy_tl + colmax, rowmax = xy_br + + high_red_xyz = [] + high_red_rc = [] + + # extract depths from drawn rectangle + + FOAM_HEIGHT = .85 + + for i in range(nc): + + z_rectangle = xyz_tfs[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + + hsv = cv2.cvtColor(rgbs[i][rowmin:rowmax, colmin:colmax].copy(),cv2.COLOR_BGR2HSV) + h=hsv[:,:,0] + s=hsv[:,:,1] + v=hsv[:,:,2] + + color_mask = ((h<10) | (h>150)) & (s > 100) & (v > 100) + height_mask = z_rectangle > FOAM_HEIGHT + .05 + + total_mask = color_mask & height_mask + print "%ith image has %i valid points (above foam and red)"%(i, total_mask.sum()) + + high_red_xyz.extend(xyz_tfs[i][rowmin:rowmax, colmin:colmax, :][total_mask]) + + xyz_avg = np.median(high_red_xyz,axis=0) + + #from jds_image_proc.pcl_utils import xyz2uv + #row, col = xyz2uv(xyz_avg).astype('int')[0] + + #rgb_plot_best = rgbs[0].copy() + #cv2.circle(rgb_plot_best, (col, row), 3, (255, 0, 0), 2) + #cv2.imshow(window_name, rgb_plot_best) + #cv2.waitKey(100) + + # plot the point cloud with a circle around "highest" point + #from mayavi import mlab + #x,y,z = clouds[ind][0][~np.isnan(clouds[ind][0][:,:,0])].T + #mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + #mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + #mlab.show() + + #raw_input("press enter when done looking") + + print 'Needle end location', xyz_avg + + return xyz_avg \ No newline at end of file diff --git a/iros/simple_clicker_dev.py b/iros/simple_clicker_dev.py new file mode 100644 index 0000000..9997cb7 --- /dev/null +++ b/iros/simple_clicker_dev.py @@ -0,0 +1,293 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("mode", choices=["live","test"], default="live") +parser.add_argument("object", choices=["holes_cut", "needle"]) +parser.add_argument("cloud_topic", default="/drop/points") +parser.add_argument("plot3d", action="store_true") +args = parser.parse_args() + + +# how to get a pcd file +#import cloudprocpy +#grabber=cloudprocpy.CloudGrabber() +#xyzrgb = grabber.getXYZRGB() +#xyzrgb.save("pr2_suture_scene(needle_finding).pcd") + +#raw_input("got point cloud. press enter to continue") + +import cv2 +import numpy as np +import rospy +import openravepy +import sys + +import geometry_msgs.msg as gm +import sensor_msgs.msg as sm +from jds_image_proc.pcd_io import load_xyzrgb +from jds_utils.colorize import colorize +import brett2.ros_utils as ru + +rospy.init_node("image_gui") + +######################################### +### find holes and cut +######################################### +def find_holes_cut(plot): + + hole1_center = [] + hole2_center = [] + cut_endpoints = [] + + print colorize("click on the centers of the two relevant holes", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + if i == 1: + hole1_center.append(gc.x) + hole1_center.append(gc.y) + else: + hole2_center.append(gc.x) + hole2_center.append(gc.y) + + cv2.circle(plot, (hole1_center[0], hole1_center[1]), 10, (255, 0, 0), 2) + cv2.circle(plot, (hole2_center[0], hole2_center[1]), 10, (255, 0, 0), 2) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + x_hole1, y_hole1, z_hole1 = xyz_tf[hole1_center[0], hole1_center[1]] + x_hole2, y_hole2, z_hole2 = xyz_tf[hole2_center[0], hole2_center[1]] + + print 'hole1 3d location', x_hole1, y_hole1, z_hole1 + print 'hole2 3d location', x_hole2, y_hole2, z_hole2 + + raw_input("press enter to continue") + + ### find cut + + print colorize("click at the top and bottom of the cut line", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + cut_endpoints.append(gc.xy) + + xy_t = np.array(cut_endpoints).min(axis=0) + xy_b = np.array(cut_endpoints).max(axis=0) + + cv2.line(plot, tuple(xy_t), tuple(xy_b), (0, 255, 0), 2) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + x1_cut, y1_cut, z1_cut = xyz_tf[tuple(xy_t)] + x2_cut, y2_cut, z2_cut = xyz_tf[tuple(xy_b)] + + + #midpoint of line + mid_y = (xy_t[1] - xy_b[1])/2 + mid_plot_x = xy_b[0] + mid_plot_y = xy_t[1] - mid_y + + cv2.circle(plot, (mid_plot_x, mid_plot_y), 5, (0, 0, 255), -1) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + mid_ptx, mid_pty, mid_ptz = xyz_tf[mid_plot_x, mid_plot_y] + + print 'top of cut 3d', x1_cut, y1_cut, z1_cut + print 'bottom of cut 3d', x2_cut, y2_cut, z2_cut + print 'middle of cut 3d', mid_ptx, mid_pty, mid_ptz + + raw_input("press enter to continue") + + +######################################### +### find needle +######################################### +def find_needle(plot): + + needle_rect_corners = [] + + print colorize("click at the corners of a rectangle which encompasses the needle tip", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + needle_rect_corners.append(gc.xy) + + xy_tl = np.array(needle_rect_corners).min(axis=0) + xy_br = np.array(needle_rect_corners).max(axis=0) + + cv2.rectangle(plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + colmin, rowmin = xy_tl + colmax, rowmax = xy_br + + row_needle = [] + col_needle = [] + + # extract depths from drawn rectangle + for i in range(3): + z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + col_needle_temp += colmin # since these indices are from small rectangle + row_needle_temp += rowmin + + row_needle.append(row_needle_temp) + col_needle.append(col_needle_temp) + + del z_rectangle + del col_needle_temp + del row_needle_temp + + + xneedle = np.zeros((3)) + yneedle = np.zeros((3)) + zneedle = np.zeros((3)) + + for i in range(3): + xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + + print "xyz needle point %s"%i, xneedle, yneedle, zneedle + + ind = np.argmax(zneedle) + + max_needle = [] + max_needle.append(xneedle[ind]) + max_needle.append(yneedle[ind]) + max_needle.append(zneedle[ind]) + + cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(100) + + # plot the point cloud with a circle around "highest" point + from mayavi import mlab + x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + mlab.show() + + raw_input("press enter when done") + +######################################### +### clicking set-up +######################################### + +class GetClick: + x = None + y = None + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.x = x + self.y = y + self.xy = (x,y) + self.done = True + +cv2.namedWindow("rgb") + +xyz = [] +xyz_tf = [] +rgb = [] + +if args.object == "needle": + if args.mode == "test": + for i in range(3): + xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene(needle_finding)%s.pcd"%i) + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + + elif args.mode == "live": + listener = ru.get_tf_listener() + for i in range(5): + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg %s!"%i + + xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + rospy.sleep(1.0) + + rgb_plot = rgb[0].copy() + find_needle(rgb_plot) + +elif args.object == "holes_cut": + if args.mode == "test": + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + xyz, rgb = load_xyzrgb("suture_scene(findholescut).pcd") + + xyz1 = np.c_[xyz.reshape(-1,3), np.ones((xyz.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf = xyz1_tf[:,:3].reshape(xyz.shape) + xyz_tf[np.isnan(xyz_tf)] = -2 + + elif args.mode == "live": + listener = ru.get_tf_listener() + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + + xyz, rgb = ru.pc2xyzrgb(msg) + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz) + rgb.append(rgb) + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf[np.isnan(xyz_tf)] = -2 + + rgb_plot = rgb.copy() + + find_holes_cut(rgb_plot) + + + From d81d3b4ce98821a2187aa3cca655133a09f79434 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Thu, 7 Mar 2013 16:44:17 -0800 Subject: [PATCH 05/26] suture update --- iros/circle_finder.py | 251 ++++++++++++++++++++++++++++++++++++ iros/execute_suture_traj.py | 87 +++++++------ 2 files changed, 298 insertions(+), 40 deletions(-) create mode 100644 iros/circle_finder.py diff --git a/iros/circle_finder.py b/iros/circle_finder.py new file mode 100644 index 0000000..b3102e3 --- /dev/null +++ b/iros/circle_finder.py @@ -0,0 +1,251 @@ +#import argparse +#parser = argparse.ArgumentParser() +#parser.add_argument("--mode", choices=["live","test"], default="live") +#parser.add_argument("--plot3d", action="store_true") +#args = parser.parse_args() + +""" +# how to get a pcd file +# plug asus into local computer +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("pr2_suture_scene.pcd") +""" + +#import cv2 +#import numpy as np +#import rospy +#import geometry_msgs.msg as gm +#import sensor_msgs.msg as sm +#import sys + +#rospy.init_node("image_gui", disable_signals = True) +#rospy.init_node("image_gui") + +#xyz = [] +#xyz_tf = [] +#rgb = [] + + +#if args.mode == "test": + #from jds_image_proc.pcd_io import load_xyzrgb + #import openravepy + + #env = openravepy.Environment() + #env.Load("robots/pr2-beta-static.zae") + #robot = env.GetRobots()[0] + #robot.SetDOFValues([1.5], [14]) + #hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + #for i in range(5): + + #xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene%s.pcd"%i) + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + #xyz1_tf = np.dot(xyz1, hmat.T) + #xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + #xyz_tf.append(xyz_tf_temp) + + #del xyz_temp + #del rgb_temp + + ##print 'xyz[0]', xyz[0] + ##print 'xyz_tf[0]', xyz_tf[0] + +#elif args.mode == "live": + #import brett2.ros_utils as ru + + #listener = ru.get_tf_listener() + + #for i in range(5): + #print "waiting for messages on cloud topic %s"%args.cloud_topic + #msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + #print "got msg %s!"%i + + #xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + #if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + #xyz_tf.append(xyz_tf_temp) + ##print 'xyz_temp', xyz_temp + + #del xyz_temp + #del rgb_temp + + #rospy.sleep(1.0) + + ##print 'xyz_tf[0]', xyz_tf[0] + +#raw_input("Press enter to continue...") + + +import cv2 +import math +import numpy as np +from jds_image_proc.pcd_io import load_xyzrgb + +cv2.namedWindow("rgb") + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +xyz, rgb = load_xyzrgb("suture_scene(findholescut)0.pcd") + +#orig = cv2.imread("c.jpg") +#img = orig.copy() +img = rgb.copy() + +rect_corners = [] + +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", img) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) +cv2.imshow("rgb", img) +cv2.waitKey(100) + +colmin, rowmin = xy_tl +colmax, rowmax = xy_br + +h, w = img.shape[:2] +#print 'h,w', h, w +new_img = img[rowmin:rowmax , colmin:colmax] +new_img2 = cv2.cvtColor(new_img, cv2.COLOR_BGR2GRAY) +cv2.namedWindow("rgb2") +cv2.imshow("rgb2", new_img) + +#raw_input("Press enter to continue...") + +d_red = cv2.cv.RGB(150, 55, 65) +l_red = cv2.cv.RGB(250, 200, 200) + +detector = cv2.FeatureDetector_create('MSER') +fs = detector.detect(new_img2) +fs.sort(key = lambda x: -x.size) + +def supress(x): + for f in fs: + distx = f.pt[0] - x.pt[0] + disty = f.pt[1] - x.pt[1] + dist = math.sqrt(distx*distx + disty*disty) + print 'f.size', f.size + print 'x.size', x.size + print 'dist', dist + if (f.size > x.size) and (dist < f.size/2): + print 'f.size', f.size + print 'x.size', x.size + print 'dist', dist + return True + + +sfs = [x for x in fs if not supress(x)] + + +for f in sfs: + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), l_red, 1, cv2.CV_AA) + +h, w = new_img.shape[:2] +#vis = np.zeros((h, w*2+5), np.uint8) +vis = np.zeros((h, w), np.uint8) +vis = cv2.cvtColor(vis, cv2.COLOR_GRAY2BGR) +vis[:h, :w] = new_img +#vis[:h, w+5:w*2+5] = new_img + +cv2.imshow("image", vis) +#cv2.imwrite("c_o.jpg", vis) +cv2.waitKey() +cv2.destroyAllWindows() + + + + + + + + +#row_needle = [] +#col_needle = [] + +## extract depths from drawn rectangle +#for i in range(5): + #z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + #row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + #col_needle_temp += colmin # since these indices are from small rectangle + #row_needle_temp += rowmin + + #row_needle.append(row_needle_temp) + #col_needle.append(col_needle_temp) + + #del z_rectangle + #del col_needle_temp + #del row_needle_temp + + +#xneedle = np.zeros((5)) +#yneedle = np.zeros((5)) +#zneedle = np.zeros((5)) + +#for i in range(5): + #xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + +#print "xyz needle point %s"%i, xneedle, yneedle, zneedle + +#ind = np.argmax(zneedle) + +#max_needle = [] +#max_needle.append(xneedle[ind]) +#max_needle.append(yneedle[ind]) +#max_needle.append(zneedle[ind]) + +##rgb_plot_best = rgb[ind].copy() +##cv2.namedWindow("best_rgb") +##cv2.imshow("best_rgb", rgb_plot_best) + +#cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) ## this doesn't seem to be working... + +##save needle location to np file +#np.save('/home/mallory/mallory_workspace/suturing/python/iros/needleLoc.npy', np.array(max_needle)) +#print 'needle location saved!' + + +# plot the point cloud with a circle around "highest" point +#if args.plot3d: + #from mayavi import mlab + #x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + #mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + #mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + #mlab.show() +#else: + #rospy.sleep(1) + #sys.exit() + #while True: + # cv2.imshow("rgb",rgb_plot) + # cv2.imshow("depth", depth_plot) + # cv2.waitKey(10) + +#raw_input("press enter when done") diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index c4b0beb..73c7c1e 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -200,8 +200,6 @@ def binarize_gripper(angle): return traj_segments def get_holes_cut_cloud(listener): - print colorize("Key points from demo are: Holes and Cut. Looking for Holes and Cut now...", 'green', bold=True) - print "waiting for messages on cloud topic %s"%args.cloud_topic msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) print "got msg!" @@ -227,8 +225,6 @@ def get_holes_cut_cloud(listener): return xyz_tf, rgb_plot def get_needle_clouds(listener): - print colorize("Key points from demo are: Needle. Looking for Needle now...", 'green', bold=True) - xyz_tfs = [] rgb_plots = [] num_clouds = 30 @@ -245,7 +241,7 @@ def get_needle_clouds(listener): if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - xyz_tf[np.isnan(xyz_tf)] = -2 + #xyz_tf[np.isnan(xyz_tf)] = -2 xyz_tfs.append(xyz_tf) rgb_plots.append(rgb) @@ -301,66 +297,77 @@ def keyfunc(fname): num_kps = len(demo_keypts_names[s]) exec_keypts = [] - if num_kps != 1: - print 'number of keypoints yet not supported! aborting...' - sys.exit(1) - for k in range(num_kps): - if demo_keypts_names[s][k] == 'holes_and_cut': + print colorize("Key point from demo is: " + demo_keypts_names[s][k] + ". Looking for this key point now...", 'green', bold=True) + + if demo_keypts_names[s][k] in ['left_hole', 'right_hole']: if args.cloud_topic == 'test': - xyz_tf = np.load(pcf + 'seg%s_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_rgb_plot.npy'%s) + if demo_keypts_names[s][k] == 'left_hole': + xyz_tf = np.load(pcf + 'seg%s_lh_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_lh_rgb_pl.npy'%s) + else: + xyz_tf = np.load(pcf + 'seg%s_rh_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_rh_rgb_pl.npy'%s) else: xyz_tf, rgb_plot = get_holes_cut_cloud(listener) - hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc = sc.find_holes_cut(xyz_tf, rgb_plot, window_name) - - exec_keypts.append(hole1_loc) - exec_keypts.append(hole2_loc) + hole_loc = sc.find_hole(demo_keypts_names[s][k], xyz_tf, rgb_plot, window_name) + exec_keypts.append(hole_loc) + + elif demo_keypts_names[s][k] == 'cut': + if args.cloud_topic == 'test': + xyz_tf = np.load(pcf + 'seg%s_ct_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_ct_rgb_pl.npy'%s) + else: + xyz_tf, rgb_plot = get_holes_cut_cloud(listener) + + tcut_loc, mcut_loc, bcut_loc = sc.find_cut(xyz_tf, rgb_plot, window_name) exec_keypts.append(tcut_loc) exec_keypts.append(mcut_loc) exec_keypts.append(bcut_loc) elif demo_keypts_names[s][k] == 'needle_end': if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + xyz_tfs = np.load(pcf + 'seg%s_ne_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_ne_rgb_pls.npy'%s) else: xyz_tfs, rgb_plots = get_needle_clouds(listener) + nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) exec_keypts.append(nl) - elif demo_keypts_names[s][k] == 'needle_tip': - if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) - else: - xyz_tfs, rgb_plots = get_needle_clouds(listener) - nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - exec_keypts.append(nl) + elif demo_keypts_names[s][k] in ['needle_tip', 'empty']: - elif demo_keypts_names[s][k] == 'empty': if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + if demo_keypts_names[s][k] == 'needle_tip': + xyz_tfs = np.load(pcf + 'seg%s_nt_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_nt_rgb_pls.npy'%s) + else: + xyz_tfs = np.load(pcf + 'seg%s_ntt_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_ntt_rgb_pls.npy'%s) else: xyz_tfs, rgb_plots = get_needle_clouds(listener) - exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - exec_keypts.append((0,0,0)) + + nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) + + if demo_keypts_names[s][k] == 'empty': + exec_needle_tip_loc = nl + exec_keypts.append((0,0,0)) + else: + exec_keypts.append(nl) - #print 'exec_keypts', exec_keypts demopoints_m3 = np.array(demo_keypts[s]) newpoints_m3 = np.array(exec_keypts) + del exec_keypts + if args.mode in ["gazebo", "reality"]: handles = [] - pose_array = conversions.array_to_pose_array(demopoints_m3, '/base_footprint') + pose_array = conversions.array_to_pose_array(demopoints_m3, 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.02,type=ru.Marker.CUBE_LIST)) - pose_array = conversions.array_to_pose_array(newpoints_m3, '/base_footprint') + pose_array = conversions.array_to_pose_array(newpoints_m3, 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.02,type=ru.Marker.CUBE_LIST)) - - del exec_keypts from lfd import registration f = registration.ThinPlateSpline() @@ -400,14 +407,14 @@ def keyfunc(fname): if args.mode in ["gazebo", "reality"]: - pose_array = conversions.array_to_pose_array(np.array(left_hmats_old)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(left_hmats_old)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(right_hmats_old)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(right_hmats_old)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(left_hmats)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(left_hmats)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(right_hmats)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(right_hmats)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) From f86e0ff4296b4eeacf6a041fcd561c2be63c7e82 Mon Sep 17 00:00:00 2001 From: Mallory Date: Thu, 7 Mar 2013 16:55:29 -0800 Subject: [PATCH 06/26] suture updates --- iros/circle_finder.py | 251 ++++++++++++++++++++++++++++++++++++ iros/execute_suture_traj.py | 87 +++++++------ 2 files changed, 298 insertions(+), 40 deletions(-) create mode 100644 iros/circle_finder.py diff --git a/iros/circle_finder.py b/iros/circle_finder.py new file mode 100644 index 0000000..b3102e3 --- /dev/null +++ b/iros/circle_finder.py @@ -0,0 +1,251 @@ +#import argparse +#parser = argparse.ArgumentParser() +#parser.add_argument("--mode", choices=["live","test"], default="live") +#parser.add_argument("--plot3d", action="store_true") +#args = parser.parse_args() + +""" +# how to get a pcd file +# plug asus into local computer +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("pr2_suture_scene.pcd") +""" + +#import cv2 +#import numpy as np +#import rospy +#import geometry_msgs.msg as gm +#import sensor_msgs.msg as sm +#import sys + +#rospy.init_node("image_gui", disable_signals = True) +#rospy.init_node("image_gui") + +#xyz = [] +#xyz_tf = [] +#rgb = [] + + +#if args.mode == "test": + #from jds_image_proc.pcd_io import load_xyzrgb + #import openravepy + + #env = openravepy.Environment() + #env.Load("robots/pr2-beta-static.zae") + #robot = env.GetRobots()[0] + #robot.SetDOFValues([1.5], [14]) + #hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + #for i in range(5): + + #xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene%s.pcd"%i) + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + #xyz1_tf = np.dot(xyz1, hmat.T) + #xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + #xyz_tf.append(xyz_tf_temp) + + #del xyz_temp + #del rgb_temp + + ##print 'xyz[0]', xyz[0] + ##print 'xyz_tf[0]', xyz_tf[0] + +#elif args.mode == "live": + #import brett2.ros_utils as ru + + #listener = ru.get_tf_listener() + + #for i in range(5): + #print "waiting for messages on cloud topic %s"%args.cloud_topic + #msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + #print "got msg %s!"%i + + #xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + #if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + #xyz_tf.append(xyz_tf_temp) + ##print 'xyz_temp', xyz_temp + + #del xyz_temp + #del rgb_temp + + #rospy.sleep(1.0) + + ##print 'xyz_tf[0]', xyz_tf[0] + +#raw_input("Press enter to continue...") + + +import cv2 +import math +import numpy as np +from jds_image_proc.pcd_io import load_xyzrgb + +cv2.namedWindow("rgb") + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +xyz, rgb = load_xyzrgb("suture_scene(findholescut)0.pcd") + +#orig = cv2.imread("c.jpg") +#img = orig.copy() +img = rgb.copy() + +rect_corners = [] + +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", img) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) +cv2.imshow("rgb", img) +cv2.waitKey(100) + +colmin, rowmin = xy_tl +colmax, rowmax = xy_br + +h, w = img.shape[:2] +#print 'h,w', h, w +new_img = img[rowmin:rowmax , colmin:colmax] +new_img2 = cv2.cvtColor(new_img, cv2.COLOR_BGR2GRAY) +cv2.namedWindow("rgb2") +cv2.imshow("rgb2", new_img) + +#raw_input("Press enter to continue...") + +d_red = cv2.cv.RGB(150, 55, 65) +l_red = cv2.cv.RGB(250, 200, 200) + +detector = cv2.FeatureDetector_create('MSER') +fs = detector.detect(new_img2) +fs.sort(key = lambda x: -x.size) + +def supress(x): + for f in fs: + distx = f.pt[0] - x.pt[0] + disty = f.pt[1] - x.pt[1] + dist = math.sqrt(distx*distx + disty*disty) + print 'f.size', f.size + print 'x.size', x.size + print 'dist', dist + if (f.size > x.size) and (dist < f.size/2): + print 'f.size', f.size + print 'x.size', x.size + print 'dist', dist + return True + + +sfs = [x for x in fs if not supress(x)] + + +for f in sfs: + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), l_red, 1, cv2.CV_AA) + +h, w = new_img.shape[:2] +#vis = np.zeros((h, w*2+5), np.uint8) +vis = np.zeros((h, w), np.uint8) +vis = cv2.cvtColor(vis, cv2.COLOR_GRAY2BGR) +vis[:h, :w] = new_img +#vis[:h, w+5:w*2+5] = new_img + +cv2.imshow("image", vis) +#cv2.imwrite("c_o.jpg", vis) +cv2.waitKey() +cv2.destroyAllWindows() + + + + + + + + +#row_needle = [] +#col_needle = [] + +## extract depths from drawn rectangle +#for i in range(5): + #z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + #row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + #col_needle_temp += colmin # since these indices are from small rectangle + #row_needle_temp += rowmin + + #row_needle.append(row_needle_temp) + #col_needle.append(col_needle_temp) + + #del z_rectangle + #del col_needle_temp + #del row_needle_temp + + +#xneedle = np.zeros((5)) +#yneedle = np.zeros((5)) +#zneedle = np.zeros((5)) + +#for i in range(5): + #xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + +#print "xyz needle point %s"%i, xneedle, yneedle, zneedle + +#ind = np.argmax(zneedle) + +#max_needle = [] +#max_needle.append(xneedle[ind]) +#max_needle.append(yneedle[ind]) +#max_needle.append(zneedle[ind]) + +##rgb_plot_best = rgb[ind].copy() +##cv2.namedWindow("best_rgb") +##cv2.imshow("best_rgb", rgb_plot_best) + +#cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) ## this doesn't seem to be working... + +##save needle location to np file +#np.save('/home/mallory/mallory_workspace/suturing/python/iros/needleLoc.npy', np.array(max_needle)) +#print 'needle location saved!' + + +# plot the point cloud with a circle around "highest" point +#if args.plot3d: + #from mayavi import mlab + #x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + #mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + #mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + #mlab.show() +#else: + #rospy.sleep(1) + #sys.exit() + #while True: + # cv2.imshow("rgb",rgb_plot) + # cv2.imshow("depth", depth_plot) + # cv2.waitKey(10) + +#raw_input("press enter when done") diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index c4b0beb..73c7c1e 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -200,8 +200,6 @@ def binarize_gripper(angle): return traj_segments def get_holes_cut_cloud(listener): - print colorize("Key points from demo are: Holes and Cut. Looking for Holes and Cut now...", 'green', bold=True) - print "waiting for messages on cloud topic %s"%args.cloud_topic msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) print "got msg!" @@ -227,8 +225,6 @@ def get_holes_cut_cloud(listener): return xyz_tf, rgb_plot def get_needle_clouds(listener): - print colorize("Key points from demo are: Needle. Looking for Needle now...", 'green', bold=True) - xyz_tfs = [] rgb_plots = [] num_clouds = 30 @@ -245,7 +241,7 @@ def get_needle_clouds(listener): if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - xyz_tf[np.isnan(xyz_tf)] = -2 + #xyz_tf[np.isnan(xyz_tf)] = -2 xyz_tfs.append(xyz_tf) rgb_plots.append(rgb) @@ -301,66 +297,77 @@ def keyfunc(fname): num_kps = len(demo_keypts_names[s]) exec_keypts = [] - if num_kps != 1: - print 'number of keypoints yet not supported! aborting...' - sys.exit(1) - for k in range(num_kps): - if demo_keypts_names[s][k] == 'holes_and_cut': + print colorize("Key point from demo is: " + demo_keypts_names[s][k] + ". Looking for this key point now...", 'green', bold=True) + + if demo_keypts_names[s][k] in ['left_hole', 'right_hole']: if args.cloud_topic == 'test': - xyz_tf = np.load(pcf + 'seg%s_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_rgb_plot.npy'%s) + if demo_keypts_names[s][k] == 'left_hole': + xyz_tf = np.load(pcf + 'seg%s_lh_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_lh_rgb_pl.npy'%s) + else: + xyz_tf = np.load(pcf + 'seg%s_rh_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_rh_rgb_pl.npy'%s) else: xyz_tf, rgb_plot = get_holes_cut_cloud(listener) - hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc = sc.find_holes_cut(xyz_tf, rgb_plot, window_name) - - exec_keypts.append(hole1_loc) - exec_keypts.append(hole2_loc) + hole_loc = sc.find_hole(demo_keypts_names[s][k], xyz_tf, rgb_plot, window_name) + exec_keypts.append(hole_loc) + + elif demo_keypts_names[s][k] == 'cut': + if args.cloud_topic == 'test': + xyz_tf = np.load(pcf + 'seg%s_ct_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + 'seg%s_ct_rgb_pl.npy'%s) + else: + xyz_tf, rgb_plot = get_holes_cut_cloud(listener) + + tcut_loc, mcut_loc, bcut_loc = sc.find_cut(xyz_tf, rgb_plot, window_name) exec_keypts.append(tcut_loc) exec_keypts.append(mcut_loc) exec_keypts.append(bcut_loc) elif demo_keypts_names[s][k] == 'needle_end': if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + xyz_tfs = np.load(pcf + 'seg%s_ne_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_ne_rgb_pls.npy'%s) else: xyz_tfs, rgb_plots = get_needle_clouds(listener) + nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) exec_keypts.append(nl) - elif demo_keypts_names[s][k] == 'needle_tip': - if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) - else: - xyz_tfs, rgb_plots = get_needle_clouds(listener) - nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - exec_keypts.append(nl) + elif demo_keypts_names[s][k] in ['needle_tip', 'empty']: - elif demo_keypts_names[s][k] == 'empty': if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_rgb_plots.npy'%s) + if demo_keypts_names[s][k] == 'needle_tip': + xyz_tfs = np.load(pcf + 'seg%s_nt_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_nt_rgb_pls.npy'%s) + else: + xyz_tfs = np.load(pcf + 'seg%s_ntt_xyz_tfs.npy'%s) + rgb_plots = np.load(pcf + 'seg%s_ntt_rgb_pls.npy'%s) else: xyz_tfs, rgb_plots = get_needle_clouds(listener) - exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - exec_keypts.append((0,0,0)) + + nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) + + if demo_keypts_names[s][k] == 'empty': + exec_needle_tip_loc = nl + exec_keypts.append((0,0,0)) + else: + exec_keypts.append(nl) - #print 'exec_keypts', exec_keypts demopoints_m3 = np.array(demo_keypts[s]) newpoints_m3 = np.array(exec_keypts) + del exec_keypts + if args.mode in ["gazebo", "reality"]: handles = [] - pose_array = conversions.array_to_pose_array(demopoints_m3, '/base_footprint') + pose_array = conversions.array_to_pose_array(demopoints_m3, 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.02,type=ru.Marker.CUBE_LIST)) - pose_array = conversions.array_to_pose_array(newpoints_m3, '/base_footprint') + pose_array = conversions.array_to_pose_array(newpoints_m3, 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.02,type=ru.Marker.CUBE_LIST)) - - del exec_keypts from lfd import registration f = registration.ThinPlateSpline() @@ -400,14 +407,14 @@ def keyfunc(fname): if args.mode in ["gazebo", "reality"]: - pose_array = conversions.array_to_pose_array(np.array(left_hmats_old)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(left_hmats_old)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(right_hmats_old)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(right_hmats_old)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (1,0,0,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(left_hmats)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(left_hmats)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) - pose_array = conversions.array_to_pose_array(np.array(right_hmats)[:,:3,3], '/base_footprint') + pose_array = conversions.array_to_pose_array(np.array(right_hmats)[:,:3,3], 'base_footprint') handles.append(rviz.draw_curve(pose_array, rgba = (0,0,1,1),width=.005,type=ru.Marker.LINE_STRIP)) From ab4508162e921c9e32619fb487f56da32e583eb7 Mon Sep 17 00:00:00 2001 From: Mallory Date: Fri, 8 Mar 2013 07:22:30 -0800 Subject: [PATCH 07/26] updates --- iros/circle_finder.py | 98 ++++++++++++++++++------------------------- 1 file changed, 41 insertions(+), 57 deletions(-) diff --git a/iros/circle_finder.py b/iros/circle_finder.py index b3102e3..6bdcaa4 100644 --- a/iros/circle_finder.py +++ b/iros/circle_finder.py @@ -1,18 +1,3 @@ -#import argparse -#parser = argparse.ArgumentParser() -#parser.add_argument("--mode", choices=["live","test"], default="live") -#parser.add_argument("--plot3d", action="store_true") -#args = parser.parse_args() - -""" -# how to get a pcd file -# plug asus into local computer -import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled -grabber=cloudprocpy.CloudGrabber() -xyzrgb = grabber.getXYZRGB() -xyzrgb.save("pr2_suture_scene.pcd") -""" - #import cv2 #import numpy as np #import rospy @@ -20,13 +5,6 @@ #import sensor_msgs.msg as sm #import sys -#rospy.init_node("image_gui", disable_signals = True) -#rospy.init_node("image_gui") - -#xyz = [] -#xyz_tf = [] -#rgb = [] - #if args.mode == "test": #from jds_image_proc.pcd_io import load_xyzrgb @@ -87,13 +65,12 @@ #raw_input("Press enter to continue...") - +import cv import cv2 import math import numpy as np from jds_image_proc.pcd_io import load_xyzrgb - -cv2.namedWindow("rgb") +from jds_utils.colorize import colorize class GetClick: xy = None @@ -107,12 +84,37 @@ def callback(self, event, x, y, flags, param): xyz, rgb = load_xyzrgb("suture_scene(findholescut)0.pcd") -#orig = cv2.imread("c.jpg") -#img = orig.copy() img = rgb.copy() +d_red = cv2.cv.RGB(150, 55, 65) +l_red = cv2.cv.RGB(250, 200, 200) +d_blue = cv2.cv.RGB(65, 55, 150) + +#minRadius = 21 +#maxRadius = 33 +#storage = cv.CreateMat(w, 1, cv.CV_32FC3) +#cv2.HoughCircles(image, method, dp, minDist[, circles[, param1[, param2[, minRadius[, maxRadius]]]]]) +#cv.HoughCircles(processed, storage, cv.CV_HOUGH_GRADIENT, 2, 32.0, HIGH, LOW) +#for i in range(0,len(np.asarray(storage))): +# cv.Circle(gray_img, ( int(np.asarray(storage)[i][0][0]), int(np.asarray(storage)[i][0][1]) ), int(np.asarray(storage)[i][0][2]), cv.CV_RGB(255, 0, 0), 2, 8, 0 ) +#cv2.HoughCircles(gray_img, int(np.asarray(storage)), cv.CV_HOUGH_GRADIENT, 1, 42, minRadius, maxRadius) + +#for i in range(0, len(np.asarray(storage))): +# print "circle #%d" %i +# radius = int(np.asarray(storage)[i][0][2]) +# x = int(np.asarray(storage)[i][0][0]) +# y = int(np.asarray(storage)[i][0][1]) +# center = (x, y) +# print 'radius', radius + +#raw_input("Press enter to continue...") + + +cv2.namedWindow("rgb") rect_corners = [] +print colorize("click at the corners of the relevant area", 'red') + for i in xrange(2): gc = GetClick() cv2.setMouseCallback("rgb", gc.callback) @@ -130,20 +132,11 @@ def callback(self, event, x, y, flags, param): colmin, rowmin = xy_tl colmax, rowmax = xy_br -h, w = img.shape[:2] -#print 'h,w', h, w new_img = img[rowmin:rowmax , colmin:colmax] -new_img2 = cv2.cvtColor(new_img, cv2.COLOR_BGR2GRAY) -cv2.namedWindow("rgb2") -cv2.imshow("rgb2", new_img) - -#raw_input("Press enter to continue...") - -d_red = cv2.cv.RGB(150, 55, 65) -l_red = cv2.cv.RGB(250, 200, 200) +gray_img = cv2.cvtColor(new_img, cv2.COLOR_BGR2GRAY) detector = cv2.FeatureDetector_create('MSER') -fs = detector.detect(new_img2) +fs = detector.detect(gray_img) fs.sort(key = lambda x: -x.size) def supress(x): @@ -151,32 +144,23 @@ def supress(x): distx = f.pt[0] - x.pt[0] disty = f.pt[1] - x.pt[1] dist = math.sqrt(distx*distx + disty*disty) - print 'f.size', f.size - print 'x.size', x.size - print 'dist', dist - if (f.size > x.size) and (dist < f.size/2): - print 'f.size', f.size - print 'x.size', x.size - print 'dist', dist + if (f.size > x.size) and (dist < f.size/2): return True sfs = [x for x in fs if not supress(x)] +print 'num circles', len(sfs) for f in sfs: - cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_red, 2, cv2.CV_AA) - cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), l_red, 1, cv2.CV_AA) - -h, w = new_img.shape[:2] -#vis = np.zeros((h, w*2+5), np.uint8) -vis = np.zeros((h, w), np.uint8) -vis = cv2.cvtColor(vis, cv2.COLOR_GRAY2BGR) -vis[:h, :w] = new_img -#vis[:h, w+5:w*2+5] = new_img - -cv2.imshow("image", vis) -#cv2.imwrite("c_o.jpg", vis) + #cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_red, 2, cv2.CV_AA) + #cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), l_red, 1, cv2.CV_AA) + if (f.size > 21) and (f.size < 33): + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(new_img, (int(f.pt[0]), int(f.pt[1])), int(f.size/2), d_blue, 1, cv2.CV_AA) + +cv2.namedWindow("rgb with circles") +cv2.imshow("rgb with circles", new_img) cv2.waitKey() cv2.destroyAllWindows() From e493c34a11c3bc1a0df25f76c0b18dc4a3b18b9f Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Fri, 8 Mar 2013 11:40:05 -0800 Subject: [PATCH 08/26] updates --- iros/execute_suture_traj.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 92b95d5..8671d8f 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -448,9 +448,9 @@ def left_ikfunc(hmat): def unwrapped_squared_dist(x_nk,y_mk): "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) - diffs_nmk[:,:,2] %= 2*np.pi - diffs_nmk[:,:,4] %= 2*np.pi - diffs_nmk[:,:,6] %= 2*np.pi + diffs_nmk[:,:,2] = diffs_nmk[:,:,2] % 2*np.pi + diffs_nmk[:,:,4] = diffs_nmk[:,:,4] % 2*np.pi + diffs_nmk[:,:,6] = diffs_nmk[:,:,6] % 2*np.pi return (diffs_nmk**2).sum(axis=2) left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, From 60e802b1e12c6d7d85a439599c90997cf9a995eb Mon Sep 17 00:00:00 2001 From: John Schulman Date: Fri, 8 Mar 2013 13:55:28 -0800 Subject: [PATCH 09/26] add optimization to simulation script --- iros/follow_pose_traj.py | 182 +++++++++++++++++++++++++++++---------- 1 file changed, 136 insertions(+), 46 deletions(-) diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py index f467fc3..2781038 100644 --- a/iros/follow_pose_traj.py +++ b/iros/follow_pose_traj.py @@ -116,6 +116,49 @@ def bad_inds(x1, t1): raise Exception("couldn't subdivide enough. something funny is going on. check oyur input data") +def follow_traj_request(robot, manip_name, new_hmats, old_joints): + n_steps = len(new_hmats) + assert len(old_joints) == n_steps + request = { + "basic_info" : { + "n_steps" : n_steps, + "manip" : manip_name, + "start_fixed" : True + }, + "costs" : [ + { + "type" : "joint_vel", + "params": {"coeffs" : [1]} + }, + { + "type" : "collision", + "params" : {"coeffs" : [10],"dist_pen" : [0.025]} + } + ], + "constraints" : [ + ], + "init_info" : { + "type":"given_traj", + "data":[x.tolist() for x in old_joints] + } + } + + poses = [openravepy.poseFromMatrix(hmat) for hmat in new_hmats] + for (i_step,pose) in enumerate(poses): + request["costs"].append( + {"type":"pose", + "params":{ + "xyz":pose[4:7].tolist(), + "wxyz":pose[0:4].tolist(), + "link":"%s_gripper_tool_frame"%manip_name[0], + "timestep":i_step + } + }) + + + + return request + ################################### ###### Load demonstration files ################################### @@ -183,6 +226,9 @@ def binarize_gripper(angle): print "trajectory broken into %i segments by gripper transitions"%len(segments) +robot.SetDOFValues(segments[0].larm_traj[0], robot.GetManipulator("leftarm").GetArmIndices()) +robot.SetDOFValues(segments[0].rarm_traj[0], robot.GetManipulator("rightarm").GetArmIndices()) + for (i,segment) in enumerate(segments): print "trajectory segment %i"%i @@ -191,6 +237,7 @@ def binarize_gripper(angle): orig_times = np.arange(len(full_traj)) ds_times, ds_traj = adaptive_resample(full_traj, tol=.025, max_change=.1) # about 2.5 degrees, 10 degrees n_steps = len(ds_traj) + #################### @@ -201,84 +248,127 @@ def binarize_gripper(angle): # let's get cartesian trajectory left_hmats = [] right_hmats = [] + saver = openravepy.RobotStateSaver(robot) for row in ds_traj: robot.SetActiveDOFValues(row) left_hmats.append(robot.GetLink("l_gripper_tool_frame").GetTransform()) right_hmats.append(robot.GetLink("r_gripper_tool_frame").GetTransform()) - + saver.Restore() + saver.Release() # now let's shift it a little for i in xrange(n_steps): - left_hmats[i][0,3] -= 0 - right_hmats[i][0,3] -= 0 + left_hmats[i][0,3] -= .02 + right_hmats[i][0,3] -= .02 ################### POSTURE_COEFF = 1 + trajoptpy.SetInteractive(False) + #def nodecost(manip, joints, step): + #robot = manip.GetRobot() + #saver = openravepy.Robot.RobotStateSaver(robot) + #robot.SetDOFValues(joints, manip.GetArmJoints(), False) + #old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] + #joint_diff = old_joints - joints + #for i in [2,4,6]: + #joint_diff[i] %= 2*np.pi + #if joint_diff[i] > np.pi: joint_diff[i] -= np.pi + #return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) + #def left_ikfunc(hmat): + #return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) # env collisions, no self / ee collisions + #def unwrapped_squared_dist(x_nk,y_mk): + #"pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" + #diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) + #diffs_nmk[:,:,2] = diffs_nmk[:,:,2] % 2*np.pi + #diffs_nmk[:,:,4] = diffs_nmk[:,:,4] % 2*np.pi + #diffs_nmk[:,:,6] = diffs_nmk[:,:,6] % 2*np.pi + #return (diffs_nmk**2).sum(axis=2) + + + #left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, + #ikfunc = left_ikfunc, + #nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), + #edgecost = unwrapped_squared_dist) + + #print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) + #def unwind_arm_traj(x_nk): + #out_nk = x_nk.copy() + #for i in [2,4,6]: + #out_nk[:,i] = np.unwrap(out_nk[:,i]) + #return out_nk + #best_left_path_before_interp = left_paths[np.argmin(left_costs)] + #best_left_path_before_interp = unwind_arm_traj(best_left_path_before_interp) + + #if len(timesteps) < n_steps: + #print "linearly interpolating the points with no soln" + #best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) + #else: best_left_path = best_left_path_before_interp + + init_traj = ds_traj[:,:7].copy() + init_traj[0] = robot.GetDOFValues(robot.GetManipulator("leftarm").GetArmIndices()) + req = follow_traj_request(robot, "leftarm", left_hmats, init_traj) + s = json.dumps(req) + prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem + result = trajoptpy.OptimizeProblem(prob) # do optimization + best_left_path = result.GetTraj() - def nodecost(manip, joints, step): - robot = manip.GetRobot() - saver = openravepy.Robot.RobotStateSaver(robot) - robot.SetDOFValues(joints, manip.GetArmJoints(), False) - old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] - joint_diff = old_joints - joints - for i in [2,4,6]: - joint_diff[i] %= 2*np.pi - if joint_diff[i] > np.pi: joint_diff[i] -= np.pi - return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) - def left_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) # env collisions, no self / ee collisions - def unwrapped_squared_dist(x_nk,y_mk): - "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" - diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) - diffs_nmk[:,:,[2,4,6]] %= 2*np.pi - return (diffs_nmk**2).sum(axis=2) - - - left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, - ikfunc = left_ikfunc, - nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), - edgecost = unwrapped_squared_dist) - - print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) - best_left_path_before_interp = left_paths[np.argmin(left_costs)] + + - if len(timesteps) < n_steps: - print "linearly interpolating the points with no soln" - best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) - else: best_left_path = best_left_path_before_interp + #def right_ikfunc(hmat): + #return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) # env collisions + self collisions - def right_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) # env collisions + self collisions + #right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, + #ikfunc = right_ikfunc, + #nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), + #edgecost = unwrapped_squared_dist) + #print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) + #best_right_path_before_interp = right_paths[np.argmin(right_costs)] + #best_left_path_before_interp = unwind_arm_traj(best_right_path_before_interp) + #if len(timesteps) < n_steps: + #print "linearly interpolating the points with no soln" + #best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) + #else: best_right_path = best_right_path_before_interp - right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, - ikfunc = right_ikfunc, - nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), - edgecost = unwrapped_squared_dist) + #im = np.zeros((len(left_hmats), 61), bool) + #for (i_step,hmat) in enumerate(left_hmats): + #solns = left_ikfunc(hmat) + #if len(solns) > 0: + #im[i_step,:][ (10*np.array(solns)[:,2]+3).astype('int') ] = 1 + #import matplotlib.pyplot as plt + #plt.imshow(im) + #plt.show() - print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) - best_right_path_before_interp = right_paths[np.argmin(right_costs)] - if len(timesteps) < n_steps: - print "linearly interpolating the points with no soln" - best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) - else: best_right_path = best_right_path_before_interp + init_traj = ds_traj[:,7:14].copy() + init_traj[0] = robot.GetDOFValues(robot.GetManipulator("rightarm").GetArmIndices()) + req = follow_traj_request(robot, "rightarm", right_hmats, init_traj) + s = json.dumps(req) + prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem + result = trajoptpy.OptimizeProblem(prob) # do optimization + best_right_path = result.GetTraj() + left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) + right_diffs = np.abs(best_right_path[1:] - best_right_path[:-1]) + print "max joint discontinuities in left arm:", left_diffs.max(), "per joint: ", left_diffs.max(axis=0) + print "max joint discontinuities in right arm:", right_diffs.max(), "per joint: ", right_diffs.max(axis=0) ################################## #### Now view/execute the trajectory ################################## if args.mode == "openrave": + robot.SetActiveDOFs(np.r_[robot.GetManipulator("leftarm").GetArmIndices(), robot.GetManipulator("rightarm").GetArmIndices()]) viewer = trajoptpy.GetViewer(env) joint_traj = np.c_[best_left_path, best_right_path] # *5 factor is due to an openrave oddity robot.SetDOFValues([segment.lgrip_angle*5, segment.rgrip_angle*5], [robot.GetJoint("l_gripper_l_finger_joint").GetDOFIndex(), robot.GetJoint("r_gripper_l_finger_joint").GetDOFIndex()], False) - for (i,row) in enumerate(ds_traj): + for (i,row) in enumerate(joint_traj): print "step",i robot.SetActiveDOFValues(row) lhandle = env.drawarrow(robot.GetLink("l_gripper_tool_frame").GetTransform()[:3,3], left_hmats[i][:3,3]) From eac630ef662ef9be9cc9cf7862974746a42e21f9 Mon Sep 17 00:00:00 2001 From: John Schulman Date: Fri, 8 Mar 2013 14:06:03 -0800 Subject: [PATCH 10/26] add planning to execution script --- iros/execute_suture_traj.py | 124 +++++++++++++++++------------------- iros/follow_pose_traj.py | 106 ++++++------------------------ 2 files changed, 75 insertions(+), 155 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 8671d8f..5b65590 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -248,6 +248,61 @@ def get_needle_clouds(listener): return xyz_tfs, rgb_plots +def plan_follow_traj(robot, manip_name, new_hmats, old_traj): + + n_steps = len(new_hmats) + assert old_traj.shape[0] == n_steps + assert old_traj.shape[1] == 7 + + init_traj = old_traj.copy() + init_traj[0] = robot.GetDOFValues(robot.GetManipulator(manip_name).GetArmIndices()) + + request = { + "basic_info" : { + "n_steps" : n_steps, + "manip" : manip_name, + "start_fixed" : True + }, + "costs" : [ + { + "type" : "joint_vel", + "params": {"coeffs" : [1]} + }, + { + "type" : "collision", + "params" : {"coeffs" : [10],"dist_pen" : [0.025]} + } + ], + "constraints" : [ + ], + "init_info" : { + "type":"given_traj", + "data":[x.tolist() for x in init_traj] + } + } + + poses = [openravepy.poseFromMatrix(hmat) for hmat in new_hmats] + for (i_step,pose) in enumerate(poses): + request["costs"].append( + {"type":"pose", + "params":{ + "xyz":pose[4:7].tolist(), + "wxyz":pose[0:4].tolist(), + "link":"%s_gripper_tool_frame"%manip_name[0], + "timestep":i_step + } + }) + + + s = json.dumps(request) + prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem + result = trajoptpy.OptimizeProblem(prob) # do optimization + traj = result.GetTraj() + + + + return traj + ####################################### ###### Load demo from np files @@ -426,74 +481,9 @@ def keyfunc(fname): ################################################ - POSTURE_COEFF = 1 - - def nodecost(manip, joints, step): - robot = manip.GetRobot() - saver = openravepy.RobotStateSaver(robot) - robot.SetDOFValues(joints, manip.GetArmJoints(), False) - old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] - joint_diff = old_joints - joints - for i in [2,4,6]: - joint_diff[i] %= 2*np.pi - if joint_diff[i] > np.pi: joint_diff[i] -= np.pi - return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) - - from lfd import registration - - def left_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) - # env collisions, no self / ee collisions - - def unwrapped_squared_dist(x_nk,y_mk): - "pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" - diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) - diffs_nmk[:,:,2] = diffs_nmk[:,:,2] % 2*np.pi - diffs_nmk[:,:,4] = diffs_nmk[:,:,4] % 2*np.pi - diffs_nmk[:,:,6] = diffs_nmk[:,:,6] % 2*np.pi - return (diffs_nmk**2).sum(axis=2) - - left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, - ikfunc = left_ikfunc, - nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), - edgecost = unwrapped_squared_dist) - - print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) - best_left_path_before_interp = left_paths[np.argmin(left_costs)] - - def unwind_arm_traj(x_nk): - out_nk = x_nk.copy() - for i in [2,4,6]: - out_nk[:,i] = np.unwrap(out_nk[:,i]) - return out_nk - - best_left_path_before_interp = unwind_arm_traj(best_left_path_before_interp) - - - - if len(timesteps) < n_steps: - print "linearly interpolating the points with no soln" - best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) - else: best_left_path = best_left_path_before_interp - - - def right_ikfunc(hmat): - return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) - # env collisions + self collisions - - right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, - ikfunc = right_ikfunc, - nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), - edgecost = unwrapped_squared_dist) - - print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) - best_right_path_before_interp = right_paths[np.argmin(right_costs)] - best_right_path_before_interp = unwind_arm_traj(best_right_path_before_interp) + best_left_path = plan_follow_traj(robot, "rightarm", left_hmats, ds_traj[:,:7]) + best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:]) - if len(timesteps) < n_steps: - print "linearly interpolating the points with no soln" - best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) - else: best_right_path = best_right_path_before_interp left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) right_diffs = np.abs(best_right_path[1:] - best_right_path[:-1]) diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py index 2781038..1b48265 100644 --- a/iros/follow_pose_traj.py +++ b/iros/follow_pose_traj.py @@ -116,9 +116,15 @@ def bad_inds(x1, t1): raise Exception("couldn't subdivide enough. something funny is going on. check oyur input data") -def follow_traj_request(robot, manip_name, new_hmats, old_joints): +def plan_follow_traj(robot, manip_name, new_hmats, old_traj): + n_steps = len(new_hmats) - assert len(old_joints) == n_steps + assert old_traj.shape[0] == n_steps + assert old_traj.shape[1] == 7 + + init_traj = old_traj.copy() + init_traj[0] = robot.GetDOFValues(robot.GetManipulator(manip_name).GetArmIndices()) + request = { "basic_info" : { "n_steps" : n_steps, @@ -139,7 +145,7 @@ def follow_traj_request(robot, manip_name, new_hmats, old_joints): ], "init_info" : { "type":"given_traj", - "data":[x.tolist() for x in old_joints] + "data":[x.tolist() for x in init_traj] } } @@ -156,8 +162,14 @@ def follow_traj_request(robot, manip_name, new_hmats, old_joints): }) + s = json.dumps(request) + prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem + result = trajoptpy.OptimizeProblem(prob) # do optimization + traj = result.GetTraj() + + - return request + return traj ################################### ###### Load demonstration files @@ -264,93 +276,11 @@ def binarize_gripper(angle): ################### - POSTURE_COEFF = 1 trajoptpy.SetInteractive(False) - #def nodecost(manip, joints, step): - #robot = manip.GetRobot() - #saver = openravepy.Robot.RobotStateSaver(robot) - #robot.SetDOFValues(joints, manip.GetArmJoints(), False) - #old_joints = ds_traj[step, :7] if manip.GetName() == "leftarm" else ds_traj[step, 7:] - #joint_diff = old_joints - joints - #for i in [2,4,6]: - #joint_diff[i] %= 2*np.pi - #if joint_diff[i] > np.pi: joint_diff[i] -= np.pi - #return 1000*robot.GetEnv().CheckCollision(robot) + POSTURE_COEFF * np.linalg.norm(joint_diff) - #def left_ikfunc(hmat): - #return ku.ik_for_link(hmat, robot.GetManipulator("leftarm"), "l_gripper_tool_frame", return_all_solns=True, filter_options = 1+2+16) # env collisions, no self / ee collisions - #def unwrapped_squared_dist(x_nk,y_mk): - #"pairwise squared distance between rows of matrices x and y, but mod 2pi on continuous joints" - #diffs_nmk = np.abs(x_nk[:,None,:] - y_mk[None,:,:]) - #diffs_nmk[:,:,2] = diffs_nmk[:,:,2] % 2*np.pi - #diffs_nmk[:,:,4] = diffs_nmk[:,:,4] % 2*np.pi - #diffs_nmk[:,:,6] = diffs_nmk[:,:,6] % 2*np.pi - #return (diffs_nmk**2).sum(axis=2) - - - #left_paths, left_costs, timesteps = ku.traj_cart2joint(left_hmats, - #ikfunc = left_ikfunc, - #nodecost=ft.partial(nodecost, robot.GetManipulator("leftarm")), - #edgecost = unwrapped_squared_dist) - - #print "leftarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), n_steps, np.min(left_costs)) - #def unwind_arm_traj(x_nk): - #out_nk = x_nk.copy() - #for i in [2,4,6]: - #out_nk[:,i] = np.unwrap(out_nk[:,i]) - #return out_nk - #best_left_path_before_interp = left_paths[np.argmin(left_costs)] - #best_left_path_before_interp = unwind_arm_traj(best_left_path_before_interp) - - #if len(timesteps) < n_steps: - #print "linearly interpolating the points with no soln" - #best_left_path = mu.interp2d(np.arange(n_steps), timesteps, best_left_path_before_interp) - #else: best_left_path = best_left_path_before_interp - - init_traj = ds_traj[:,:7].copy() - init_traj[0] = robot.GetDOFValues(robot.GetManipulator("leftarm").GetArmIndices()) - req = follow_traj_request(robot, "leftarm", left_hmats, init_traj) - s = json.dumps(req) - prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem - result = trajoptpy.OptimizeProblem(prob) # do optimization - best_left_path = result.GetTraj() - - - - #def right_ikfunc(hmat): - #return ku.ik_for_link(hmat, robot.GetManipulator("rightarm"), "r_gripper_tool_frame", return_all_solns=True, filter_options = 1+16) # env collisions + self collisions - - #right_paths, right_costs, timesteps = ku.traj_cart2joint(right_hmats, - #ikfunc = right_ikfunc, - #nodecost=ft.partial(nodecost, robot.GetManipulator("rightarm")), - #edgecost = unwrapped_squared_dist) - - #print "rightarm: IK succeeded on %s/%s timesteps. cost: %.2f"%(len(timesteps), len(right_hmats), np.min(right_costs)) - #best_right_path_before_interp = right_paths[np.argmin(right_costs)] - #best_left_path_before_interp = unwind_arm_traj(best_right_path_before_interp) - #if len(timesteps) < n_steps: - #print "linearly interpolating the points with no soln" - #best_right_path = mu.interp2d(np.arange(n_steps), timesteps, best_right_path_before_interp) - #else: best_right_path = best_right_path_before_interp - - #im = np.zeros((len(left_hmats), 61), bool) - #for (i_step,hmat) in enumerate(left_hmats): - #solns = left_ikfunc(hmat) - #if len(solns) > 0: - #im[i_step,:][ (10*np.array(solns)[:,2]+3).astype('int') ] = 1 - #import matplotlib.pyplot as plt - #plt.imshow(im) - #plt.show() - - - init_traj = ds_traj[:,7:14].copy() - init_traj[0] = robot.GetDOFValues(robot.GetManipulator("rightarm").GetArmIndices()) - req = follow_traj_request(robot, "rightarm", right_hmats, init_traj) - s = json.dumps(req) - prob = trajoptpy.ConstructProblem(s, env) # create object that stores optimization problem - result = trajoptpy.OptimizeProblem(prob) # do optimization - best_right_path = result.GetTraj() + best_left_path = plan_follow_traj(robot, "rightarm", left_hmats, ds_traj[:,:7]) + best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:]) left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) From 9d4ff53a7b869179dbb1ca4ee87a0241a43b005a Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Fri, 8 Mar 2013 14:10:11 -0800 Subject: [PATCH 11/26] updates --- iros/dev/circle_finder.py | 194 ++++++++++++++++++++ iros/dev/image_gui.py | 106 +++++++++++ iros/dev/image_gui2.py | 187 ++++++++++++++++++++ iros/dev/line_finder.py | 76 ++++++++ iros/dev/simple_clicker_dev.py | 293 +++++++++++++++++++++++++++++++ iros/dev/suture_scene(holes).pcd | Bin 0 -> 4919296 bytes iros/feature_utils.py | 183 +++++++++++++++++++ 7 files changed, 1039 insertions(+) create mode 100644 iros/dev/circle_finder.py create mode 100644 iros/dev/image_gui.py create mode 100755 iros/dev/image_gui2.py create mode 100644 iros/dev/line_finder.py create mode 100644 iros/dev/simple_clicker_dev.py create mode 100644 iros/dev/suture_scene(holes).pcd create mode 100644 iros/feature_utils.py diff --git a/iros/dev/circle_finder.py b/iros/dev/circle_finder.py new file mode 100644 index 0000000..d0a71c3 --- /dev/null +++ b/iros/dev/circle_finder.py @@ -0,0 +1,194 @@ +#import cv2 +#import numpy as np +#import rospy +#import geometry_msgs.msg as gm +#import sensor_msgs.msg as sm +#import sys + + +#if args.mode == "test": + #from jds_image_proc.pcd_io import load_xyzrgb + #import openravepy + + #env = openravepy.Environment() + #env.Load("robots/pr2-beta-static.zae") + #robot = env.GetRobots()[0] + #robot.SetDOFValues([1.5], [14]) + #hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + #for i in range(5): + + #xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene%s.pcd"%i) + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + #xyz1_tf = np.dot(xyz1, hmat.T) + #xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + #xyz_tf.append(xyz_tf_temp) + + #del xyz_temp + #del rgb_temp + + #print 'xyz[0]', xyz[0] + #print 'xyz_tf[0]', xyz_tf[0] + +#elif args.mode == "live": + #import brett2.ros_utils as ru + + #listener = ru.get_tf_listener() + + #for i in range(5): + #print "waiting for messages on cloud topic %s"%args.cloud_topic + #msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + #print "got msg %s!"%i + + #xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + #if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + #xyz.append(xyz_temp) + #rgb.append(rgb_temp) + + #xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + #xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + #xyz_tf.append(xyz_tf_temp) + ##print 'xyz_temp', xyz_temp + + #del xyz_temp + #del rgb_temp + + #rospy.sleep(1.0) + + ##print 'xyz_tf[0]', xyz_tf[0] + +#raw_input("Press enter to continue...") + +import cv +import cv2 +import math +import numpy as np +from jds_image_proc.pcd_io import load_xyzrgb +from jds_utils.colorize import colorize + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +img = rgb.copy() + +d_red = cv2.cv.RGB(150, 55, 65) +l_red = cv2.cv.RGB(250, 200, 200) +d_blue = cv2.cv.RGB(40, 55, 200) + +cv2.namedWindow("rgb") +cv2.imshow("rgb", img) +cv2.waitKey(10) + +#rect_corners = [] + +#print colorize("click at the corners of the relevant area", 'red') + +#for i in xrange(2): + #gc = GetClick() + #cv2.setMouseCallback("rgb", gc.callback) + #while not gc.done: + #cv2.imshow("rgb", img) + #cv2.waitKey(10) + #rect_corners.append(gc.xy) + +#xy_tl = np.array(rect_corners).min(axis=0) +#xy_br = np.array(rect_corners).max(axis=0) +#cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) +#cv2.imshow("rgb", img) +#cv2.waitKey(100) + +#colmin, rowmin = xy_tl +#colmax, rowmax = xy_br +#print 'colmin,colmax', colmin, colmax + +SIZEMIN = 21 +SIZEMAX = 33 + +COLMIN = 200 +COLMAX = 500 + +gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + +detector = cv2.FeatureDetector_create('MSER') +fs = detector.detect(gray_img) +fs.sort(key = lambda x: -x.size) + +def supress(x): + for f in fs: + distx = f.pt[0] - x.pt[0] + disty = f.pt[1] - x.pt[1] + dist = math.sqrt(distx*distx + disty*disty) + if (f.size > x.size) and (dist < f.size/2): + return True + +def fil(f): + if (f.size > SIZEMIN) and (f.size < SIZEMAX) and (f.pt[0] > COLMIN) and (f.pt[0] < COLMAX): + return True + +sfs = [x for x in fs if not supress(x)] +circles = [c for c in sfs if fil(c)] +circles.sort(key = lambda c: c.pt[1], reverse=True) + +horiz_pairs = [] +diag_pairs = [] +for i in range(len(circles)/2): + horiz_pairs.append([]) + horiz_pairs[i].append(circles[2*i]) + horiz_pairs[i].append(circles[(2*i)+1]) + +for i in range(len(horiz_pairs)): + horiz_pairs[i].sort(key = lambda c: c.pt[0]) + +for i in range(len(horiz_pairs)-1): + diag_pairs.append([]) + diag_pairs[i].append(horiz_pairs[i][1]) + diag_pairs[i].append(horiz_pairs[i+1][0]) + +print 'num circles', len(circles) +print 'num horiz_pairs', len(horiz_pairs) +print 'num diag_pairs', len(diag_pairs) + +cv2.namedWindow("rgb with circles") +cv2.imshow("rgb with circles", img) +cv2.waitKey(100) + +#n = 0 +#for p in range(len(horiz_pairs)): + #for c in horiz_pairs[p]: + #n += 1 + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + #cv2.imshow("rgb with circles", img) + #cv2.waitKey(10) + #raw_input("Circle %i. Press enter to continue..."%n) + +d = 0 +for p in range(len(diag_pairs)): + for c in diag_pairs[p]: + d += 1 + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + cv2.imshow("rgb with circles", img) + cv2.waitKey(10) + raw_input("Circle %i. Press enter to continue..."%d) + +cv2.imshow("rgb with circles", img) +cv2.waitKey(100) +raw_input("Press enter to finish...") +cv2.destroyAllWindows() + + diff --git a/iros/dev/image_gui.py b/iros/dev/image_gui.py new file mode 100644 index 0000000..e97829b --- /dev/null +++ b/iros/dev/image_gui.py @@ -0,0 +1,106 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("--mode", choices=["live","test"], default="live") +parser.add_argument("--cloud_topic", default="/drop/points") +parser.add_argument("--plot3d", action="store_true") +args = parser.parse_args() + + +# how to get a pcd file +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("suture_scene(holes).pcd") + +raw_input("got pcd. Press enter to continue...") + + + +import cv2 +import numpy as np + + +if args.mode == "test": + from jds_image_proc.pcd_io import load_xyzrgb + import openravepy + + xyz, rgb = load_xyzrgb("pr2_suture_scene.pcd") + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + xyz1 = np.c_[xyz.reshape(-1,3), np.ones((xyz.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf = xyz1_tf[:,:3].reshape(xyz.shape) + +elif args.mode == "live": + import brett2.ros_utils as ru + import rospy + import sensor_msgs.msg as sm + + rospy.init_node("image_gui", disable_signals = True) + listener = ru.get_tf_listener() + print "waiting for message on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got it!" + xyz, rgb = ru.pc2xyzrgb(msg) + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + +xyz_tf[np.isnan(xyz_tf)] = -2 +rgb_plot = rgb.copy() +depth_plot = xyz_tf[:,:,2].astype('float') +depth_plot[np.isnan(depth_plot)] = 0 +depth_plot -= depth_plot.min() +depth_plot = (depth_plot * (255 / depth_plot.max())).astype('uint8') + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +cv2.namedWindow("rgb") +rect_corners = [] +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) ## this doesn't seem to be working... + +# extract depths from drawn rectangle ##ADD STUFF HERE to make this work better +colmin, rowmin = xy_tl +colmax, rowmax = xy_br + +z_rectangle = xyz_tf[rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + +row_needle, col_needle = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) +col_needle += colmin # since these indices are from small rectangle +row_needle += rowmin +cv2.circle(rgb_plot, (col_needle, row_needle), 3, (255, 0, 0), 2) ## this doesn't seem to be working... + +# plot the point cloud with a circle around "highest" point +if args.plot3d: + from mayavi import mlab + x,y,z = xyz_tf[~np.isnan(xyz_tf[:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + xneedle,yneedle,zneedle = xyz_tf[row_needle, col_needle] + print "xyz needle point", xneedle, yneedle, zneedle + mlab.points3d([xneedle], [yneedle], [zneedle], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + mlab.show() +else: + while True: + cv2.imshow("rgb",rgb_plot) + #cv2.imshow("depth", depth_plot) + cv2.waitKey(10) diff --git a/iros/dev/image_gui2.py b/iros/dev/image_gui2.py new file mode 100755 index 0000000..5d0b2e1 --- /dev/null +++ b/iros/dev/image_gui2.py @@ -0,0 +1,187 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("--mode", choices=["live","test"], default="live") +parser.add_argument("--cloud_topic", default="/drop/points") +parser.add_argument("--plot3d", action="store_true") +args = parser.parse_args() + +""" +# how to get a pcd file +# plug asus into local computer +import cloudprocpy # my homemade pcl python bindings. built with trajopt if BUILD_CLOUDPROC enabled +grabber=cloudprocpy.CloudGrabber() +xyzrgb = grabber.getXYZRGB() +xyzrgb.save("pr2_suture_scene.pcd") +""" + +import cv2 +import numpy as np +import rospy +import geometry_msgs.msg as gm +import sensor_msgs.msg as sm +import sys + +#rospy.init_node("image_gui", disable_signals = True) +rospy.init_node("image_gui") + +xyz = [] +xyz_tf = [] +rgb = [] + + +if args.mode == "test": + from jds_image_proc.pcd_io import load_xyzrgb + import openravepy + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + for i in range(5): + + xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene%s.pcd"%i) + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + #print 'xyz[0]', xyz[0] + #print 'xyz_tf[0]', xyz_tf[0] + +elif args.mode == "live": + import brett2.ros_utils as ru + + listener = ru.get_tf_listener() + + for i in range(5): + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg %s!"%i + + xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + xyz_tf.append(xyz_tf_temp) + #print 'xyz_temp', xyz_temp + + del xyz_temp + del rgb_temp + + rospy.sleep(1.0) + + #print 'xyz_tf[0]', xyz_tf[0] + +#raw_input("Press enter to continue...") + +rgb_plot = rgb[0].copy() + +#depth_plot = xyz_tf[:,:,2].astype('float') +#depth_plot[np.isnan(depth_plot)] = 0 +#depth_plot -= depth_plot.min() +#depth_plot = (depth_plot * (255 / depth_plot.max())).astype('uint8') + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +cv2.namedWindow("rgb") +rect_corners = [] +for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(10) + rect_corners.append(gc.xy) + +xy_tl = np.array(rect_corners).min(axis=0) +xy_br = np.array(rect_corners).max(axis=0) +cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) ## this doesn't seem to be working... + +colmin, rowmin = xy_tl +colmax, rowmax = xy_br + +row_needle = [] +col_needle = [] + +# extract depths from drawn rectangle +for i in range(5): + z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + col_needle_temp += colmin # since these indices are from small rectangle + row_needle_temp += rowmin + + row_needle.append(row_needle_temp) + col_needle.append(col_needle_temp) + + del z_rectangle + del col_needle_temp + del row_needle_temp + + +xneedle = np.zeros((5)) +yneedle = np.zeros((5)) +zneedle = np.zeros((5)) + +for i in range(5): + xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + +print "xyz needle point %s"%i, xneedle, yneedle, zneedle + +ind = np.argmax(zneedle) + +max_needle = [] +max_needle.append(xneedle[ind]) +max_needle.append(yneedle[ind]) +max_needle.append(zneedle[ind]) + +#rgb_plot_best = rgb[ind].copy() +#cv2.namedWindow("best_rgb") +#cv2.imshow("best_rgb", rgb_plot_best) + +cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) ## this doesn't seem to be working... + +#save needle location to np file +np.save('/home/mallory/mallory_workspace/suturing/python/iros/needleLoc.npy', np.array(max_needle)) +print 'needle location saved!' + + +# plot the point cloud with a circle around "highest" point +if args.plot3d: + from mayavi import mlab + x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + mlab.show() +#else: + #rospy.sleep(1) + #sys.exit() + #while True: + # cv2.imshow("rgb",rgb_plot) + # cv2.imshow("depth", depth_plot) + # cv2.waitKey(10) + +raw_input("press enter when done") +#rospy.spin() diff --git a/iros/dev/line_finder.py b/iros/dev/line_finder.py new file mode 100644 index 0000000..6681d09 --- /dev/null +++ b/iros/dev/line_finder.py @@ -0,0 +1,76 @@ +import cv +import cv2 +import math +import numpy as np +from jds_image_proc.pcd_io import load_xyzrgb +from jds_utils.colorize import colorize + +class GetClick: + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.xy = (x,y) + self.done = True + +xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +img = rgb.copy() + +d_red = cv2.cv.RGB(150, 55, 65) +l_red = cv2.cv.RGB(250, 200, 200) +d_blue = cv2.cv.RGB(40, 55, 200) + +cv2.namedWindow("rgb") +cv2.imshow("rgb", img) +cv2.waitKey(10) + +#rect_corners = [] + +#print colorize("click at the corners of the relevant area", 'red') + +#for i in xrange(2): + #gc = GetClick() + #cv2.setMouseCallback("rgb", gc.callback) + #while not gc.done: + #cv2.imshow("rgb", img) + #cv2.waitKey(10) + #rect_corners.append(gc.xy) + +#xy_tl = np.array(rect_corners).min(axis=0) +#xy_br = np.array(rect_corners).max(axis=0) +#cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) +#cv2.imshow("rgb", img) +#cv2.waitKey(100) + +#colmin, rowmin = xy_tl +#colmax, rowmax = xy_br +#print 'colmin,colmax', colmin, colmax + +SIZEMIN = 21 +SIZEMAX = 33 + +COLMIN = 200 +COLMAX = 500 + +gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + +#cv2.HoughLinesP(image, rho, theta, threshold[, lines[, minLineLength[, maxLineGap]]]) lines +#cv2.HoughLinesP( img, lines, 1, CV_PI/180, 80, 30, 10 ) +edges = cv2.Canny(gray_img, 80, 120) +lines = cv2.HoughLinesP(edges, 1, math.pi/2, 2, None, 30, 1); + + +for l in lines[0]: + cv2.line(img, (l[0], l[1]), (l[2], l[3]), d_red, 2) + cv2.imshow("rgb with lines", img) + cv2.waitKey(10) + #raw_input("Circle %i. Press enter to continue..."%d) + +cv2.imshow("rgb with lines", img) +cv2.waitKey(100) +raw_input("Press enter to finish...") +cv2.destroyAllWindows() + + diff --git a/iros/dev/simple_clicker_dev.py b/iros/dev/simple_clicker_dev.py new file mode 100644 index 0000000..9997cb7 --- /dev/null +++ b/iros/dev/simple_clicker_dev.py @@ -0,0 +1,293 @@ +import argparse +parser = argparse.ArgumentParser() +parser.add_argument("mode", choices=["live","test"], default="live") +parser.add_argument("object", choices=["holes_cut", "needle"]) +parser.add_argument("cloud_topic", default="/drop/points") +parser.add_argument("plot3d", action="store_true") +args = parser.parse_args() + + +# how to get a pcd file +#import cloudprocpy +#grabber=cloudprocpy.CloudGrabber() +#xyzrgb = grabber.getXYZRGB() +#xyzrgb.save("pr2_suture_scene(needle_finding).pcd") + +#raw_input("got point cloud. press enter to continue") + +import cv2 +import numpy as np +import rospy +import openravepy +import sys + +import geometry_msgs.msg as gm +import sensor_msgs.msg as sm +from jds_image_proc.pcd_io import load_xyzrgb +from jds_utils.colorize import colorize +import brett2.ros_utils as ru + +rospy.init_node("image_gui") + +######################################### +### find holes and cut +######################################### +def find_holes_cut(plot): + + hole1_center = [] + hole2_center = [] + cut_endpoints = [] + + print colorize("click on the centers of the two relevant holes", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + if i == 1: + hole1_center.append(gc.x) + hole1_center.append(gc.y) + else: + hole2_center.append(gc.x) + hole2_center.append(gc.y) + + cv2.circle(plot, (hole1_center[0], hole1_center[1]), 10, (255, 0, 0), 2) + cv2.circle(plot, (hole2_center[0], hole2_center[1]), 10, (255, 0, 0), 2) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + x_hole1, y_hole1, z_hole1 = xyz_tf[hole1_center[0], hole1_center[1]] + x_hole2, y_hole2, z_hole2 = xyz_tf[hole2_center[0], hole2_center[1]] + + print 'hole1 3d location', x_hole1, y_hole1, z_hole1 + print 'hole2 3d location', x_hole2, y_hole2, z_hole2 + + raw_input("press enter to continue") + + ### find cut + + print colorize("click at the top and bottom of the cut line", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + cut_endpoints.append(gc.xy) + + xy_t = np.array(cut_endpoints).min(axis=0) + xy_b = np.array(cut_endpoints).max(axis=0) + + cv2.line(plot, tuple(xy_t), tuple(xy_b), (0, 255, 0), 2) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + x1_cut, y1_cut, z1_cut = xyz_tf[tuple(xy_t)] + x2_cut, y2_cut, z2_cut = xyz_tf[tuple(xy_b)] + + + #midpoint of line + mid_y = (xy_t[1] - xy_b[1])/2 + mid_plot_x = xy_b[0] + mid_plot_y = xy_t[1] - mid_y + + cv2.circle(plot, (mid_plot_x, mid_plot_y), 5, (0, 0, 255), -1) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + mid_ptx, mid_pty, mid_ptz = xyz_tf[mid_plot_x, mid_plot_y] + + print 'top of cut 3d', x1_cut, y1_cut, z1_cut + print 'bottom of cut 3d', x2_cut, y2_cut, z2_cut + print 'middle of cut 3d', mid_ptx, mid_pty, mid_ptz + + raw_input("press enter to continue") + + +######################################### +### find needle +######################################### +def find_needle(plot): + + needle_rect_corners = [] + + print colorize("click at the corners of a rectangle which encompasses the needle tip", 'red', bold=True) + + for i in xrange(2): + gc = GetClick() + cv2.setMouseCallback("rgb", gc.callback) + while not gc.done: + cv2.imshow("rgb", plot) + cv2.waitKey(10) + needle_rect_corners.append(gc.xy) + + xy_tl = np.array(needle_rect_corners).min(axis=0) + xy_br = np.array(needle_rect_corners).max(axis=0) + + cv2.rectangle(plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) + cv2.imshow("rgb", plot) + cv2.waitKey(100) + + colmin, rowmin = xy_tl + colmax, rowmax = xy_br + + row_needle = [] + col_needle = [] + + # extract depths from drawn rectangle + for i in range(3): + z_rectangle = xyz_tf[i][rowmin:rowmax, colmin:colmax, 2] # z values in extracted rectangle + row_needle_temp, col_needle_temp = np.unravel_index(z_rectangle.argmax(), z_rectangle.shape) + + col_needle_temp += colmin # since these indices are from small rectangle + row_needle_temp += rowmin + + row_needle.append(row_needle_temp) + col_needle.append(col_needle_temp) + + del z_rectangle + del col_needle_temp + del row_needle_temp + + + xneedle = np.zeros((3)) + yneedle = np.zeros((3)) + zneedle = np.zeros((3)) + + for i in range(3): + xneedle[i], yneedle[i], zneedle[i] = xyz_tf[i][row_needle[i], col_needle[i]] + + print "xyz needle point %s"%i, xneedle, yneedle, zneedle + + ind = np.argmax(zneedle) + + max_needle = [] + max_needle.append(xneedle[ind]) + max_needle.append(yneedle[ind]) + max_needle.append(zneedle[ind]) + + cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow("rgb", rgb_plot) + cv2.waitKey(100) + + # plot the point cloud with a circle around "highest" point + from mayavi import mlab + x,y,z = xyz_tf[ind][~np.isnan(xyz_tf[ind][:,:,0])].T + mlab.points3d(x,y,z,color=(1,0,0), mode="2dvertex") + mlab.points3d([max_needle[0]], [max_needle[1]], [max_needle[2]], color=(0,1,0), mode="sphere", scale_factor=.04, opacity=.2) + mlab.show() + + raw_input("press enter when done") + +######################################### +### clicking set-up +######################################### + +class GetClick: + x = None + y = None + xy = None + done = False + def callback(self, event, x, y, flags, param): + if self.done: + return + elif event == cv2.EVENT_LBUTTONDOWN: + self.x = x + self.y = y + self.xy = (x,y) + self.done = True + +cv2.namedWindow("rgb") + +xyz = [] +xyz_tf = [] +rgb = [] + +if args.object == "needle": + if args.mode == "test": + for i in range(3): + xyz_temp, rgb_temp = load_xyzrgb("pr2_suture_scene(needle_finding)%s.pcd"%i) + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + xyz1 = np.c_[xyz_temp.reshape(-1,3), np.ones((xyz_temp.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf_temp = xyz1_tf[:,:3].reshape(xyz_temp.shape) + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + + elif args.mode == "live": + listener = ru.get_tf_listener() + for i in range(5): + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + print "got msg %s!"%i + + xyz_temp, rgb_temp = ru.pc2xyzrgb(msg) + if (xyz_temp.shape[0] == 1 or xyz_temp.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz_temp) + rgb.append(rgb_temp) + + xyz_tf_temp = ru.transform_points(xyz_temp, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf_temp[np.isnan(xyz_tf_temp)] = -2 + xyz_tf.append(xyz_tf_temp) + + del xyz_temp + del rgb_temp + + rospy.sleep(1.0) + + rgb_plot = rgb[0].copy() + find_needle(rgb_plot) + +elif args.object == "holes_cut": + if args.mode == "test": + + env = openravepy.Environment() + env.Load("robots/pr2-beta-static.zae") + robot = env.GetRobots()[0] + robot.SetDOFValues([1.5], [14]) + hmat = robot.GetLink("narrow_stereo_gazebo_r_stereo_camera_optical_frame").GetTransform() + + xyz, rgb = load_xyzrgb("suture_scene(findholescut).pcd") + + xyz1 = np.c_[xyz.reshape(-1,3), np.ones((xyz.size/3,1))] + xyz1_tf = np.dot(xyz1, hmat.T) + xyz_tf = xyz1_tf[:,:3].reshape(xyz.shape) + xyz_tf[np.isnan(xyz_tf)] = -2 + + elif args.mode == "live": + listener = ru.get_tf_listener() + print "waiting for messages on cloud topic %s"%args.cloud_topic + msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + + xyz, rgb = ru.pc2xyzrgb(msg) + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz.append(xyz) + rgb.append(rgb) + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + xyz_tf[np.isnan(xyz_tf)] = -2 + + rgb_plot = rgb.copy() + + find_holes_cut(rgb_plot) + + + diff --git a/iros/dev/suture_scene(holes).pcd b/iros/dev/suture_scene(holes).pcd new file mode 100644 index 0000000000000000000000000000000000000000..b466c51e72a7282764525ec4afe89a5e5085f1d9 GIT binary patch literal 4919296 zcmd?S2b5jKnXbK+rB;q8t0ke>Ip;p7^XWc0b~WeIu6^sZ?NGTE8z*ZJJPB zTji+?C!R<=nRqI3a-cgQT-#ign0@|FLZm5Bl~{fLPeO%1>Wd_1od1*1P+J*sCFW+Q zC%CF=Yh01U?ELhE`r4|7fWKC4mj3rY8S>u*`~QU#v(oc2)6)|w%OYio-9uwtlP41_ z>oafDf9K4ZW9fg(e=n3R+W$iNLeIzBTXR+RW3GppxBs7J$sOeH|1q9J_vb=+9_^p7 zWFeI2qP40z$K3zL>y`p9OOON1)c1w+6~^$~d2i11=i>es%5!P|c)Vc20?1#&BFW%P z{+X97pmh5JXSQFyST1;m6Bb~5Upx=fllJa|?N{w} zCCBDx*&^VTtCs;U+qe>V#pcz(>o1Z6&RpNx^(%n)EXVq>d+B0G-$C_>`69al&K!T8 z+B^1qTp#99f5`m}-+$hJSpw!aYsGRnUs}Qv;KlRt{@b@Vrabt3oSzG2J|4H9dGoP; z#bqilySc~Yf6+p`-bWvK9IpR!@4FZHD<6LZ__>ci3jE!do(6vHOUS=?=^04>-ZwrE z{FCo}4fyvz{0{KH|LD8GfBViifxrLZ_W?h4$F;ymx+1{6Z4JPO`a6M74h#TaGBgBy zbZq?1d1MUIj|`0h4-Funz497Jzvj#pz+t}^IM-DKT;z2E*Hj|sWv4@Wad9zlC=>#A zhCIOg3bKGN&OHD;cKQhLeb-|C-~Y~AA^n5*AwTyatWRJ4(EDNgA3XCE@E1S*Dd5Y; z4*_=#VSa`tE`jvJM^6GzoxBYASR6ib>=bN2ID++IWB||4JT!pyfSg<_tJqT_bMqYDj|g>L|9?its^5FArgQrGF=+Gv~RtL3(EOM&RrkOwX#`3hCQw zF+I_f2gzd8ju(}(q=u|5m7 zZ-`=lb0CQ0)j6_zO!*}hVE*bF_d|MKGq#uF4m@9VTQ+Q8LG7Wq0gqP@!TflGyJ7!m z6SkMCc5F}K(Gu7`eAEdXIaUVTbOh6xJCBsZ_RLL_nBIJ(0=93Xkmxe^N6{A9Q)Jg7(O2&)W3$Qzpfv^`+uPv?Zf`M zVE~^O+`lt7jN$X6{?ME6&(E7ydOkFFrojCRbYcCgYr*!%&j(ivJ`bEt$hm%e|J>=p z{&-Iy5zg=PUkn@w?gfre`wsecLAob^>}|#R5$(nH z6&S+%>!Id<8%kM+pUOb+^8}EmYo)^JR+&)14S)d2|+h8x=&j8h@;4of4KaYd-zQ@lye!ps_ z_A;BXy)@JKgWD5x+hObUyuNB0Z*YG(t3RRshWj6`pUe$Ict7i@J~xkG z{eG+5GK%MG7{TXx{V=uRQ^Mw*nV2t@p<8<@osVT zW@vvkn@IXE71` z%*FarT!dU&g8Ak0=JE^`!0}d~4EsYqUR?>+k9h2HV14mAu|9EneF<(KEynxH z`!k11@c7I%C0M_h<6Tdv2(O>(4>Q*{?qB%+aCy(_zv9%-c;^q6V0qS;V|{2Y#qwz= z!u!F;4;Es3;Qpf4fzJ=FUj+y8`^>Ig_;QRxLz+QSjg&cJM zsQvKsjG3?Bmxt}KG7rD6TquWg@q11v2ftqyXXE>OVJ1HB9ho@)#9Wh%;{jI+9=|Xh zIWGl|7muqB;`ZhH@cTny3VwfMPEEq?(~_}%T&VxS+h3^f$J_Jq{?W|mWBx~7te$3=Pr~2nz>%~1D7ts<1d|$ymB$lcUtuRvZbXJ zj$hi`0Gt!_0keN&t(F@wlfRwI@%+12E`s#MYgPg;U613x_3PI|`nGM`fD<=u241&( z1@M;Ti-9j%g8Ad}x07S?znJRxBCen0w{iPjOzA5Y;q@2O^Ez|kLdY-sn+xp*HdDUb zKQMECE|h2afaJScz(n1}T@L0w&J{jf2nyz3hqA^m6v*2l{RdLjMlBi+C^UpfN( zo=b*+@0r5w?>o^6>C^X~0shH*?gReYbLW7+^}@5j58QGC@R_rxfO~qIfsb_J^_?2% zf%Fr^r-u3FMaF-z|Vi| zBfuYh@ZG?dz4K1s$YCtsmeIqI-bcRP#L>$kee&4bfKQ#c4EV&cOMu6ZTngMbgyk_h zI0flbhjIIX!6T49JaP=UcMR)Spc&g|q{Ru_2OH^oBh8;Tbm99He;@R>XX5e5N2qJU z`RZWnKG@#dxEt8fgz07EFN8X9eBaoI=a0~Q7tc?yuhK&P9nViN^Y>PsuZqX~y*f(s z1>Qq=KbWiO`*YPWeh=``d`&HVpN-Oddx+-a!!#euTob|fC+1o&-oG069=yNqMBu{e zEx_3>{N9vVeG#Ous>SWsdGY-?y%vwpJ|Hvuf$aOGS73e)()a8AP8`p~_4C-*Bi>WG z0j`&seZPanINsV-vVB9hu1S{6F^nc>DGHaeTHnc@dnyqt6L^>3|n_ycyG1 zd+_^*m8CY18E<$UOM$y1iNO1tuznsOAF#9`6}B%Re>I+e6Aod2)=Bf@Jpaz~k%6O? zaDM+3K7V=sa~9M5CeQcA>ewE{CR2q zm*-=7{=R7p`%mUJ>R*|8KCg-TSH3>(?>Rk8<;%|#?*Dx>A09bc4&~8t80$~C7yJKa z@&lX5ALr+V>kyW=n|$?}0et>@>3Pe(dVLeNFF*Ni9g%HtJ)KdU|7&Q$=SO=t9?#h= z9m34}RB0!EpLBHLcz`*-3%4)q!Q<6*;`hC>=8NHc?&d_`@*qB+D#AFPiN}=@JiaG{ z&r4?Z70deyAwSOEV&L+Aod2jN4)@^w_w?fU-ra-stC-3^uMO`{CH;P&q8`hWf4@-K ziuc1!{dFDn=OOY_>)UeRdK|ZjMk*}UZ?>qJF z`2G`V#r9Rwjq@jE{WxF4zu#g%CrW-av!@-~S8WT9x7;0=9~Zsv)pTP1n0@Uy-{Ys_ z@%vw}9gpXw>ksr{|K#qY{1S(IFg?_b<<0lI?g+L=_HUUR$k%1=nQ%h;@22`1q;&Sx zdHmt)#s0N{e!tL2K3|BQ_hIsX*_UDtkzYNFX}rk(XUz!q$Cd22_F?@C^kV(y{)_!; z5B0}9zVuJv^Dr=p&r`l%jYqIQ8kxlL{Lo?SpV&ubpRj}an^{cb*LL#NJ1D)2{7?1+ zqvZcJ_2ToCxw#MPQxpCEfqg;t3EB7a(eF2kI&nUwc>w85Lj-Mk9)PF{?e|Cqk zy;ga!zc2OT{yCL6KCWAZAl`tM*zmJ*cN9)O#NhO~soqWcULcBkYVk~biPiFSbyrua3 zu5;pe%~gu+k$pS%_ZpnIJu~}Yd_LYjLOvhohmXho3D=)^ejk??`+;13T)%6Jv43Rd z_QL1m`^g+H|6%ea*;nNJ^Zn=h%je_k;r7JW$3EaD@;j{^G=H#W1GJ}$m#qR$T8mtE z0KYdEChdalE6A6t$iwzqnUBv?Uk*MGgX9m_7h?a(ezrFo`+MfvbbLNDyE8F=%sJV( zKeICn#}mxOnRtEtJSs@T^Rw?)l#J(hq~rD0rXp7-VSaf3!XzBuuH^UZyW$K&h0(ERZBe7sp~ zXL#oOI{SfqeazNeDd3s?tp)Re*?(JP3xqS<$BSRKh|^oyIlkcXg*bn@Y{5b(KWiC2KlbH1Aw4Nl51brDAMijOZf|W|0o!k+ z_hFZ~qXS*Q$A@}=CxH-^2y z<^DS0GG8rlRZTf?wF|#j7FS?;Rw2%JB+>Vd>~bd@ueK8XzpGAP0qM7&y$tx#J8uU5 z=$$tKf8w57fj@HpoxorE1m545KKWrtfAz*Q9S=>|0JAmq;CSax9>18`+(g8SU>ChHL$(68QmffJFYsW=YDnjJfE+LIK+#&*o_TLRj>mRp$p~a-{IWX@$8XI0(s6vVCl$Bfl#J;+ zGI9KtUxnqX5f#N~UiswRpM`Il3_$TqWoqQ6G7vrONsqy0X%<4}l zehK?)%cje0){f&t_Vvoh_hjFX zeL(j6JoI~nc=3rjexRFve-i4$`5BI1#eNz40PM3gQv6o-vAMrypO2Y+-Z1sg+@D{l zAHe;GoBYPgew+`i8o=>5*RLS?c0Ar??k2y9Idr@V+9StHWdFu@7~8*#;<>qxIN*4E zKRA9E`#v@7BT+m^_LsPP+3$dj2vu_2YP=c>td$ zT>tARUT$a*zdy|OvGIB1r{5cJ{@FL<_?Aud{@glF`9Fl;2RI&cBl*6~6WAXy_miK^ z+)n;s8~Is-%NL~M4~*gSy_2Aa56Zv)Vdm#4Gq;~WAJzx{J&B9@ zD{mL}XTCVU52>K|<(wbp09`LLZ_gZ|`W>bEKfAtT{p0q_%<%~uIld-6&-i_aP9N&t4zzF$RvzUCta2}4o*w?Dc$NRy)g(nNkD_%NZA74NFe(XQQ zWA-ih_#BUqeMUzXj(3>ZPh_9bpN;(q`+@8u^8IDslkc}b7uzfQcD2Co=naTs~Z%3-ho% z*|+5QoXp%F`1ss^F>`z4_Tr}UXXgAc^Yt^c-^a}LkJ}HIUqLRmw}TnjU$5SX-@`Yq z#QA^?%kg_YuP^A?htE6qb#rs@ds108K3^*+-X6#6Mzj*1AJILSvVdnhu_1eW5Tb^<9%g6giGvDtyF1%N?4@&*C`D`QiM|S%UMq za}$=q@i{)=>R<@d!!G13eE-_D4##g>S1f_;=h6DT3s&O!IUXSM=Jj~|^{W!#`0FX& z-#Ut?xPLDCfO~AAccy&f`G4wUa6Yd83FHH=UxwGm`CYYi0UVF(=Q27Tw_j$?53`;9 znEJ%&%5^RdAmINtH0Uf{!ncs}Mn@&ns@u)K~3 zBXB(LKAbPymWAV?lnR_5$*n*iBd5Fqj+b8H1l~{a@psbuLxCUf_e5hm?ElzJw*x!)$6Z3bd;}9Ibs~fqecO25&``Uo3Jb1qY96zN4-#_cg z?_+MDcyje^_&&+$&0TnWj^9x;jP;Y_5Apm4$M^6|IN^FZ9!UkoFW~RhjTE1Wf3Mv{ z-|N}`;P_R{ynQ>x1K{ zrEfRfKZiRJxTJPFaBkh!H|0z>re}G!;r6aX;OuHTKKXxHjksV$LslWe7~KA=nu00w<{aRFYNO%C#B%_%o!PrA^(vGet#Hl#qYPL$yaKh48s2D zm3aS?({MbMlD-hOFL2`b$Qs|pke)*MN#}Tf6u&Yzh|kYzn!oUn|HAFTcc=``&+9uf zvv0=SaM%gQo5i#qTmv!t5A3USOycoFeb|5V`h$L&|MXCN6YmjxzW9z{d9dHX*V9Pr z|8hF7U&r(9%-o+c$BW+;rulh}x8t8Ghx@}mOXsm#NN294_*l6VkB;X*Io=+}?_uWt zKSJ?f>W<<4V)h-w>+?)ueF;$fGB>Tq%=e$y&#b2V?I2&0eH#zO=i~TKz7~9c&7k$W zlY+b8el++JfrGBiz`1_pf)GAG>cZIH)rPSDNTKz3(`h}@BwCL)Z4iC6!oFh2Pw_x0 zFt5+*qxp08{g^pEFmo0?-w)DyyzKL_k5|!%?;p(GhGe)NANh}-b{tOx$p7T^n7#b_ z37Y>7(t6)KpWa04{jvWS>c{bG9mT`rcv2MxEWR`MP^?{@q3SEg|2g>L}LlLW-wVeAEf`rH0nyby0uT zLGg53>HUEHziJx)v(MotpEh3mcIBG@%`el zzZ>^wKR86^@1|DEFly4$cnV6JP$`oi%(+4pnMdg4XY-`0kAVtonX?}gm7zIu%t z`}Z_I&TnUiw&3yValBeX9BRYoO-nzv*YE(2x7Zir-v{vTF}VMz89?7=md{7)xpMnv zp5;3Yp)c1$>xnjxV*9P5cyyKYd$Vv4-tS-+J`dPu<@H4U6fZYG>)qEj;C!2_elOfV zUnABBPd(oMXk#L5-`<6Ozpn@L%kd?n)IZi!|H$#RTj}?N?EA5=*D~&e{52iI@@Jor zd2kHJ=RHF>-iY`6LH5a*IbI%fh~g77vwzO9%>Q!z3hiZD84zz3uNZ! z12eZD9-p!Q$osQj%iKl2Unh-U;*FnMI?+#PY{Tab`+v+)`u%RC1^b_F@&UV=aeU)z zz~@1=pW3Sj`^&;oY@b=h*uUnK;`@JjF77{zY5iLE$(Y$MW1nmmlP|&XmI4%?j`wFj zgZ)4D*VyOd^>CSad**oY{n-Cw|H7S)^^2MF!_4_%=IdwX`^Cp+W`BwA5Br47eE&F} zWC5+;TT1JVGPBRcJ{$XC%)CAm`(69o%-~=hHB) z|J+3DD@Ss$f8h9=%zVGt?~2Q`zAXD+?4vRB{b6RmljBQreJG^$$$5Wf_Dz}D&*S!x zMeA+nQ@ppvTztQ1$ier6c(L4@k+!@hJOv{5)Zw zv8({go1a(AT%Wjn`F!QHzHcy##{a||-<6r4C(QAlU-A4v_Sbp)(lork#VI)6$WO=d zOl~Ur)SGF2;4P_mf9Kdj+>FmMi^(Tp-{b!@v;TFW954Uur!dFcKVCW?k2&7{s_{bm zeXGppn@h)Mj(a|;KYV}qd>6`mJd6E2iucDp9Q%3~%Ir6>KgZ0z-Q0yzqBHG}nfJd? z=IdqV<8l7%@OLr!W46}f^CjDj^HB%FZn(aM={SFKV8b#<-@A4R@WNHgfq6aP6>FD5 z`tmgiz}r`0`nHvrzH0@}_a-iz5Bqa`z%2{#esTQ1MQZQZ`x!4i!ER79_kZ0o%pb?+ z-A(ZdIo_nb9Cpn8nn(RR^Q``!w!hH!$nAmSYjS)~KE7RiG5Kd+Me8B2sYIVAe;ED0 ziP3(zA2(cc1@MD6TnGGKS|9d(x8DNkkH6za;3sZ43w+OIM}cp-3cEHck}map6_(_Nzt@-3`Yu6- zC3X0{xYUjNb9#{r=l2S#aegSbVk?}V*9T_KsKorR|HtbCA1GP}$4@O-^QN4VkK?=K zyj8IMo*dkNXT}Oh-&9) z-+}_nPhJJypEB9&3=|bwp|XUycXc za>NP8uRn(40rnmF`5T~kUVQz${vDS$`={~F&+&Jd`T15&@oSy*`-Z##zTf88?Sk?s zaHG$0G5H~TgP2}K?1^=f+YdCt$811;r17x^$6?8H>)9E#6><#Z8yH()pg?g9W$@z8jsok;_*9kkm^r>){kVr z%}f48Ijz^}BVV#%q5$ec<0QVHw4B88L&H)0p4CqEp?Sgy$K&S<_a{M$|K}%viG9aP zicePFgY##_w7w;ee>uKgF0FT+Px1X~C>~%Pt=Cvd@jR>hv45$gc(LVOSiT%DlYJXE zjrX|z@p|jbJie+SKak^px|?u*iq{V>rFg0y>W}Lv9&33R`)iI@elUpX$zdE{7SsCd z4)PEA_fI~0pJu3PsYeixTFf3IL}8Nu;-8~y&Hlj8ri((f;tDV{a^iv0UYX7<%MK4jBiIrPVo z9_*j$DL!$8{Ntw1eAqwQisjAmN&W3OzVLP+b9_(!eV1zh%ag}v%=~=x)A)+xRYqz3 zVqR~#g?@j)@fthm`NY1ZkK%uFeAiGbmIwQ{?El3}kLL#l$p`e-r^5Z@_Ux#@?>R-K z*gqE(<9M6>2j+M_0s8~YygxI?-(!D*{T5DV-;J65HTEyqU*vd6d_5eWFPr=oX7(T0 z2dtxbZ|rCA_57omeLy~beh$`m_V3s);`m~rZ2Z2-J`10Z{V!(rkJxWxpNrQcWv(j0 z{*c$h=Jl^PZP@_rZ^a7y-p2EL2Uo3w?Q^##0+;UG3C!y+hiLun0F@`#Z)PrEEC9m1$lpF_5t~R^6|NS^7iqV&&ToFm}?4gJjnhq`)tJpI3E=RRV&9N`Yi5prSVDda z$MfUo8T)_Cyg&PYyq<9OLA-xlUzlgDpUUg0#__ji`B$_(ukU!FejEEC|F{@xby^VY1x`D5md zYcZYUC+9`S*VIA5Q#73YH&EXVn2%bEx0Tfy-HiP_g%x(Lg2 z%ewV&JYJuf{XbhLjk!N|^?MVJ*Pb|DDl_lT^^=*mR~HA@$1FA`)HixQrKI6_ueZMo zw(lJu2A;U|IPkUCT@8HK-FEw1dGYfJ4Dyf^#hpyXg}U>FRf?HeC+a5aJ*aIiTD3wcis)@cb~cxIDGgpaAGF{U*Jd$ZciMXLSG_4^LJia z?otwGW&h(19@pZMqW>h*Hh#5CHeb&3$Jf9 zjPs|>6#tOF=QH#AG|U`-hvNyd|JB%s-|OS~ErqmRbT-8c^1C-f`Pb5Vv6WTm2iCZ@ z!uF0T952M<68iqk>)Wz_$m<0&XO^yo{G^cImYt8^3$pU?dq76cO4vU$7sosMGM7R+ zb86-?NH20=dF>*N@}<<@r>;9`4_H zefAbw51E;t2Yfsa`HVh_x5z#zpTCRdZ$~Iz7RM{(_?@_TEbI;CTJ@TIvt$XnpNA>i?Q4zMzAAjm%c`Pkhbze5$M8 z4%b)LgyWA;7e2pAJMsRpKb24ZZzin=>muK&ntauAx__08_`Y6LkNGL4c$%dY&ywS> z)kN|6%Usrg=_TPrC?8iNj@LY`m|oL~`StYS^PK%WH}%Kt!?aSoGLBzXL+fK!4x!If zM*arJ$Ihqt=p65k5{bfNIzkjg*R}{qh>w;MS zeNn9cUTUAr0qT##^m`UB^&cD`lH=|I_rLL& z`x9n&JNCc64!nPET5s4L!smIJ3)@qL3&)#<4s3tyYp@@~J^}k59PfvHxmmtnCS6|^ zUSGU;aqKVTW#jXQeKq!<*xzFxkNpPr`Lfcnex#&e`DSF`c$CX49<$%U*TX&%um8wC zOFU-(k2#0dTjuy{ZN>Qgw1wi;alADj#dBoeh?)H)u8*8wj#tL<{5W1&I>k%dmyXZx zjWjjm?% z|BRQ;_k;7#?ScJ9_K}(6)xQjiSGQ%`MyT&87p(){w;Fxg{VUc$din;O&v0D44br`t z*q*rmVjq#858R*d^O5~fejYK$^ZodIZ zIh~o;XHHMU@k?6jZn(e9>|-$hcl%jO0+k?mrikFS&^NQ~Ppa`V+3dOZVdUH}Bve zT>tTrPT*5xJ;0ZYb_2it(n;XE&t3|A&()U$KX3;5EUm{o(%S~xPmc5gU&8+0P#>hT zuQx&Q`{Kp_8|}yQ9in)E@s8h5@%9S$;do+Q3ckIT^VrlVLNg0#MJ+Z5KH5%T+( z+5ejr?~nYyqsLA|evTY}bDlbZ>Bml83Hu)&od9lWXa%mW$M)fCABObq_IhByy8^h8 z<|{`jUKFnf=s8gh`?H_tqxBNmA7JM76N5Bg%khXfJ|O#i9KVU<12S`bBK8~Dcj5EL zi~q+y2Q$YLWMkJI<&;`g~k+J9R%ey>}TyAqDKgW?+|SL68|O*o$r=)mVo?-3^)ubb8n zZ9QBJ>E(U6{ql4iFV5X2Z&Wkm?@ih0CuY@QesaC|eY4ny~A9LVvAzVK*`-9AUyk>fSa5^*l zV9YJ#tF_bfhvVxFQaryX`9Q%*9A7k3yjEt82gc0(wTIRN<@M8eJ^9*0*kAJcx%~WN zKeCzDA8wq)_S8Os*V{$gM~;@m{pa#wKa{!kD2@l1IsR5FjSo2ge1F;ZYoYa$8>dPj z|1HPy`ni7e)BYU)k=s)%#TRayDuwfP97TVy?Fg1P$1C=X;e1jNt&dvLkK<{cKV?5- z)_SC~;;~`>7U)5)r1)ex@O`3)e1-iKpDc;yZ^OM<9?TqXElTl-x+p$h2l;o6 zIiYp8w($e#&! zVt%5u{_gDcIPrbAgZk5Y^8I+dMsAPs?jOgmD{sd6GG5=dycN^SD83jo$NOaem)F1K z_>BGztk1kYE61-2bYcE@d>Ewr!TlRE$EOOmVE;HPo)?u5$Cu*uCV4$_W@i-Zqa%_8 z^_~5{!T|P{JpN>^@ZtE?>BjGu>3%#O_s=yH&#spIMUI~spm>pycJx!YyuB^hzB&G4 zfa2?N`SSYBRn-3D`F;6*9KSQyda?XC9$<9<%d?8glkZw?&y z*9NdZ;&_8))PIMld^x^dJU@-&@3jo#c%R?rd3?(6FUW9qeuSF$L;LoT?;fG&Gp~2S%WJ$G?p9VS8jh zvY!0I`gZJ}_~oal z;Pn zjO5|>ANHZ*`F~tq%;tBQv*m?mxJ{;rhh=8Lw~7 z^Pg)sQ~RL!nC$!ItXc`}Czy=w#X;-&Ity^T!ug-opHct7{R!{SJ}bwkWgnCK+gUy~ zt>?|>i`U-yelYX%h5b!OCXUx<#sA}YfW+~9KlbI>r|0#5^V0DBf_*>cx9WSu^8@3h z$2)(#^)uNgVUBlvnf-~K|Ka@?Q984o95a8!{!~0>-)vTVHu8r!fAOyGt)}z&nECiz z9`Wu!`+m%Pd}huMGy8kY>?<*|@5bx3Ug-H|`EL}DZV~bF#q*(lGOwidXxA)8KWxd; zg|I*KiY2%`AD`C?Ub0{w9B-v9l+DbavX2%o-J;_yNLUQVU$rCwc^T;3d?k?SWj zw>AZgLiQ!&IKRMC|9MAvb_W3BgiL? zT?y%zpG1D!sWXs1F@6lVtp)3cFVFz#uDT#_XBE!(hV!vK4%A_LKGToii&73(!|}3@ zdx1G#knaf2hqJ%I^Zo2I#AEg$;xYSu%-%^STo31;*+V`>E6qRLim2}q@RqI#)?)fAC6Bkc^vzT?qhz)Pi-64kIZKL zo<1*W0c^i>$9&+Ntc}1a?tQ?i9-P0)^HF(*u>8_#zBHBYM+&Vsl|6v|kBjE3*#C;R zJ}|exE{Z?O{t$E95hq+fb1V67%$^B+{@0G-_r!Mc9lOSGd+u+#=zQ(udv(xyot+e~ zt&8HhHJ-rnLhGe&xZbH#_t~J^pOEiw9hJ9x+zH388p8I+>kBr~`ffb`8feA$ z0rmkyH2+*WiqF@w@k+=~!3c78KbA+l=Rf=X%pCv5+lJ5Aa3_9G4Rv6DA8t*A{05uR zzxTH6hV+`~HsDbGR^UKnGjLS|pSLyjc)Wrret*u7;Pa<|;^P%kyeLl33-5ySmj&_s zC0@*b5zUvEP&}+0THiFA(hCCkd@T&(^OgNRj&H{Cv`Rv_e_jOdUnZ@$U0SyTt~b9D z=T~Yf)#+PP+^gYy%w;}0z8}lG z!jJ8>+=t~~Me*X;uVr?TzntBK{zE*@ARmQ&G4{#W_hZiUgY9{XAM5+>226J} zrbGF%Ps{!u`+pq&znS7wdfIWkUPtSz^7_Vkby&YL1K57ELzw?~{vZ2~nG{cv!$s4DL!gGtryLHX1N#pD}KL-=O^-drWc2>f89sViy*Cc9H9Jj`>mt)-rb1x zYoHCEKW_GW`>;N7Jb#Wa$lnJV==U!}BPCEjndSG4yC3>o>CKsm(?2=&F^7!D56pYP zu%xH;ya=50+~*BPO=`SU{pw4GqkXy7^?&_J=^M`_PJe3q zlMacW_tlQC8J75Y>!1C);r51IR`afJ0zYu(TZSc`?Z5u(%Z6R5{0~%r+pt%~yBmM( zJB9;lz3mef-!=IOsrzyHL*Fy(YuaO-nfC+3;nscDbv-{c9Bn^f-Td5-42!?J;@@5| z$Cvnh;lNJ}OZsz<|7+>#$(_^DSD$o<-}}QgKQ-y%`|Xovc4=GTTLKJ`nl{s#CP75`?qySvEx&O@&oZd2a}^51y9 zblKS*)72mUsH3_i-_<6HEVKIIkG{7hWH+ zs1WNn`&{e;I@R~?k0f0AiVydzfA2J0n3HS0 zvaj2)_zo|(^ca@-d|$k|*Rc3n=bq~`EPmI={@ic4UagP%MAD$)XimEIu8twY;Wt$zhp(DmP`|;Mw0gbuQTJKHDQhpX-uq{$2Z($SmO14fA7tPrT)D9nHd(J=j+Yy zFzIrAU-|>`^EcgM(xrT!Ex65;pZI;>|JDrGtM>WF@!L(h@T#SE7_L_F9S=T=Tv>Lf zNpC34x7vR&!%^kmoj87%Nf&?Z)-`tnzwiAqto*?jT<@GoSN!8wXIR#k{;$jLG3gCO zxz@VP_Zk-8FZD@eSKvOAEc%_lAc|dY!Yx8u-r#&G~B`#nu&fJT${)`PO~u z4;ywl^Q;~BJY?=~v?$Nooc*xjP=21!=^ntH?6TAzw{Bq%~{D-<*G*w7v$sbM|gc-_FI|R z_hX-tRa8?Vo;o)@vlV}G5QeP_PD+EhHgi{jaG zJX~g8?{`*wKZ=*j@lG>R@%v9&GJgL^PQ~$fQVOQC@9~dj_FI_aosWH!e>hXTDfUxT zWr6y_`M1b_T9B{=w$ECz99X{I#MZy16dx;rd_VTpF7*2C)5Z8k@yeUi`FwLJ|9t#^ zG;@9~lsW%gp8tRN{{0V6*W7-iJsy+esppSjsSoP;G{ba1*@u$&W$O87wwL&KUut+@ z`oWuTu*d%i2?^GRp1$Aks-=spwm0sZe&hPL+wTJ_6Bb%s-7_pc-@xbZHR;0N_|Lni zQ{Qo&{k%v}>)A#_cTLZ`=i2GEn>Ra`typ6H`Mq~cf9IiV?D5-0YJ2yF8D6_+uJyp_ z+fBNhZ{W|joBbs}D@N}y#}}^n*6oJHCp=M%JpA?Xu6)QF=gqLB z9~r#Gq|5$IUw(&SNmt`XlONe%jV}#vT{urw@fqKdeNB$fTe=;;Pwk}jm*e@5+sXgi zu^4^Gx9b0K`?ye!*B&{(-;z1=q5M`;f0wrpzgKO@-eLW%Fgjh~9Gq_Ho#$M%XO;D- z!iZsO{R(TzzXqpYc(GsA@43#^2X|ZDKMfde3e;Oq{mgH8tZ&3x^P11_k-iRV`=YHuiJk`}|ZT+>|@X_uz>t8-yJ6$^3H~s7v=QyYOJFSnOa~T%jZ}00av;8H? z_q+UeHNcJ+tIYPNRJ^|pU#v8Iay4Xs5C7{tx7|=~c%ZM(`pdOthQ~%nty`~h z8a~?IVI^PbFzh^V(0bwWQp47s-B#x%C5Bh!=UV@Dyx4F?PKov8b;Z+P86TZ~$7dHf zv+^9)*UlCJzxsI5wEML~(>L9<(3zfHY_0yC+W)(Ur>`$t>=ggc`|~2h?y6er`X3e= z&aSMp-np!3`jcam)4$xi#F<;|u{O*pG+a>=ux|fjzTrw&&|3A&Jj43~t=5e{$~9c9 z*27KsW{%;O_QTdSFJ>F=AG*XkbaSRT|G@YO>xru}43DbyeSdaIy5T+*FL2jn8gTny zs$p60_ulpt!xGQ$+mU3$M~}bFTIWsz4wM}V7=nev+u|1WW`;iD(e_d9m- zEVMuI|8_3=>A7ES*f-s<;u(kde_eOJYPc>OwjSK`6T`Uy<)h!JlWb+`7ef@ z#d|Hs3qLrQ?%AvA-_wpFHDBXs_`YGETHmMiweK2s^cGsBC%!xbc;KJUjo!aU zwf9duJX1B+vZudg*n8AvUGMv*Ve$VGe*AUA;{O%jAAa6!FY%DRkpDTuwoh}o(4YR zy6oJK$97J?{@BMIvVHC3$#dJEO|<6&(xUsV>GvHooZXya{b=6gxf`zBVb90ZG^bn1 zj1D^V;+CH@iH0tq0CT4DVL) zK=zGBX0G42+nV1UHsx6q-fw;TaLCjziFfp^yZyl5_>9N!-pE1gs%Pp&GywJPV0rvGQ+aI_ma<)nENd}|5t@GtlHn#GV@ISLaM*3>&iAP{m;U0 zrkndM{?irnQw?{j{^~z-l7OcM_8XS|^|yEL0akU%u*7fu$$#xIT&wzrmXvLVrTyMF zZ;Q!Klk$l#%G_vJ*5|yXbG>0%pL5yGYi3yaX4gEk(y;h`bAP?eaIacF_Oi_hhP$V# zRQ+FMxLvIu`_z^Nro6gN)mcwg&ow-G(r@*?`qyW4|2M4Gn{Fxi55v*XTq}I@zXQ8} z`WwSCe_2`dnqis0EWYI@hQ;^G{`n7plS{rm!=ojtK7HdE-CsvlJVEvRGVD|F%+@(x zFxz|7{N%DbK4Vzo|IPo^Q-(cx=CPa2l^f~r3^Eb;krw>1?@slHX8*n;71F;M7T-?wSB7Q1b2*j#s3&m-%qDzhRl5fBWgh z#d`Z{^}JHYGhC_GE57q^Z?PV)m8tpI=2h1jc6B9NL$5txI5@24r$6)Y8CK);`FQL_<@O1RUiJ-u&i&c@>8PoBk_dpdS$I)=}#VV?l2te&9px7?t_NKM^yPY zEc3^wlgmqV{>5jx`fjgbiSKpO{3gS7;Uu|U!{VR4>j&e8CBD+5u1gFDnscOnoAbGp zzyJ2r*BbVPlB`?OZ!+vse*Rsr+-5jK#g|g;t3=-)@l#ZNF)V(NYM&*#eu*EX+OOdv zwH~kY+y@L7tMw!6x;|#urTmcS{HF|8DPO4Lv1!94{zNt3_`KmF?{=xrhEqJ-t;^r> zHN$DXMC-b&e>S{V{T|@9fBru3yH5VtaISiOzOnabCA$5Hue9WIzcTDl@pRXB{m!s6 zuwUAnVTn(ca_<|4%l-SUZCmG*>f;p#4yf_WJj2;_yR8GCS~$Zhe)5N|Szl^yv0dJ$^b+zR6PmHe9X7V?%it8?Ff^Tfh6;Uc<7UeESdoL+8oYR0MQZ^J_1*qWvzzPS0-ZhpBGE4)-pr|Ic2-;%EM5I$*e1#nV1^ zZP;+8d#m-=K)vBK*Cy+`X^o|N{F(3GVRiqp*>Is+&-GVNwHYo~zu!1|x)b=XRXv7F zReif=X}@8I8vhQyJW#5~hvK9D{;pxe5`Xft=0k=ZjcL}xZHEoZ?_F;Bmr292-u0FT zj~bSEosagOFf8pkW8Wo)3;esRPygaF!{XoWsy}VG(7W3j{KOT8bG(Vx`!}93oLRTc z`u)kXhA;MSwsv-3RjSA1=`DM$eV@JBu;e#o*R_V_da|y(&an7-zplH!RFB`??b+7k z6K^*xe$ZbQ-Dp_+pttqkWH_RHocYh+Y&fXmbG?1{Er#7{z2DVW-fFl)`D&_vG%Wt` zcE=sS554P7!{YxPeB&;|(!YJM`JINv|I7W6S0+-G<%j{pRIc-eXwSFK>DMLBj>Azy7iBVZ+kD54`^o;FRd2rTYD6r}Ck* zKk^vxCDF%A%TI2bUYYU{hwMN1!%rB_4lAE)*?SG|QNE&o@B7XE!qGDyFf7lH)>l4g zxHPiQ>M8lK;e+Ab*3dm4F`OLTV;%nUM-A78cUs3IPa2M>cyX6~_~VA9|54u~%=L+% zR+0DA46As1U%2Dbh9hdc;s3+ahGqQxa_AiJ+B2Uq^{+|!e_L<+tf|i}haA?9iswvv z^Pw`^|I_umal~Q!f10)b7t7-RY3>MQRlMWw=e}uJ>Yw<3y1x+?|4(y3wGZ+CH2c;5 z;{WOV|I-{&zuyr5PqV)@$GT(pE5PFa>GMhZz3aoT0*n8r z)3yJnS^IyQWxZeV|1?YdY4QIwOT0hv|8#zY#sAaX*pX-Zf3Yn7pXOfm`%CfvH1{aK zSo}ZTUxnKWZ2wPll|RY$|8)DS@hCq|`G1=8OVG#9&&S`p6cwQl!0QK!PjuNI+Z}qo zuOc(Y_Wv}OXJp&{pPuiNctqm=X%=5V{J&Th|4*~T6B7SVv&0V)|4*~{QRSU|4m}?y zKF3A3_8XS`iT|g!7k@?kzgQOkPqX-d;{V06_gw9{-0*;|LO7)7XMGP z_<-X7X_odb{-0qL&r!{9o8yV^rsltaANU;dJKOIx=@L)xw!h4<#M`^+*1Jr)u=s!a ze6qdxf11S~6#p-l#sAYBRlc40f0{!ozvBOCmiT<)|HZQSf12fd;{R#(loW}-0Id85 z!`{+j>!-huVQ0Sew;SI*ldf3&KkZx8JDj%v7t7-RY1aOqKEL+=G)uff@&7ctOLJ}i zPv2khBgOyIEdH+ef10IziT@YNX+M0}v=3=-;{WOXOWKe4f10IziT|frwio|Tb8%k2 z?f+>`JD6nqf13C2-*5YWy8W$OdEWoiynfjl>w8~$%%S~`t!p<~k1u@G@qzbWJ?-n> z=sdW6t?mEm_F0~rWcz=bZ9V*IB6X`YoIsxPzZ)7&|5{T7uUUoSJ)e~#BE z^+o)@6@R(G_Wy*%|I@7fKf@|rJ-%nxBb5*D_7h8 zpXP&|F8Qm*V_Ky!Zk~5|Ian=y#Kdo zZG!FpC9gQ||H=Bf;{R#hrF=N?|1^u=C;p$_U;I1q|Mc;ftzKgLf3Yn7pXTMums{fh zz4l+%+5X>>B};7oPv>`|@@K{W)4XZHeB1wv-Cq1Z&EiLj|EJ4O{6+EqG_P0j6UG12 z<+p9oeB1wvW%2)FS^PiE;`@pJr}HEGi~pyY{XdSED86KDdz9nF@)nBMxOg7=aLd*G zjNP8&|E*iN7}D1+!2W3^#na>Z&ix;!Uns}xUlJ|6zGPY-*-A%$-O9rF3)b#+w*U8r zW5D+RELA+>|7n)W2VcY-HeCf!5?f+>$*4JhG zf0|GAb=v-)=1cm!Z2xb=c(3jMogC`1{Xfm8{_g+j?JpZX@BhWJ_FuX_du{(uv&1hH|4(24RA;B{|7kv|(#8Lqch8{h|BZC@*#6%utA=g=Pgwjv&7FO{ zw*RMD;{S>Nr&*3C{-0)tiuWh}pXQ5pZnynE%}MI_h~ocgPA(|4{l8xfkJ$cSN}=)* zl>etWIj__b|L=t#kJ|pgl5f11OUe%t@koaXjhFMP9LT61ch z&-VXvdM0ciFkE-u|I^$WZnFJ9&Fzsk+yB!%-Zy6Zf0_q-CT;&u^VrY{+yB$&)Bd04 zv14zu{Xflp$1k`2zgQOkPxF*o-&g#{Xfkm#ih3Yr@7dbY&mm&bnb(< z?>X=L)g;;epJthV5&uuK%)f~Lr`aDpU@gDv+vnc*^NVfYuStCm6#q}N#5)rIPqW0k z5&utfy;_e^{6EbSALzOxUo+gP=Fi3d)9J$E|2$l<^koSi2tWq*1Ht{FP6ps(;QVkiuiw;W&Ow3E_%$c#0ymOBZlkybFH72 zKWtdm|Ly+HgN8fQ{DJs?I{)%}eewS^x2pAt#sAYR>kEtjr_V1e{-0)#icco~pJwr^ z#Q)RWI$U7;f0~+)e9L8G}-FY*60OMFA||E8Z#wEe$g70*Nbzo%E8_x~i`jQD?=3tBU5|L?kQ zY`6VCSuaTZzpM6~_x~CP3T^-I$`jk{-`~5Hzb5{l=8#%XRQx~9MJisD_+z@&j`II>c^0er#ND?A&Ha=4N%8-5ealhv-QxdgcBpttUwy6CaFv>GdudgT;iAqo z+yB$s*C;)W!eP96DZQiT|fr;-iWG7t7-RX>L{fi~pzdBkQw@|EGEA zn9KJ6G!GtCKDhG#G|T#};{V06_aC7zr3 zf11UI68}%L_(tOYX_om)@&97EQu%+Hwf|>W-B0oVVp;q@%@TiP_ibM{EdANmUwp~1 z_=DpA>Fs6xXYv0ui{B^ypJwr=#Q%$B@&7c}s_PN|PnVDQa^nAKZc*hY{-5Sybw9-a z)BE>NocI4Ui;pM%Uo4CNr&;3rK3RRGVX03o1t$%Qf9U?{A;Uoxzf$>dhUNI;|LNmt z|1Xxs|I;k-2gU!3W%2*?^~m*#|EF2D7ynPQ9AErD%>lLkxcGm%J`0Qgr&;0!ivOp# z53BYi{+~X-__pHz#j^N+n#Cs+|1Xxs|I;jfp!k2WEdHNnIltQ8@cH$sElc+w(!N!C zk=|a~xA=dW1InKj|4(lpK3Qk`f116=-OAVNG3lOTb>g=f_D@#J^VYEUaHWht42xf> z#$$$MJR|;}KE9-j|EF2}OY#3S*N+$4{-5T6T0d9(Kh4c*Jy!AmG&iXAQ4=O)%>{le|mi8Q@)ei@<6)93T5c)8;L zX_oj;;{Rzbu1U20Kg|d0Hrf84z8~o--j(=&nkC+s_7$@=r+|7p%t@%F_3(|kbr zZsPxGF0I*Q`+u5?t1hzrKh4?7rxO29b5_kpYkK_`OLYBCRnN08edMda;{WOGQ`LB1 z{J&UM?Za#@{*Cy5`gp?P|7jLKQ2am5Io@5i|ED?2z1{ZzG^bW?vi(29s{F+Ni)Hcu zG#{)z@BhWJ_zAnsZ%=w*ME);{R!u?ZyAoa7x{MC{-0*KpW^@N@o!0UvhDwA&TPrF zUb*p_Qayea?*H|*hMg*YwfKKJUHotH|1^7*pCkUCX197@5dTlJ_(kIXY4-lz|I;jf zq4?yYWzgQOkFP6ps)B9JbcxdAPX?FFM+Ww#BS`}Yc{6EcQeI>U4r@6ep z)b{^0*YvC3v)uSGbH0l1T*81UT!w&U(z)i0{YwB->`hAV~f4cs9)%f|hFFj|r7oJLb-mr|H z|MR*R49ocWiq~E=JUmur`+xfUgQMsDKg|+PaLxRe%=QxBTl_zLe);|({-5TCkz(8b z(=6{3;{R!O$@dK9|7i~P7FvV5Up6eik2`ecpACy&JNfFj4VSCh*i z@&7c}b)NVCG}o%{6XO4Amg^J$PoG~{{6Ed&7fSp;%|6v$#sAaXqT;WL{};y+ndx-xR%i{m( z`xQvfu>HSS7XMGP#GexXPqX-n;{R!u_>toOX)Z3xu>C*Hr7Av|_47A#+7&FwqmP=9UTFG2Z%%H=a$vUaWQ|LOEb6;Dh2Kg~JH z#}fZfbC&Wg#sAaCm-{3BpT6JXABq2`S$sY5|1^uQC;p#i@w3GL(=0xq_R|7q6#pXP}26UG12tmFU1viN_R<$A>b(=7QF z|4*~zNBlp{;_He3r`hKyvHd^Ifij1+>A-tTdXuxv%KqF8HGrvE=T6)ITfOPL z|Cf=z*Q&htQHSQjf;8*LX^$CZ|F5h7eKhGWV&@Mpl%+kz?l0{vmic(>560tJKA?I& z#U7u1K#uPx{YmWh(%;0gwEtM<^?xP)Xl%Op^|8$H4>`V{JkMeKWb`3&lhHS0=JFl|Hbn`*vI;xX3igTJYQvj=wUHF+amJAta+?!HI`RL$)pFkd6P-!?Kf|g%N&G*<%4ZY*PqX-4;{R!0qI^^F{|qla@BfWAo%jFb z_Y)HTPxDr_-mUn5iyF@Re-|w}@Be9Dq4=&R@0ot1`@CPbMy*#X@&E4XJn#RlS$^LC zyJ7Sich*R5P?`+xfQ;-fo% ztK#|T^RHQBMWZvkU5)?L_{QXaOTu#7|1pf2viN_R*DYFL$N$s3VaX!f|I_&qe{at!}Dt=-54DVOni@5rFf2kibme%Dh{@?TWpPiP! z5>I>E@)a_^HoSesN*RBf?f1`}Z(aI{vxa4LpxFLuCHc%NEbQO7y$P%L2U9-6>i0#4 zrG2UQ55wXkH$8HdDSu)0`z4bu@%{W)U1{!bzWO~w^jB9H-j=_|Y6;Hp(!FaT|I61T zSfBi6!}O`;L$<$WDV?(RM0C3N?g86xlgpVb3{QXD@xPgS@8~+Jvu}IAV2r^9+`C+G zZ|c3+mTg(h>cx_6$+Bg+_XeRFOb>yCmI@@4bV7OnDTIV1q>&I3(hDRcPeOWop5%G+ z-Pe8e+nRIote2Jbe((A||K)4#J$v@dnVB<3bItGWP56O!fm%|~5O|X1ljHxLcy_z{ zfz5jp`G4Ze4(xXSPkgkm$NfL?sork)|HPN>+!h^uwK9xHzTa1VvmuGe|5N`f_wMxk zzc_#E59>nvX=`8kr?r8v+Lg%vQ~yhM_PGBiKGnO;{XcClJ|OvjamN4C{@G*sfaL#a z|H1fw;_W?&{6F!Y-3k9se0bY7_y5GD_InxsPkjFT+3x>|CuOa0|4*EmU+DhdIla5x z|H~>Ua{o_E9w7eT>hJAw{}2Ae7YhfjuG?ql$a!Ts`Q`5a^?z=^`+#fK)w};EF0=Z* z_mrc1O@V?agzcxSozr_z-;{IRP_I>XEi90(xqgCU6(!b&d^W5(% zFE5YE-u0uvMb#_a|5JN$O}hJkf$K8d{}UI~tgz>)-|7GL%7pJ%V9#st|HL&t+0l0^ zUg&@1+PR+3x3;f1dhz?u2W~i4Ngh&Q>i@lP&exOpoA-PzaJTsz&oBLI;Nbrajt{&4 zH^^HKl_mVYLB@~y%Im%mmhUj1&i%j8f6)JnvHO36jL+x(UySkpw7vL;?*9$8!|wkL zGV6E$FSfkTmf=?*9$)Ci5BG{~Khs$Nj$;yZ<-H_z(Dh+g_aG z{vVA0C+@NRMgCu$@&ClF<}2d=iTV3F{-2mUL;SxuxwU|Bv+#1+O9uTvF@75U-`hqG`hS*Ri2v8V zWtQjv@%MduzS%$iv6=4Et+%|4ynh_*UwwRr=l#`hSsYzou&@80U!3l~Uzg=AK7Ylo z{!h(FJm2E@_}u4v1GifH$H#6DT)caA^hkSm;JNnv82?Y>71b__a(~zvc*26=?*D21 zBj*hB{J%4E50QT^2oVgD6d9tZxPJ`em3 z_x}cuzp|=%3IA`9)9m@S`+tKx$La@6&{)?=&O{}b1rSmXYm zxarb$?*EDFPbK`nIOG3`+b*^1_m-)FTThio8{aS~@K*D?&94ZIuVnd4f!i-#@BW{* zug%tn|0kCJC*Ed$7yh4^>&M{}=LFtzpg4N4E4$usBvZHR6E zKe6o(fm_Tcd~D#?fw|s2GX0e#w*0Fk#{bjj*I?H#{6Fz#TOa;kobms}O}2jgKXJ2t z{`h}ld{6wpIGg_y)=$2g`9Xp41M&Z~y*wYq{}YoZi~lFyX1@ERjC%riTRtrLe_CJ5 zp(6MH#BJtx;s1$S&F{qj6StU8i2oGwBMN7lEg<|txV#r50@sf z`LBWb{xqNUNga={9iM?)?Rdfe)Aq7{{6Fz#J3jIMv^?{{{}bce+voL!=8x}({}*Tc zzc}OniODC%{}XdRVZL5q=7;~M_JrT~(Z|J!^<@X%!pOcq~|Ch`k4curx zuKRz3*QcgamX~Syf4VTXE9K(?Z?fm{?*9#r-)Q-n?*9$)2CHA}{@);1Zp}&fe}i0M zeg^)Z?$7W~@c+cCEbou}Kk>4rCGP);S6W^c`G4Z7+QkX~PvcuXdH4SY8UM-szdi(Y?-w*#!oNIY&_F_qPmF(u|0m8Sf6V+pG4-AC|Kg1QCnmoV|4+>CMf^YULc8C>{}V5^@yP!R z_h*(zjsGVmzZ(BfjL(Pv7iauGG5Kite`50ZF8X?3V2)q>Kix0pn2(45CuaM}|BEyE zf8t9lFB<<(Onp}TKk=HD4EO)Ug?2r`{}Yp6i2o4_>cI1 z;?&~oPrR|a!2LgQmH9&Wf8v(*c^Lms+-kq4$^R2KSzaCfpSaTeI`aR-HFm%G zk@OFjgx_a-*Sr5GuInjr|4-byBisEyE#GGE@8SOi-m}jAKXJp3GWY+){GP@C)Bb_+ z|HK=6i=&^8c`Awf_J1ZY`{$E?`Ak^frrm|nK;vfvciQ_jpMUgofqCEXE2BOin7qH| zcYh%;d4S*h{1*dnK2YZVpXSrCuOzy6+gHN+d4DwRsjmj^w7lX6XFV5~`UFd__3rmUNBqAy z`M&sn;#zw@5dTlt6P73cFV6UX;`XjQ_y5GL_I@D#pSZSrh3Ef?Yr2-Z|0gCd6#q}_ zm;Wc0{}*TcKXH@gBjW#wsn?DFC$4E&;r^dKzYVpC{68IktE&_KpE#=|xt>#LUUGg= zS$?t)h#wb!9s}e5>3I`A(OI`_Db@3)O8fgd{-3xc-M+8P{}UIlG=Kdb%L5#I-i9yt z)U(}ziB6XUz!|B0C&{-2o71OHEq z???Wh7{3VrPmI5W|0l*rBL7c}uY~_6#_uElFV5uuiK)+u|EKNWR9x)-pE$R;)crp_ zuN*gJn)`oxUb*yQWAp#?ymH>iMEzfL0Nwu^H-57Fe>59MI66Q48fo1<|h+B(_qQZOb3+*j7Km0$5j{8axibv~(nUn-~8175#0 z`FiD)XN!vr3R(w8i$uHUmK6pvudG^R?SoGDJwt*#=&h`A6{1qAYJi0Y-OV;YB=Ep68 zPqvsZuxN;{+0m0U{_D0T`+r+=79_Rjk4@g+)MJg$Z`_2jNqp|aaY;OK+TgWA`+yAr4CC%^u)c;G(OHAcd|L@#k$@_ymK>WWq z58Rxn|7(o@C&t&r{}Z2oZo>Z)lP`(?CmuEYJoo>^BSwty{J*CDo097Pisk=}dh$lk z|C9eGW<31Ai=Mr~^Yvi-zb}8`de8qOZ;$%F&%JQQ{l5z?xWN6t7k+x3`+xZ3EkN+p8o-Xx& zwfykm!`=TAQ!g3+Py2`MeJX#5@dfe!)J`6t-QR`r$B!7s`yYX6xBJ7u_=cYb@Vf1gjY_WPbW9eAt>apzjED>cra?o-6jb zzV-N_2>(xf#W%8{$GJH^?(2V_&)dlR&8i> z|4+PrL%sWd;_BKK_y5E-bxrR7iMQ?8<^G>|XWx=yjg|r{xbEywv@_IRD)0{{}visQ)X*_rw1a;|t>diSYyR|HR7wi!=UT;NuDZ zPy6qPG5((zA8`1*1)=}plh@c8GL$cTz~)!`=b!c0+Gr-u?*Bde>byif z;GV7S|LJ~d)%rE=|B17!7ANxm2Jffx%(tQbuiD8^@ch5Q_O(sR-T%}5Ruoh^7tyDXUVflYzd_w%cIOG3`$veF4 zTOSVFx7qxTzwLP}aE&dG|EK)}WYJwm$qn zF}@7`pSaU}68t}LyX9r!|B1=l!vBl&PxjrP#9N2m7dTNL@Eu|M8+Rq@|7v*{|4-b| zm*x3?;`*KTKB@VC;_@9Cp8qFa+neeBpSance|+t)Z|py>W47n<@%Q`-Z@VLKlZ{_F z|Mn!l{>j?{xAxiJqnchHnEJjGEV z{y%);+Q21yS4CZ?ujxPi!L&quV5>(<{@*``C49hA^U?7CE^C|R`F|zbb9sK*fB39~ z@5lT8zj*p+|Fwr_c-~)?J%70KPY3!ho0jnX+PhXpKh56T|Ca;PJkO%n<~#F|zWxzE znL3bnrZrX{(CYtc{!{7~xc~Rp_sw*laf104_(pp4>Xm{XZQ)6_(F}|0iy-`ce3Q;#~8+zWYK^ zSYLtpTljzad@JpGG45bam|vA$Pw@XVU-HVx{}XRCzmNPsF?nI+|B1;j`|yVsgwMa) ze4nMim>0O#d_1dt7`V!Op_%ow0#{#JfnOEI!xzH;)A%s{pSaC@A^g8M!0~Kp?{nChgQEc zF#ey__e^5^Kdm4C@9J|t@TB%9e01j{Nxbvf2Ldzyj%9BP%=wA`r}1F?Kh3Y+{BZLB z;*9?nXZ$}gd3Mj7doqlNPxsis-XzBV)B30n{q2p-VLm*M9hguVnC~b2KlSJP3I9*b z{P6#@{V@KYnEYJ)KlSJP7ynO;k7vij6JqLD+vgh?zn1(zwd2>?{twLeJN}=xAIAR^ z%l{M0{}Yqni~lF?IOO?`kBiCAGrun|`FZ?P`(Qp`p_ucX{68^yo;H4w82``43rziN z^AiJiT7IC-KQPPN_9d~6ADH}4{6CG~VR?}Fe`4l?|0iy>>jVCuxbH-z`+wpcN7vi> zW`_306BX|N>H6B7$S*7wZ?ybE^8dt@mRE@Xr~A{o1FPKs6Ibmna{n*zu2T2^#Ov+; z75`7Xy=6|+vgvf-&f2N&|7m?S<~QO0iR&zHjrzahj+!+0|FnH=R=<<{KXFO*boc*s zd=*trb^lMCUOCPEKk<_C3GV-iv)7Ds|1Zwe{}odY_py_oE!O#vTbbtmpP2kW^8dsI zYbMzF_(EXv1YiF3cLNuikB9%K{`iCVf8yM#8Sejym)iQs{}V5;`B48?jNeB6U$Oi@ z@uYQ=-TxC$8T9|e^8dt(DyF;tC(g3GMEiaz5ofNO?)iV>i7PfP_543Ez8?Nxobms}*>-=1|0m8e-wyvz_h~#>f8?Q{NZ=PfUIv{-3zQd~y6gF}@%EU!3v(#O>yr6=5jU7mi2tYlt(Lck|0iy?_uugU#1(`7pO}1T{6CFXY5Di$|B1=3BmYm_VBd%2 z|7m&h?C}4@8@J`T{}*TS|HS0wzvG%GllZ|O^#{f;d|%P01LGHd_}-_I82?Y>weQT0 zE_mJ3VSfC+zT?}U4b1QBDVfg%rv1Lxe?D-t{eD>RA72REZv2yZUm6I_aj)emD{}Y#VWJPa2{gc4dAIAUF^`*l6>j&4o9NL>L z&;Gsd{8`|}`q}RPssF0RneP9I*S1#d$W{-4(0VCN_Kf8uKM3CaHxS6V(H z{-3z6J>C63aaGe&_y5Ej?fYS1(;veAhSz@bkAVwomPTKi^yk1!OLzh?^!L-UoLSL- zz4W)RzVZV514FEx`h%0^b(ZS+2marvw#|VX?CGKT<-p#7~f&S&aI_-{)K;l z|0l+8!~YW(ng4V6{6De$KQaDa`OSO7^5iGs z|7kq=e`5K6V#dS&i}S&24<|AHpVmiz{J%Kk|Apl zvp)R4IOG3`@z3!8#4L~hCvLZV2I~K6dpZge{-3sYQBJP=e|lbd-uMab|LOT~_UQ5M z|LOT;?%0W*|95hJ!vC9Vc{bGl6)%}O!~MU{uS)oUbu*{A|0mvMd1yBcI}`es6x-ih zue!ce=?D9|y*7BL7eQ zsi%woC*EX!9sZxVr69-sKQVc7_ z5&ut&e~14kW_$4e#B4AApO|+1KQZn2f7(9wAO4>hKMns+OgsLcmWT2G#Pa{dhDgP$=!P+T;2towiBt#-Yl{;&LijAFYUTmGMTWnm)! zPfQ+R{QC;uIL@i{K z@?_sHwH|M(zn9vcT7MVcKE8dayutEJ*4>2$&a&q+JS<(34f3MY5BE* z@&By8eG*&#ZD4#h%f}7O_~id-Jp45B|HjQt_II-&q<8`7o{isKm0lT zzX_!Y{|_JVukXEcfDE}8PEIL<@&Cm5qjO$=XXr2gPvea}e`K`e`n&8|aKbmF9xwi% z7@rXTPfT9mmhaycwrA4C3I9*qLtY>LpLpcCXGK*%xIN4tzw*kpLp;*hybN^2~$?8et z|B1PN;{WM*g7N>voDcYaamN3P^H+XwCLHf9|E5(#Ji{)y_{}z5_oBM!Q z?CJIVzc}OniOKuJ{}a<6|4)3wv4igaiElo#+xMh( zz^cIedbdWEZz~I2oU z)m`rYl~>e7TOKGF5EoY0MsIqmU?8__kNbe|O+PSxY_I!(oo9 z#Jzn7-2W4I?@IW8;@`ap=kI~H9$M}GpSEv{`4RYkV*EY)Ke6)v#MHOJ{}Z>{`|src ziShaH|HSwq_0~|HT>qPmKSD|0iy?_v`Wh;*9?%roTNu4@`Yu z^8eIcIq3h1=}-QjxY7PTkN+noAA$V8IFtV;uD85F{J)1EN^}1Y#{Uy$jSz_8s_%Qt}#3J$Y;32CE;G({f8-^11%_o0|fYABO*@@z|gEe`5ThMV~wq z`q%8s@%%rnuXaB^)alTUUrGL-J)^ek@5f6UY`&L|xT?SXp_%UcZL~awsQl9Yt3NY6 z;rChI#h*@}2wY?Jf8P0l!~K8TJI(X`;NSmxe}Cp@rn>Lf*1a@(f9Ib5pJgU|zkSD7 zx&J5LWqt|%pLmn)zo@h)@cQk=?*C~#u1ENP;+a;D{H5nM_dhWy;rm5%&vXAzJbuQo z=))s6^*>iP!}AGq%jUcPC!TG71^It>{(Xk~e`!_I-2W5fFWh%ueb_(6=5u`Mv5jH> zk*9gL+@W<%h)O$+SryKBSewaT8CynJ$XVCqSm&lDKH6aP=2 zFMMxFepo-g5dNP&Ul{){u=#WNf8q|?|M-96UaKEkaOL8#eLDvIKOGO`0pkCOyUZuV z{}YqPXa5h3zjN1h(*xuCnI93j#rj+Q#K4;_tB9hx;{)R>ooc-(aGm*0_cK${-1ag{Al*z$|b6abWhxs}Eis z82=FePvi0Zga0Sy`{#Ezc7^r#9JKcV%>UDT-~sdh#C%`k|HYTb{}bce;s1sH#`u46 z#{Y}=$Nv+PpG*Fq`r}`c|0mvHJ|6y``d3??CjOroKM(&;*N0|1AMyXho&F&AW|10Kw3;aKEr(J*W|HK{U`;-5t z_2Dnz|B0KdULyXVn0y=Z|Fk{T_BCRIiqr(`+wr)>t?(ECtkKT&HX=d&gv=d|HT>qPh4RB zApW1Y(EL2||HSxt_;{S=$*G}~OKYbs<_Wf5Pmj5TlU&Q~@{nd)q6W#xd z^Y8yTKeXfbUHXMZffrkSVf;V!pJV%f!^D+gebWjrcK=W9%kwXG|4+O$cdYw=;X+4BFym6pdx{-0R& zf5rHG_qPfWfh{-3zm{6hRcaarT? z=*@TS30!Kwck%yp|A;S$|0mA3-^ciW;<=V5i2oO7{68`NApW1YWYbFb|HO^$OWpqy zlmCVPC$2I-2meo8X8Q~OPxtG&8|S(IC+73Q|I__(e)Tl>|HOs0Gu;0ZlOIX_-#9-q z_U01Z@279P#Qi^Ukq__k#O3A-;{OHiw0eu?|B2UGeNp^BvHZU{qPu$d%sQ)W&?#^-l zPuq|GhW{t7?ap=oPh4Z|_ObohU9#{UyC3G)BM_>$!R#ToxE&iH@g#_n|Y{{mY+AO4@NFIDDu zvVOVyf8q^w%c2hrdnL5z*UyYT*7J+NrS|^Y6Hos#Fg_ptpO&Y7IR2lw#@;8y z{}Wda*8dgPwkGQTiskEB>MsRc?thd&zJBYb`RTJs^=Z}4`ta~0(_|4-xN=Y8hSeMx-Jg581fEe^Er zNn-pzEzkDg|A|>2`F~>a_sIVf7i8zS|0l+8!~YZG&*A@R|EJy zCtkH+iTi&`9=+Q00Q1uqy8kCGFUoZPPyNYHyRG%+aD2i)|HG|ed+_t--F;iwe=z=^ z_80kl_jU#{U!J7n1*{`Qo>oe&(Lgj^Bp=r~WYhpP2RG|B3P2@c+cL zd1qEGe=Hv|4;4m|8)LQPZ9r5oIhq{bm8F#!}+*rSGs=u4+wEKVJrOQd!8uIl@h?9#kc5R$3elVF`kQ-Y5V)I+#{i&xJ=L=HWFEpPh-j2T( zXMD3bPcWb9f5)lIr*dk2QS8I`c>mMq7jL)tu%!O~;&aj*+kdIY-@h!MI^NmI`zuP} z)bUa|^>`#d5C3n$^*0SHNKY%9eZdI#|I%)_(ewMJ4jehp&hKr*`_^J$r~55C3oSjh5;5(u}fEBhGREPmDi@|CfF58PEUY^TPjYf8;vP z|6_doKWfI}|1m!PpLmSbpMBR`?h4DZy%W>!wtAx1d%hsPpxu9j_2bjo{YhZ_Kf8Yk ze8Jce?*D0fMvghp^Z&wpFHHDP|LOBsV8R{#pLnjF zZTNp;t`_9~iAUP}$o~_kpM3%ECk5_GFL3`)?aS@=75<<2Z1X9p|Ev9*ZYMnTf5ppe zefIk)upz&%0&~9L|7{r7>ptKltG|u^C&q@x|NG?~+ui@;a)AFQF38KX`}c;>zs2$Z z$^ZLtNss$~dyXA(|4)3a)d&7!UQKAfYS90?`m5dU1CsBD|0llj@ILqd#HSDLasN*& z|4)4B@%`@qiH{xH<^G@e=)Rqv|0mwHt<(KK&F{qKP0@@^o&OmCoa!O_)rnwm$%#fzcQ=$d+?L_1LDT@^-Tr?jNqW>^eIi=Y@7S-ro1R)9(N2eyZcZarghkExWgS{-5rbaw^N+{}c0k zq%8Y~{o*zDzCHPW;tlrqcKkmv^+JA-_F}*8mo`{^QT#t~!>%&-|HReX6aJsL!v3C) z|0m{sdi+1}4)f9Q|HO@l6aJsLX)ym!yxAE4@4io@x&PN`{qg_A_yPETV(QOXy~V)$ zto|_mpW63W9ufYZc#A!so-_8T{8ybG5K5O zbA;vbdEWSzPb4w^pZfQj--rJv-eGU!3v(#P}2Ve`0(L^8dvAeHs5xj8B69 zC+6?X_;Q#yw3jqPX3>m_2K`;8UIhr_BDO+t}q|`oZGwZ3|wvbif1;xvA?V$;q#H7xaNO6W@D}{a-Pk2mYU!dPq<0y}Cd5Pcz*2Yqk7@j{m-*Kch0?!|{9s|L=;66aF7ufBbm= zslI8Ruh(q#fbsv1^-p#Gug&UR;r|^NpYZ=Wd$ZjCd+N*-&-*(-UYzCsiMx+iyZFegY|EKXsnje7wr};#S&bH?tongNDvlIT`viqjH|JPbN z+xKc=-1Cf9g+uFaDpH?|=M1^@s8Q z#9Qt7#Q#(OPV+zU|HQ?I3f=!x|5e9I-TxEguUb9jC&Z0|{-3^Idm51FQ3_R!;7O9>4AL}0&KM(&;?XZ2m zMVcS?Gq!z!H=B=V^9%j^tlqQvk)fS@X7ghMGoJZgNo?C&tnus2AIAUF`eFP(agF(l zul{;b;JVjsVE%#ko=W8Z>3(qci4E@m>F<3_<_F^c#Toxkywmao@&ClzkFR(CPuyU9 z=DBN%H9q-+_w(qo|B1=VHvcs2zvew_-Tza2>%R5w|B0LX%DKLT{&n`~nEJmuzDvz_ApcLCw>gvR zSLnai^0lb{tMN+h`^`Szz_nE~-T%|_<*UZK|0iB#Z2798|B^Km-T%{g7nvVN{-63! zSU1)EKQTTY{$HH&|Kg1QC&uT){}bof^7wyo#{Ua!ejWLLV)=h!@)ODb)A!ZNHB;RG z6Vq<)UuaJ+pUU@VVEjPp|LXn=#{Y{m{$HH&|HSx__W zQ~x*4)c=h$^?$|b#TQ3MzgHHBH+n`@FKz(FG+N0%xth*!@3^ zms398{Xa4JmE`}4vn<~Z|4)30)w9L_6VJ2yxA=eJ%<6gW|Hb+4_iRaOKW6!Vx}T%o zHvXSDuWFY2f8reTQStu*+x;E>pSaNK`OfX!AGn~|{JYtQk~rs;BZ2X8r7XV#~=|0m9Ep6C9bnCk=npLmt! z1>*mSORe5I{-4&jrY+(BiSs)$y#B8^&*~ME{}$i*uUg|7rVbtsVbQT)8#d{lCCnneP9^8UIgQ z)w9z5KXIMCpGEy&G4Gq<|LOM-e9zPGPvTj#J{Y*h^7bCO^wGd&y&3NRX?cDxlm92i zpUZyb!zKEC24BAFqe)y@{_)TszwYbr_(Wjd_r(9xd|ND!4*yTwZ25%vf8r*q=ZpU* zrhe|RT?1jf_T72WKR)~Ez&%#)7ynQ5h4KHyjF0~(W_FZ5B2u`9{GP_&WCrr z^wYrP@!|ie9VY)z%=v`>C#D_$Ph4yDg7Nq} zJPm&i|1Zw?e{m-NPmJ$(Uos>Ke7Bjakk|#;s1%LcZmNd#_z-bi}UcYy@44Y z|1Z9N{J%Kk|B1`eS9t!P82qPmC{w{}*TcKRvI)55oTw<3Hj5 ziOJKl=UYi^&%Xk*yw%4_V*EcXkB^1_C&rh;{}Z!3{+}4%5dSaE_%m0h>(;v7m93QlQ zVEz4pncuxXPUdS*JrLSCe(?V^9{U^rPt5U${}*TcKb=D=4p z+uw_yXbOC6;iRbQ+##+-M~fX#r0>Pq^sOX5+l9EHQep6mI4V)=h!`F~>kzst|OEiBLe@A=hR z1C!rq-`@i>e`_^eUz$;dFZI;vdk5^E&iy^O@Jn|O>^>{u2eQ6{nL|vTU-ZelLx1xA zZdiIx7!St()A;nq{}apq3vBg$$^Q%UH($Mc)euiIACLS$^&e{|1pc4q$9&2Ei!=UT ze0%W!v^@Rs|HNlm9v}Xn`0SDAx&J4|XT<*#<1^y_iSc9Y{xa}H^VckYI;QS5jr~NzE>W$<7 ziRak$4*yR)?3}aQ{}Z2U`_q1Zh4$&g&yD`qh}MDq4ZZHSO|-Lf$~i58xxS`7(>U<* zKexLtm^OWy`+wrL`i5xtfx3Y?xA(X&cvA9PI`jR={}apq6W=&k|5tqG)Ist^|NVBwF82X*${O7N6W6xwcK`3ux9@iUucLd9`+wrzy~o}E6K^`0 z$o~^>K9Z>aD<J=qAq`|8G;~X z@-u;{Z-@Vao|4+-~590rc+wFNV{$G54_;{S>9NAUl|_#^m#V)Fj}cKSVGe&j=0K22c!kt2^i9JtDS z7W_XgkKcm-r|pCB|HSxtyT&{anEbzoAG$Aaz4>l07r!Ggd6M{l8h^FDe~N*g{R)s|MoY{wD&_kQA+(s{J%Kk|B3656ubWy zXZ%0$M)ODT|HL&1$TzzsF!e|A|I`lS|B2Zj_*0_?Gy8Vtl|CHlOa_^s5=} zv(X>_Z~W?n|405G{@-)=O!quIo{!-Fy>8ny&;P42zYqT}=aW<2|Esg-4fub*ACvI^ z8qN2^|9fBW6wm+L)R*D@-&?;k+5Nx1<7MvuiJPsSB>8{ha(h07|0k~QE_VMMC{rbQe_2ey;2VPq@+xS z-TxC;b}o1SFV5uuiFy7({-2mU1pGg7QR_nY|MYp6+4%T>V(L4Q|0kv%6aJsLV$%}$ z|Kd#kU*PUbBFp9p`={lA`Tswd78pOSV#1Wb_+SIo69d!(kIutu-TxEsusk{ZKk-(p|B3%6=6Zzx zCvLIp8U9~j^R4jz#9UAC|HM4sv-+5UJI(LI|I_tE{-65G{}baMT0U1;exv!|4}Pyd zFnMJ6mV7cW_1*FRv^@EM_nZ-9nEK)Pf0}Ql%^&|yj1P|g zC+2#I|0ni5So8nHZ8qOI|Lb@dpZd$^e|Aq`+VTIi{+?s&-2W4In-7TpC&rJ%{}WSR z*pC0e_Tz?|r|HT>qPuzTB z6`xPw)>HU~GXi&Cw!!^Bt*^`KkK6o<#rS(xPd$mPK6|n5H_1QzL0Vg2@=JetRZrmE zCo7^q|9F33?*IN-c4^=i+aK=#4c?E!?*9!kd52aXJFFic75`83Yd==v{$HH&|HK`3 ze}VrOXY&8Fe>NQ|aQ`pP_TvzQ~w6@NAUl|HQmeH{}YqfW%bcRduGKf>Zb>uvflE5%>PsWiRH81{}WGGGt>P) zoo^G%XSx3;Ua)SK`+wp~%4d-OS|Y}e!~YYLABg`aUa@|T`+wr4Ha`BJIIC=e`+wp* z^Yh666KAiV<^G?(Z!*fKyZp8qG#w)(^Pf8wmN>F)n&{Pf}}?*EA| zDVga0U!3v(#F@pDqdU&84xCXmiTkI(^X>D%|I_*wRm^t(PrTIfDe?c}jQ=O*{*C-U z@e1<;@&Cm5foVs&lNkR`_jk0D|0l)|#QzgBKK`G0rTK{Xe`50c@c+cQ3*}QIpP0_SG8rk|0iC*#qzw({}b12&2#@xyv}?<{6BGt<>lf3iE}JJ5&uv3 zzZsT)HGA82fwLMGy8oy9<>JQq?*EBPET0KQaCr{-2hY|0izhEs5Ix{>jje5BQ^&#{={Gz4x&v0`vR* z)lvO{$@j+p3*%Y7H~ycv%ij0F{}XR9|8T<>J`?8GX8zq9=6p7ZUwqx?0^{qYefycf zHRj9prGH_Ft)A}();=4?$N$T@|4V`8|LOC9@&ClE|L^xa7r5Pg#9@E=dSLR&&u@G_ zaP3a}d)lMl4BTe#zfKzUt-vka8PSa0-wsT@T>L*Be~p%phyN#Tvb;jbei5t7}-TxD}+VPJ67iauGG4-+W|HQSOneP9I z$v?*b6Ia^%2l#*DMtk4*#drQLa9w+b*Z);J^}+G~#I<&PCjU>oc4H#{Pn>V}8|43q z<^PGxa;HT{D*iispQPsh<>fAO|4+}aiqkXQ|BEyJpBR7c7oXW&s^>Q_{-0R>U!2MR z6XW;c|HT>qPfVU5{$HH&|HR}s;s0qqF#eyI_2d7=dFxkqCoTWy|K1ar`QNf^U*N3t zW$yoJdFl&O|5wcV$o~`Lli>e}sW*)OCuV!`|HK96-{Aj=@m=0}`N_ceLHK`ahxeU- zD$EaGZdm@MN&Khs%R_&BrDu;{k;M3adR~P;g#Q<3{J%Kk|HT>qPt5rEe`0(<{6BGp z)nmo~6R#^Ma{o_E-XZ>-x-!?f8+mYJdRKNKk?#B%LBLkKk->3&vE}x&;QfU9_Id^*s8%t2Y&Rf zQa!)N55fNvj~_qY{Xg;YX%~6@U-8OJL&EHG)=Q0+~P1^oc|1Q<9%T3AK zOC2wjvlb`&gQ@j-mn}}t?_0SnIq$Dv$^V`+m&{I{|I#^0{O|fv|2O)7W7w8~Mej%p ze&0nkn}^tZGW@^LZjApYZndp>Zs8FB?yh^?|5N+BKKGRSf8u9ec`1?qw?5$u{_Y1a zCi4FV`Q@*FIVw5THt>N#{_-uM@?e$dEz`GCC`whWYyPb&XQ|CIgruX%yV z^GVGIOx<6peBQ9Lq9wn3VBo{GH+ml61%v({HCIbU&hq-Y_Df%8X=ipc&|`*_O}#{Y{m_YxX!&iFCz|7m@TrcHGJPuo*C zeX9F^`aJTcOmhEEJaN)A_y5F`CQo<&Ps=Z!JJ0<;an1^RpVs_8^^aC8@%+EQcKqW1 zsXyC?|0iBy`GWX=;wk5z1#+n_$2gLuo z;vYTk|1F<1+5JCp&$`m6d7wVD-+pwT`+uFcZF3*+w!?}1zs8bo_y2A=u+#lN@ePOe zMg@6Q17h<3{*+r8`1+#31@ZsH zd$+W^|0mwn*5Ur2=DW8eQU6!lC;w0T1IGUo_ipKS|4+Pkd&2({zi#IN_y5HAoW9xp zKXK!&cewv2ZoA`d_y5G(uYbM!f8wswH@W{O-h1Mt`+wq!#wPdw#LaodQQGmmFyFe& zyr}ukyn*+As@HwMru=o$*I%C-__D5j(Smp94t!}rpZkGbJNLQ&_v)K=xewTP;F$Y= z;$Exw`-%5u4~Tc{JK_0%;{E#*`G4XgN3L@JPkhLHymw!h9+p3NB;o(5{h0Ajw=NI! zId1*?TbBhsbmHph-i=EGA3k}F*Z@Rt@W4BL+{i2tYk(|zJ9_y5G(FHQFS4xdP7 z>I28WUw2)eoCnx_?DC}cb$ho)4_xxo{z}V3ZXNw(>D02!ME>94{ZV1pg*) z|He1mJ;aBs-sPgZ0=HVd#c1xE`cLL1{5iPz$vXnKneTC`_4XmQ{rj=s-xiqqjeofL z^?}K6T0Z~Qz?C-N-JiZW@VY%&(Zic=3S43Jd|&$04T16b(r&vxFuouDpN=2+-lwlk zYRCW6{A(-^5&!QGw@vr_zbbpag8#Swm1*w(QNP&gllA|iB;n7kv*#hy|2_5CRQCbp z|LyOd;`x6~JF}zWi}v@QTAJ|vnk}!B`oH2$=I@aICti1`!u>yS#^!|oCthqmG5LSu z^9m=p|M!beOm@F;e)c5y|NeM>!bcoC>n!*GG{42O68V3ce`(fa_y5GR3odg1Pun{^ z`$G5s#7ovrb^lNMC%r1o{Xgx$QX)srCKYf$J^r#Gd~LuHC%S{XfmO-h4Xz zKQYVW|A`yyc`5#%xVm#benL1tHrn$_t6vzny?eR)f7(Aic0A($iEHfq#QziHBjNvv zsb`G;C&vH8{}c0kX#O8Z1#a11=>DJPw`FI(`+s8Uf8qa$H*H;LzU#2SZJX!2|EK-m zwt1=hf8y58CGP);+qcYj|4-c0x6=JTafA8A_E zwNu}l{6BHI)epx16K^md2>(ya^$Y(`%=HWZPb~jWEdMXCU0?D4#7*Yc1e}?}j-e~tLXl?0&=MA9yR@-{${m`*v9VBL1K5H}Mbg|HM`1!{Pslw;i#+ z_Ydq1<8|)KwE3P4+;FVe{Xg|@I)P7leOO<+eLi-6g#NIdKS^wUZ4%@EX})boi{1Yd zw;u8LD?UX;)d--UjH}FcD{x7`fbJT|EayMyU6`Naf!V@ zME;+cd_w#`@#>CD_y5GJHf6Z~C(dcla{o`9*<#PL%>NTtn!iu}pLnh1#o_;nSFamq z_mfkTnEJo^{@Jj0g8P5ss`Ux~Ph7rs3Vwa)58L-|V0=ORKYbtOuO9FIpLjv(#h(AC z@#YncasN*|$Layw{XrOS;i}2pKLp0_v-^uAw)>C3`DK&c|I>H{<`+``H*o0$_y6LI z|0m8J^#8u=_RY|Hj$wzeE2l`@MbSCszet*_^2VtNvx?6XO4gOPlQPapwQ&{udt)|4*FX zlJNg@znpLNJb!%a^(EqhmL=~0iEAw1AOBDH_toa};s1$QKmMPXdcOF7V)=h!>IIPh zCoZ+WAK?GR8UIh~CqIz-zvA-NC7%B$=KU7@KQZsO;Qxt>wwkYH^?$|1gZ`hG_e=2q z#JpdE|0m|}73BZL8UIgQ*;nHEf8wfLrC$G6+e7{w`G4a29aeAG{6F#P9?NsG`oH2# z%SXij6EEB}&;37f?ygMt|HR$q_idd2{?Nb6{673Y{XW8{!~YXEm@kO`Cnlc`|4&T4 zU;ID)-fA_*{}Z=Z{a^e)@y0>_Ps`U2=KqNqAOBCx{=oke%l{M0{}Y#6{@>wG_J{SY zwfpH$jr(-q4*Pw2_Wq}m82?Z6BR>!SFV6UXV)=h!d`GNX$<-w*#!+%)L_i5my~KV2_q$Nv*In_u|%%9q0OAz^&jUAi=S8>nz7n{}{MzxK`$gauJ0J1?G(NvS$^R3R---Vx#^=TV6XPf1 z|Hb)-!~PJs+VVp2|J1&=ak2Y<;u@=0O#NSRMb$#PKL0ITPa8_6MWbH$uW{NjF@6vJpZd2H z=eqwVZYs=<-u}pyq22TO_Fa|4_lTU{K7iauGad}>W`+s75Kl1;? z`Gq;||B2Zj)c+Mvvph(fdzfD|<^uQsv^^J&91~e~U+FpDzsmi-v7^UDR+~3)_UMHF zr}hnV7DhXszozuTzg+3{eW^!z_Kwqm$-Be$>Q#*|R7uf1Mlm92CUadX<51%*d zvwWbyd>-$g{^r2=cz1s^neqR0d@vvUzc}OniP?Yne{shDi!=V8nEi|YCuaZQ|B0!; zjQ=O5|E*WOBOEXIm~E5q3(V(%|EKd8#{U!3|5HCo=Ic&85ZdvN>&Cn@F#a+ApO!CJ zxy=1PG5!|*pLnd*XT|>$N9OZU|5wlFmze)T{-2m{3;aJl&yP&U!T%GFpK9-)TmGLo zf9l2V|A}i?SiKeV|HR94)4l$0-`lS7{Gg@TiTpotNe&hFhVsQqbC)OaYx#Oyuj9+7 za;k6lTAZ5K_wV|Csr~tU;`4hg&Rd?GH<-$=RsT2D$4jl(o3k|8*Gp|r^#N1;zZFZ9 z^9fV^#nkmLUy^+Pk-B`U&-5?;REnRKS}!=Ye=7e^KFA_LfG^-rW%RC~?uT^D#Ze_w(jhJH6xmQ}_QlDfNN>U5+fDEI$6(=OyRg z;XlROQ~BJ{$$5e2j55D0HviEn<6oGvy|3j5`r@(iQrT9Pw7%5+^IDvG{H8K~WY%Zz zANa<{u6N&$`pV@0iOG+{{}YcNJ|en&+WiBUK6Zoqg7{}&GXGEQ_}=(`V)6s=|Kd#k zpP2nk{-2mUx{A6X9)13~?*Ebbrh38V{}063?hgXf-|im*Gd}*G`os8t;<4rn;{R#= z_=)&`;`2vb;QpWZ!V5-w{a-CV?SczE|4%&OT+0JA|L?M|T$iXfZ2sJU`G4Y(mUoE% zCuV=+|7m&h49Wi!pJn}T9d<{U4~+k(c9zHg6O(6%|0f=O-U#>q#Q1>te`4|;Z)?4I z;G18+)_p$m814QwFn%TZe`+^f)BQj3*~1h0fAe2H?fxH(|9A2)*SP;jeOvPXzBD57 z{XOe~k)Ho2o-lT#*Z&pIn0&G4|7rQz<3>l^TWEZIK-R7G^M20lS=WXAxnjyhem{im z!xyyoivky~SnU3vw!dZB68HbawU^9|?DtFPf61ha`F#_3;s~opZT_G7FSGnU{6F!E z5$C!8C!Tdd!v7P`9yL6=_s~`0^IUP^aQFXoKFv3u694aA72Dna<9dnzH~Bxex&PO= zV7~i*;?8x&?*EBzKDIad?c;T!|E-7iML*b6J8;*n-R=Y4w12nze;1Z?xeti%hyN$O z)qFktKk=E9hu!~+Gyb3Wx>Nhz{}Z3N^nm++V#dS&6QAhnh+ghk8|Jfp)8^>5yVi#J z?%dqv`G4A;-mQuJKkbk0o42_CCvNTNbpKD>wS9-@|B3hY9d!RseAn&wy8kCWb?3eA z|A~*?erNRe6GdS@M{mC;y7OpZ;1h3pi~E1-fBO0x-2W5z?Cf*@Ph4X8hWLNt{H7-N z|1SB+4)_0-n=gp}CthvKC^uv3y18>=L%Kg7ZH}|<8 z*tPF6_y5Fw`!DzWKk?qfSG)fwJ}~J2#d&z&iZK4(LH|$l**EC_iH}%5AO2sQkF8%4 z`1qv>|4-Y0>{O!uuXyiC^ZP9SFNtH{heuQVzmu0;pY(lr^2#$w+_iIm5|{V1y8rhd zjkDeVo4YzEy5mzn?AQHGM%^s;|HQ=|_PoISzju};{6F3o#{Uzy+TY8U7Js|nYP7k( zS8w%6-t&zY0+SDh|EK=^{q>>${zhouX!&CJe_Ecu&*T4z*PG9R|0k~KnB)GRxP5P? z`+s8Ut&#sH?mA??o%w%ad@S<+#H#-*ramA3pJmPr*7sfO{-4fdS4qw)X59miL>|7VVZ`+r-Ht#bb_&f^Y#tY5szo}c6Y z#h16|zk$gg#Q#(KW~(1K{P{=2@;#Ox^z@z&Cb8v31tuR5|1T_Wd0qH_VthjUKQZ-# z@&Cl+lO2V$X*%|1Zw?fBJlB$N!5n{-2n9F8n_+`CRyaV)C2t|HReiyWszc z*YC-3|4+POU!MDaV)=h!e80{`XTtLI$Ny7%#a{b+nfZU>O3P2c|1)RH{lB&L`~&~* zf}Di^S7W{(`G3dHPWXQ7wk+}dzYlJj;`x8%SCIertH&n0|JQ8(CjMXZm6JU0kNi#i zKXH%MgFN}r&i>oJJ#pZzpMA7+iK_57F^{1pLllO1o!{6z023masN+D{a^C` zw10}s-|PKrOEZ-*V&uq&Vu;<@_^DXbh>f;5bUYtEY56trm{6BpjjrP0*|4+>G zF#JF9Mtk1$L-YT{9lfRQ|A{y4C~^N!+_+enDXB=UVyN?QIJCuh#q{JHG<6 z{rG?CPktZ%U!3v(;%xtqal-!_YA?kfN@~adi?`$diK*|4|EKR482?Yq{P6$8_<8t$ z;tfYj@aqCsSw1TMpV|lW2$R^xe_ZY46I%bkEq1){Pxmi_K3}2wO9QjNrvI|4So??12mdeJj~d(dhW=gldEx(Qye;O- z;s1$ik63-H2d@rXf86U|2j>0^|4;q7zr+8FGyb0#KhXAP5|jU@`O;4QpZenm+WQ(w zZ2NzRZTs>6)SvrZ{68`GKlp#*cDvug{}Xfl!2c6-{lNbd^L_{ZpSboQ{_c;9!}(!s zesmJ!|EZnvEnhW>@&DrO)c+N;eyiVJ5@-BBaf`jrfd41vdPV-9xPF)U8uw`|8I!X-2YSmrB>gV{68^yfcSsnMXRT}|0gCN5&ut2 zJ|g~~c-h)n?*EAwub%GypLofd8Sejy7nV)+`oH2O#S=aMPrSG&;s1%}mt5rjpSEZ5 z>Iv@uiI=UL=>DI0<%TKl|A}WbMig+ zyZJq{_RhIZzVG_@i~D-twbr}JUi+QB?)7{62LCV4_l#PS)Sh|DGUpug1@Zqh{~KCv zdDE8vCr&Tx75qQ(86{nV|0nKS*)#Zm;vqI4#Qzg#&Pb1@T)5ep{JZz^wk9$DpZe2| z|0gCtko-T*U-9wq|HLI$Ul{*S^I!Zv{J%I;|5x*6>hI$JiN}~R;(#S;7b$^1VtKG*DTjyp3y zC;w0TGsFBe{J%Kk|A{LXjR^jqxOi4(@c+cQv(khACmt~`EBJq6^40MF;ynH0Z#mbj z7#Gd?;-MtQ|I^=3Q^C@`g;q15C2b$AGpo@KXJAFeM0`9mWQeTE5`T3 z|BEyJU!2MR6SFoY(919{!)0{6G9Z@q(45!T%G_SU4{Df8siOzwOAGzw-XI z^X>P&-CsLTviAY+{^Hlp#a91!NYQVc%jetsYR7)-TsAK=8u5>Bobes;|8)PWFrS$G zKQZ^Sg-!mFbpM=k;otmzTUy*R_lfQ`nCnkRp|4%$|L}v8;Pd55^CymSs`F|QOjQ=Ob zpThss^7v2W|HT>qPb~j0&izl_igRB!6H2$Y}>YNWceY^om#dJ{@=1G3IDHSi*~{P6X&%$J>>t1XWRPm z|5kpmJ@|jQcD(Wb#KT8s1piO{8UJ6-y28f?|GvJF@$vBgG=6+9{68^%8vdVn+Ne>X z{;zmOq17`n|4%%9^zh*SiSawh|BEyJpIH8%nDOBMiSbAA|Kg1QC$6>QkN+noj}ZS) zJYjUg{}YqHhW{rn&d-j<{N@HfU-0042c5Yd@&D8x#{Y}6<@+S{$N$sy$oTR9#Eb|3 zPt5g=|0k|CzZL&a%>Lp3#Toxk%<-fCug1gmO#NRm`Fqs=jWhLs#l^!%Mt_-lbK~bP zFF$(W7mdvM$N$skll9^MiIx8+Cch5%{6BH_ z!2Z#b58dvcpFVy1MC&Hq;f$Zq`LWxJ^n9NDn-`|s;f#HT|EG3)TpoQe`Hmtz-|y3- zOSH!PLGh4&U4s9o{-d(a4*s8*`tuWx-sSx>hNVScX58&ODkm-J`)OoWvR_t^naqV* z$^KfZ&zI`&rMCY&{{OptYJJ~q%O8sSM&!-LIn@VD_5D))y3~5XeBZ^_H^F?*IH&q} zshsNnWeqqhY5BotC;NNp1C!UEnkSgL{(tBH{W~A*-}zCg?f>FOrTBx`WcYvgWS#K; zjPd{CjQ=OT!1C?z|HS{i;YjfR#NU1Ch2Z~*Kl<|X;Qxug{?W(5|9kKUy@UVvi%&lc z`G4ZC-+MLqf8yuvx+(a7;@j^%82mr+Bj3F<_h{{OEW)pN2T6 z?q6#C)_e|4&RF zApW12dbRj};wCN3A2k0@OkN%SpBSGI|4%Ic&*p%^|AX=W#N-R&|A||ee}?}jZew|Z z_yzu|DJdFS6Y~#WI)A+~-#Q#(K=}k@v{-3znDNTd_C#L=~`G0Yy{;#%= zpNaq1EI;A@HMRP`_H*{biF=rTJ9>5_x3}xd^0~def3MyV+1cvfu~(0XcLB8i)7rI;nCol%XLW8DF*c14 zzU$~7-@m*L-Gcw8{hvQ-Z1DfY2+M!O{}X4M&xrpg z&T8H)_7MEe!tO z+KCf_|0lkvt~Ofvr)uwiWb=mL|Ec||jq9SzzFXsCfn zmzOyo*m6O1+0s(yOSWzd{@=?5^MfyV>GsVb|4)4RwoTFSg_FJil{+p9{-4?}GsgcD zZ?t;D_Y3Am|0iBy^^P-- zkM-quY~B|9KeZpf>DJ)?iT5A5HTZwxOAg)?{6CFn>%k+z{}XRJbTrDiAm5MYro)GV z|EJ|)>i>$jUVTmQ|HK>iUmoROkmv1d_g)cAUp3tM0?QXHy>xiPtq(2rFGybA!AoJxo?>u2>xzv>x$zCz1K%549sGrzBW>+T;o&st*nZRY=}Kfj;i|B1=- z8MypI=b7h^4gR0EpEoA>e`5R){J%Kk|A}j@UL*N`;u_0?BL7cZX8zi@_q<;JT%Ux$ zH+9{_=r=uHb1t>#!9yN>#km;YtmI{9o{!`IX?gqv^8dsow*Fs^d#?Ve&1VE(uhjfF z{J+QE?-BezwvYcOrru?rR?m2Up2z;^&ZnGtUQPa=)`yQq{-1cBh z*H@1EcxTz~@A!Y(e|*ByX@`A(7uosP_nU*xSe%aN|%guK?cg9uDi&l>{pXo|x{2u&2t*^xV82mpm&#%e<6XVm6|0l-hApbAU z_W}}ZTkz#d7iUKEayHkWcYoL5 z`xVc(=WEN?*DpII;roqTG&uU_?HAN9oZBVj@s(IU5&mEH`<;XTH*f8f;QxuK*Ny)- zcyPl1D_&I`{6BI3lK#<*@r%5@eMz6-|7rOsuT}8>w7p&#?SlWO@wMq=^V=qK>ep6x z3;BdyyPOv4|7w4_cWV~>KXKdKR?#gNPxJjvx99WJ|JCs*GA{VM(wTZ-k9I3}9=jkv z`q9u*KcA&5Cq&biPIexi0R%S}~sbeo5TEU$%4E^6}CBx{M?q|M6fSKhH0pYB$K4&u>=Q+0Nv({p_QD zetc?IkBMe==;O@i``xKMo$EGFj_g^q^ZfObqo?2O;ylCd@0rayIg<~E|EJ?U+3H*2 z|A}YL&xq#EYUNyAHz>L#t%dJT&71*I=S8PGPn$b1_g8!%XNmdUR|4)qHhyN$0o;LoUc&_CE;{S=~o1cRJr~422T-`o; z+uLWDU(}-Tb!YOq@c+~w|A+iPG52%)zc}OniSf_z|HRbq#Qzh|v-=JHpLmY#5BY!M zI`fb5|HL!Rcf|h_PqREg{68`NFaDpHdhqyvV*E1vKQZ}qZVslTDnEXF&pZ@rN;;9=F`F~>a;_&~(mFDN;|LOY% zHvh_*_2K`ieX<=t{6F!SwfVvS6HnL}{55ZdWH)iK#EkKQZ$O zYabo}r*@uK+2G9l68}%_93S(K3v_+s2fq2pJ4uZH zr~VaoJ>dU|OV^AH{-2ho{xJSuobms}C9Cs-{}*TcKXK*i5h4FC&iH>~<~R6%V(u6C ze{shD6Vo66&-vW^;Qz&${68`IOyvKGOYMG!|0kY)?!@5#iK~~73-y0>e;T%OY{>tM zGxdMPxhw4N5A*-TIm?TJ|0m8^S{VF4%`XR8z7q9+#na}E4E~?`PoJM3{6BHk+>ycm z6IaZ#`eTJ7ef+s|hTGpGqn(Fa-m>}BjXXOm8gk!Q=V9h2S$?texanEJ|I_-%PRk7b zpE$$(3hMughg1&^`G4XO=Ic@aSNoGWzDw}`#MDnF|4&?K^^&RoD{eixYw-WX9m;zK z|4*D@^`^=Hi!=V8c$oQt_EZv0$68(>{-1c<%(USDY5qFR{8RitagD7X|4;K@mdF1S7fl}! z4S3;_Mn2*HY5pw#PduqMQU6!-eVF_|ak}|^n0E62#P~q?f8wgeiTc0dLi73X|Kg1QCzk&wp1O2o z)ZxopeZ0I6(yj2g^Ek_c#{bj)@cRe;pP2U@@&Ck=ms&kX%l{Kkv^>)-)9)$N-#64F zKKa}CI*+mX$d|Re-+6}3Z}I=M{Jcd&Bm6&c@zVU@|A|Xi+WT-nc&Jc+Pm#ZOSN6A) znEXGrm#rEd{J%Kk|B0EuKVxSP4f%h%o_YU_`oD3; z{}a!&?+5%p@r>ESg8wJ3smlreU!3v(#N~@e2meo8wQNlA|HKQIQ&R;P~&c>6WJu=gjQ%;Q#4)3_b+;e{m-NPh6Cf z@c+bPa;@I7`G4YS%g-YJPh4(3AO4?M{-0R>U!3v(#PrAi)AO$>Lx%?cPdqU#E%<-x zPrX9&|HN5C(?b1UF+NSdx#xSk{6DR4xaAMx|A|NBPM0zLI(Ck%wy$%qR&Ar-e3i^sY`oap%iFh&2DaGae4+VyFW=nAIp*6f z%--wmndX!IWB=tvdVYt`hyN$WufzWnQ(qMSFV6UX;>uj}ldrkb_jj7*0ZvOh;9Oof zIx2iInFr0e%G;?o-0@G1Og&=!Kdm2sll(t1=L7#wOgsLcxO8-W$o~`1D$Ec5pLpiz z5yAfxbG}wSbG?rTo<98s=aPb9!T;0s0ptIPiwp9j&V3FgvDNQ$o>Vw2T9b3g&p$ls z%|@nvE&iX@2jl;V*Q zecap0Yy0o6w>uB%*E{%s`h1<$vsdu{#4Rn~2>(yd<40IQO8h@@p7~Drf8uQOb@2c6 zJioY0=ivW|ho03fYI)(E-j4rwAgXJ-uv{-65i=2(3e^Z&$!8Oc6eYJT3oYyWpX zU#dTt%Bj9ys*m^Ywx8 z^L-fapUSCufcT^F{zC@z{XaQtK)Xpd@&CltrFFso6TkZ0+rj@6|N6r>ga0S~;}1Uw{-5|) zpS~UZzx2Kd|L>Qdd@uNa;;-L%Irx9#*B&??{6Fy>$My&RPyE!Qw+8=D>;K?{|0n+R zrKf}cC;t4UXM_Kz<$wD63!(n6_z!Qr6g{)9ra}D4BllTeNVW4zH*8BfejAE2l6Xvt z&zEnl@$-$%7w4es#e9I&^Owr0*TcVXif>5$()jkMzZ&P}?b{@A*Ry&g@hNSS^8rt9 z(ln|4)RU6e_pkexynXg(;*aibDBX2w!`kJ2$H1QzHFE0pn#%ug{6Fgdo_5i`kmra0 zhW~f-&PzfbAo+0ke{shD6XTEJ|B2=QiK(BA|0h1l{J2B+-R#@L_rw2FJ3b)(pIH7M znQr9&$^R3}{}VSif%40*ZuI5x)A0Y)4&(oc@#*mYv^^OAPwl6hzlQ%OZf5md@&Cje zFZ{nGHvbO?4gar+`E>Yy;-=>J+59W1KmMPV=Xl(6^R+%6^84`rG(LPp{6Ft+`$PU; zoXP)d4*M{}mj+IOPAq_ZF>ptHZ{J%DKJn{d;t!;VyKXGUCN%8;01H1PK{+~FnQ^(-{Y5nQu+wpFI znEKt!O*Edq=3}yN+P`6K+wk{=^X%cnBK!NpnfGn*|8#tEx_1x$pSWMUj=}#E_ifuD z_Z z+ocyrLv|PW{$6v_q3D(Eh0a?K-xMv_QsBJtx)dPe7H+yKp|I4-KLHK{-k~z7-{}Yohh5sk!_fY&l@ig;I@c+a!R}}{TPh59i zQSkr773UWQ|4&?LehU7dc;U)X!T%G_x8HluF#k`?`{($7^H!Y^^80G7KmMPyf8tqIzx989dcX5*^MCSp+~-Wa$?v>w@&B~Hi_C9q zC_7kx#pdoI53knzy{*5vK8f@8T<5%CV{!2R)Svp%_T z{mbU3M=SnwxNom~PDb?kfL!M?d%lDJr~VV`(t`gdo-}K4baBtYzCTmV=lt8OfzH)d z&-eC|`}_Hyy2SF0uIcONf7g$pLmWvPsRTeKfds_mCpF5_E!v7OhlQ}b=u;b@kX3N|0b>{ry|7m;pfcSsnM7`mj&iIb_e`;SCj(@K6Jo|pe|5H18 z#cThwq>;^kyDX>HdA9kqaYAiarx?m|EK=UPw@Z5iM-FRo$>p~|5N)^^9S+4#&5B^`A z@&Ckp|KR_{8UIhr{Tlx-&iH>~@=MA8i!=UTobms}l{OyyKQa5$=BaLlx}WfVklkOL zsh8fXs&^9O|EWLq)$#wt^r!x>n7n54|MdL^pLmq{diZ~0{5bqS@dSI{ z1piN*Z$2UZpSZw$Ir9HBUnL(5|4&?I^?QH6d5^RFKh1{=ZG8BDV*EYw|1^Kjn2{Fp z|HR|0UhuC=_IrDgov#b;z1(?d?U}*<(|j;{)_{=zCnjGI|1Zw?e`4|s@&Cj{Gc!W| zpSE8zBjNvvOU;kM{}Yp!hyN#@Y`;(7|B1)XNssXV#3hTZ-nZrdiFyA6|4&?I^H2Og zG1ou&e`4wv;Qwj7l{O#7{}Wd%%MSjZxZLvO@c+crlg0lNlfQ@mC&qWe|I^<$)KA6# z6IYtAh5sk!{Nw*=`6}}z@&Cjl7i9xT{pCXay$L^7^QyD_KlO+4|HRY-E*$fg zGv^ooPwiz(Mh5>+jIWCSC$6^pLHhIW`u3*T_5G)A?>poB;s2?>{68`0AOA1T_?kN>CZd+Mx=2>(x9YvaNHi!=Fu;>sD>!T%Fi)MkbJKXLht zA;JF>Q}6e@SN_AdkN>y!%wHxk{-65KHeVF~PdsCZeP3GspLnMEh4_Es>6Sl;|0k|9 zU%p}1@11My???PU-T$Ur{Sy2?-9M}Cc;Wx)ep^;;zjs*uUvd7JKEeOf_s6&qeS`le z9-G(4X5WqZE1BkFkpHLWMOnFN!T%GJKZXA%#<#%#bI!;L`G0Z7{}Y!Ewfg1e|HXM( zw?##I-ZMHgJNnV2#m)s;InnfWOPrPer{zmBGNSC&%YA+Lg0J7a!Wlo1{6F<)y!d}& z{Ej|*&-L}^56z4YJ+dl^$^X;yCwvtAKQZek|4)pcga0SSr^Ejf1^|amN1> zv%lBPzryzyKhU1PI#03sw)lTK9%V&&!T%H26pjr3U!3v(#AO8u|4+>E#{bjysV|KG z7iauGF@7BWpP2EI|0k}s<;nkx^UgD`_wBR)_7j{-4H+PmBMj`xm|+{-3zQ#zX#}`ty0j|BG|Y zfLpyk`KkDST7E*#@ZkT6$K(u-F8TU4Z_iKfAN)VHj~sY*@c+b_y?X}#Pdu=1zu^Cg z@elC-^!aOja*N>q#d)~3>-l~AQ%(*3pE&J|Ucvtp<4@!NiOH|S{}a<6ai|E2nUsd<5^`FyE7Vo-A4-;lI3leV8Wux}El`hVF2llu?ppFG}F{uiGs zCEqR8_e_i<|Nip_3IFfG6a4dcUyUvvIjiB#w8Zo8Hy*n` zk^gt1{iC~YOyvKa;2&E(;425!`uN^>^5KyGr|tdBe8iT|O!M|%zxGlh|4-X{p+5M3 z+WtG17l{8S{`j3&qUK*#`SL%1wIQ04*2o`!_u-`T|J*e@l6cvO|Bd zUgP{TwO(#2|GWCU|J(I*MVAK}zW1X`f)8hUb5yk|qCr zr>`F$u-(FBj<1jXd+}ShHsC{D5{zwBgT;u+qSpJ`w z?c@JxdGhG+|J08EXYU{Q{;>a+Pn^W~e~tYU{-5|XyTI`O#Q1Oce{r_?lQY}5`IR&E zfARm+pW}=FCzk)G@#Dwg|A{-=_wU-}*Er)_)_w14=TlBSDdhiYedJq`{}*TK|BAVO z@c(QM9{fKT|4+>Q694ZHy%YW)jQ=O*dTQ70l7>H*Bz!-PC;p!ppAi2~%<;qj6AwK3 zl;Hn~M|bWT{6F!iZoPy5w{BR%FHCRIF8F_9d_Vj@ji;yOJ2F?&_;Xse2>ze0|7qz% zg8wJx`_%qE@$)};;930r;(TWRUi^LId`7P>!T;0oqrNctf8svvTZQ~TagLoI{6BHF z1tR1BiSvx{|HRB@@c;fea$)fQI-i>G|HS(*S{M93@s0a04gR0_n%z62J>OLM@>_Oq zjc)mRs`Kg%Yl8px^WV%5e&D(_%cJ^lmp6#<|7L!x%z5vY4bkuKD|J4wXGe6!-6hV4 zckc-P-}p=C1%L41&TYZ}6YsYE_@c-hB|0llC@&obz#9MB;JvzL2xbupe?~Jk+40B$5_?F=RY5X^B zzb@LpDA)JrvU7Jvch1dmUbx}v=((BM&P%u45PepY<$S@mtD`?xWIC_iacz{bFtg#% zt&4(BxO?lB(fzYBocHazHadISQ0JR=ULD<9p6>kE;d_Grr{(wGbbE9#E6vxx=issE z;UR+>+4kqn0Rx>cJ9bAjD*bHV-7)Q`mfQ~&CD>B0XKS6P14pFV%Neq;ND?^iza zOneJx>P6!JseSz1!NLC%S6V$D{J-C=>K^j`rkWo`{-3zo{2lWD#Qgq^|0l-JI{xD) zoq2wa|EKlifAr|^9dCzcJovaX&&RJXe$1IXop--{B#B#X{kC)21x3OC)Ap&4i~lE{ zY592ge`4~Q@c-hB|0ibr_S58?lb$^XLt6VE$0FZh3A{2KhfINy?Xc@ocl z;3<}#JSe;Y!2MG*O}+rCBybOmsnl}{-3s2Gk-wv|K@G&8uI?8 z&N(aif9L(aOYr}AevAM2^Rk5hSFs@B|9yH=!vCwX=UZ>Ryr%w_8#{%(zs2S=9BOu6 z{o?mK2H$V&hKk_-iL)%v2LDf7HGg#Q|HRp2dItYbe8%v0!T;0xJEWf;{6B5K=g_v% zRWHt~*LXYjKP~uwV)=jCza}lC;QxuE)1%=3iJNt39{fLXboMF1{}VS!J3aV+Kkb|F z|JtWF4gR0F$MDwCZ3l|$#V3zx9(8$rg7aw;+e8PNjC1Zdv0d>0bUr#wY9DRcG}_w- zO>7q@>Hbx2zLEJg&fLGK|EqTV8~i^peiHtlc;=>JzAus(|4;4J<`3cjiOEmH z{}bZ_-g(AxA0KS@&qlW6V|l2~_<>g6+?o2F_K8~&e|h{~iC&*~W+er{h81BL1Ivl6~Le z|B3PQzA^t#EdNj6XRsZAZzuoN{5a>OYbWB*IdlHMxom;+6dRw_FLvhp-NxgL|7Pod zTHD7DwEjtK6U0dEi9Fz(QOW$MbFF><+4@JTy~_MJTc0z2r;X3K#{47vKlPt>?y%th ziEGVY!v7QFv*Z7XXPB>L$IqGXZ~Q;C!#17*G5c@l$C*4ptFPL~mXBxkos-zc?@T_X z<(WCxSbiV=pUxNcfARmsygz~eCnlc{|4-wAEx*#4&y)GBNo>a_iShrmJpJ+i#5Eho z;nzCXUNn*8>3oiTzHL6_JkPFo`}{iN|Jmm|iS771lQ(Ghha|T9M-top#hK%U|EKYh zXNmtOuCV*J-M^f9|Kg{={xpg0{5s?R;{R!RnEXF6%j5rvtIZ$B{}V5^&mZ-F#f$9o zivK5OefWQIw(G~4&$HEsFVyFKTJV)yI5Ypm|I_j?{$HH&|KhywH=TWX=2!TCT7S9a zyW;+R6XZd>G#j|4)3j`F{9+ zn%@t!`n%Ns6;qEF|4&Sw82+Dlg!wanJ?%>8{JB}tj->~jv&=`s|I_?$K-JkH|4*DV zwQtmJ_qEYtlmgpLmkxCF1{yCs^JY{$HH&|HSDt?R=R3Cmw3=>)`*1 z%jyOP|4&>oJKg5DH~V-e&dZ2e?ztt2@&7b_+VTIy_=e>FiHj`H8vjo`Zb`!b6O&hl z|0k|ok{|p({e3fiNm20s#1(T#1pm)@PEPRuwEVcK1ERw(K3J&sf*EH;y?a08Jb6(@ z@c;DpRM9yjg8wHTWBF_Ne`4O>#Qzi5*nArQPdtA`LGb^?^Oh&_|HSx#_C#GI6{-2oNWAOj9z8QA^ z#Qzhs|K$Iv|5WoQ@&CkQmyQblpE%P#@A!Y>{M!D({}Yd%IUx9dV*EJ#KWz^m5C1RD z_(JMN1sC!;s5FR z4Ecbatp2YUA7fMf{31Qiq5p5cUf?`DCnNg9t_4MU{=@Pm4=!}ZH^l$b^5xmt(Ob8j z*e*wBI{pWfJ56Y5lb0|A`sTlUJ*Gd#rUHpJ(~2rR$vWvF^KQy)!=GC*Q1V+@AS@RlPPO@oVM_`gp7z|4;jeUx@#w zcGidg7iauGXY;4<|8#!wsWx}m>FXoUZQ}inTv|9hYCC?Hx6^;y?|1t8@WV!2w#zwx zbe{dbxZ62*xcTi*H1es#Gb76q^Ya^ZY#sbRo&T)UI|To4&kwhU{J)&$or3=-&bNA9 zwKMs0 z_!361yYcBpW`CwvAM$qg_x-;g_VwXg;{R!U z_^$YWV#bgEC&r(}{}Xe3#&cOltpk+_ruD;QuXamGJ-ORW1nrpZKk3-wytt_^0o_7W_Z) zFF*QT@c+c$y#H$O|HOaz=#Ak2iNF5f^+f*PBRzxv_v;VeNaX*W;9tD;d?Nqv1i$vc zZHfH96a3wKjwbT|PH@9R3I9*)f9%nFga0Rf?bT<4|0n+Vl@}8EerJFh(-{6Fze%pb)6i}Ph`r#k=inTL{&|Gm4`CGnM$nkVs`PMo1e|F4tz zadD;^Z=6r!^vC+A=KJ9XzWnF|4cCuN_|IgX{JN!Q}<%jYA#GN{K2>zeA z$*{EO+~)Us`>7++qwMqVaUR{bL-g18?sgtzzGK6%M#lf!d*fZ+-qyzR#G7|CtSCwN zcZ~POFK%lf(+s~4{#J1#pJaJ>_%l{MO>*4?T_M0X0|HShD z#8I;*!T%FePnr6^V*E$)|Kg1QCvM-WS@8dgY7+h*O#NRm%TxbXj4z1)r{&2D#Q#%! zOUtLj|I_}E&xijfKH2;^{6F<450Lynanq(vga0SSC&d2~|+dbjVMhSzS{ z8S(^&bnF`ZKk=Y;or3=-?ql_(@&7cQZZ>}WKaKy47AFV)Py1V#epc}R#F-hrga0QU zGPp-Z27AiihcQg8!w3Nduo#N>iKoS|I_$p*G>)opLpS%+Tj0* zw=7!~{6F#SS6v@nyLXIlZ|{w_2LDgTZ~L_g|4+Q^+8cuZCth^r)xrN0kGk?e@c+aU z4;>EvpLprPL&5(Ouek9@$o~^>zcG>jC*E_*Ey4d2Z!#Ya|4)3LjgS04?ayUft_l91 zc=Nftg8wI8u=vv8|B2@=*c<#m@$~t7g8wJ3p0g`zTaw}HuU))3N}D*;dG*$7qlshE zoiEvOWwc<_5a-*D+!JjXKG=EdT@M8RPwT(vj{AcDC*F9+J;DDIZ@K4z;QwiVufFI0 z;Qxs)zx}SH@9WENx;glN=U&(=+#_KiNAg1hT#8+@4ou-;QwiUa_Nq9q7DPU zsMq|XdP+u=`yW57|K!CU!S@?w^?u$x@6-C5nk0O?(xrJ(>!zPLPg<56mEQER^JMd% zEFZ*qiur!8yz!wk_2o`k^no+)Ymfcgd(PzZZNK_mXY$#e8SswtO#3}{!cX6-|7c$K zkk2>E>iwRy?M>&prS`sWr#GByERSOAw_bCunrHb}7rs(&&+HPuUR_qy(DG&Hvgzs3 zf8F(>GtUb~jD5j5*YdsAefFI5$OXfL|EKj8o-@kwyPmC|+$rIc@jm!(KY!Y}#`Yio zPyOdvJ`Vn$c&_E^{dm)Noq0Zr|EG2s|4)n`f&V9#|0kv$|4&?M`CH`wiShC9|HR~% z;Qxtf$N!5n{+}4%5C2c+gXgFCe`5K6V%GPY!*_Z+_1N(L)K317`6#}A@}a(b;#Oz! zdwNyf;*1}F|L5Z|#{Uyj-|vdeNBsED-Z&z{}<≫=6K`(iOIKF z{j+Q9cdzLh^55|H?%#clGtVo2-uvn#?)&V4B%V9#N@t!2AO6eb&OA@X|I_xUmyQ1? z#`nYj6Nh|5^Z&&3$Nv+PABg`auC&jqJwL3snykV1E17$C@c+c6^9BU}Z{@gz|3`ir z{@?A#I*0tf0(<^T{$J;5of_JtKT3IEUAZ9Y!@U!C8mmAx-v^?#jPHx2%u_@rJfgZ~$2{6BH4p`D`z ze;n`IYn{<0`hM0}=iUX~qNasK-oH;__vnQOMtS?tv7Ms4UyX1cQq&=OaKLcq{)L^R ze&^&kpE0aeboh9tbDONT(M#jf>veouWweg|{@NfvpUsE1ivF|3fF#EMv&_DP|2M3C z@c+b3a@z&}Pu#MwOO*3McfTGwPO|q=T6A^h`MaGf=TYW=;{R!Re7nofZ0Fl2|8&RF z*3OGADvz#tzNPQa?6s4k)Bf4anfo32f4aWm12;BxCO-=Q&+iAu_I*;{S=cKa>9_ z#@ELG6XWNR|0iB>;rQVHiTOUn{}Z!3{+}4%5C2ch@x=d&Gyb2m)hEUO6W3liD)@im zs&%7nf7*F_^?LlpQ=Pe<@c;b#$-ZB{G5=4DKW6g{XU-q~pW3NEi~lE{Z^sk=Ph4sJ z&98GVGhfO49cS{@%x7}u`w0I}%a_^tu>Q{Yg#1%`!bi**B_?0amUo_K`FXbf(Q2P- z=f~FP%=KsEbFQ)L9sf`L`93HAPdwG~er)~D_)7SHYOk>KWyjAM-xdE)?ehP`^vC}b zSKIeB{+}2>4gW9BHh$+SJ3jb-YKI#-l{oW#|8eDXXY%oEf1UB?@c*^|A z;*9?%#?Qn5i!=V8nEJi=f8rUN#|QsU%=-%Xe`2m5{68_v~xfYFlVPW+9%Ue5_n!jxK182UUqBA=>NM_`R-+q<({rGzrrxi_e^MzBBcF@&DAHyg&Ru=jjRmFV6UX;*y%d!T%Fa zsZQkoiCG`{e`2i~ z@#FCS#Q1Uee`3xD{-1cVy$^@~CoY*kJotZ_?~O7)jr>1x-qb$9|5JaM`oH3_Regj1 zC!TCRAO4@1d^7w%G5Kcre`5SZ{6BG?)l2>Bs-wRBDYpDSU%$z@#FoeZ)A;a@@c+am zc0J+$i3`l1#QzhIt{oKoKXK-~+~EI-@mb0L6Xz|kyl?aW#N_jl|EIriW-Lqif8vUH z_WO$E|A}kNw`{xo0p}9)t?>WUUO2sf@c+aU=L`w{pZ=a2x5(;ATK(TR|1=)%XZU|{zW$r%omKx=%U9d)S7#l6$=hqK-Y@>2mWT2G#LEBE^3-$2{}WF> zr!e?`;*sX_e)z;&zI?&7v!a{YyzM+@#(?OY9 z`SAb5Q)@GW{}*TcKXGM^y$@{upYDeh)kC5`Ui=s5N#>V-{qo=ZemZPI@8JLGemrg@ z6^I(2x2AIT$iYeNF#eyOm*B_Y|HYa7KRurz4+;M-&iH?No3YV)=jKNyA1&i(Xvo>nGm}|4-W+nVazc#QDR9NBDo@VdiTUZQkUZ zYxQQS|Eu-m8&UsPjF0r{tJ|E(rHM~B(?0lrV)Fl%AKP7|=Z6DZb|OE-8UN3o zFFG$7F@pRN=fd&BqK|&E*S9x%Y)*7&!KFTa{4@MNUBCEi_4*yRq|4+>MsQLK;Z^ysH|I_;M<9>DaHO}~PA2u{HzMj>m z^LF^Y-!(G+8~&fx2jl;V@!KA}<2v8I{6CFP`G0YKV8Qi%z8T-Lza%sMpRNzqSK9do zKR>~zyT6g~`)(h5(A&9w+x_y8FAwAYX}mE0U!3v(#OxpbpP23A|HV1|kw%_s^`P

aZxhyNWJ(b!2`1f0CK3}T8N1kH5 z|0p{iaV{8^?DvfumRz4WmD#_f;HGlPsvOkU-8gnf3Yw z>KmqVsxO$zoZtBV4I7-i{eS2GrM73Dotz)||JDBsI#_HzV}nZ?Uvv^eS>t?XmgULD z`PaAJ8~ne!YtIPze{a0_V(|aOUw-;&@c+cW`@ws`|BLe%f1TBE%OgD+8g6;2=s(Tx z`+Qs@|Hk~jA74?|*lu}$6;IbSX!#$%ULPGerIFu!;qmD0@|oU#|M43V`G0>uBlv>% zUArrh|967#xq3&)|I_-8-E>Xx|HMx`eqZqa#E(Aya3cTj#PZM7Kbgq?JHfBle<%2V z>i_0*PX_-_{MK_%2mep}!*}0|@c+c0y!Tr4+B22TKeYV8`0@UaM{iH!BTH+Ocv)t0 zexAiiB(+B=d4ZAnHSzV6KZgHTcjw-a_cy@m^Wy)B@#XOU;*9?%ZehL`{-3zHU0~$@ ziS6Nb@c+aECyxpKpSb^oqUe-kcQsT#v?r0LH)KH6@$EYrs7XrRUB8ZPqVBnk+|m5B z-bZftcE*eUM}`^xANynec*AF(?g~B^d4A@XCo%q?`k!LL5&oYT|84M-$GkuO--5o4 zOg*n@)MW6b~K648`{Vn+q4M&pN>bT zwk@OY|LU-hx0BUZ{kp1=+qXI`_ zTG|0WKD1lDv@`9qetWr}UyJ7p{-3TF_@Y-YYp{2Ag71evjsF*C{J%Kk|7{t+J@|k0 zC;v~3-$(wRxTWnc{-3zL35WQ9amN2Uqj|#rOFy+~@c+b>0|x~EPu!wU=ivWoJW;DA z!T;0#P+ymKF?4-bTfQuFGjaE`dj|hcOkNK8e`1y=|4%&4{PgKx@ABha)3;mj|8)F| zJ0c}RD|)mJ{-5{{yVu+MJJk*1TQ1)d z{J%k&^Mem~{J_58|B3ItVo&h@#5e8O82mr+u2l2YiLXEJoZ$b74_RIy z{-5~3`tzfrw@aL_-nb^3_4*X&t>*Wwe`&Jw=5^->|4++rykK?k|HN}@rv?8{yx4rd z&mW%P%U^%xzTp3<{n2Z#j{bV-SU(<*TzysW|8#t|9zGcSKk=4BH-!8@@rD}?N53o` z-SEVoIU&Dr-E{|}GfPG}*IajfG{-3yR&br|LiMMP&82mr+rTY&D|4)4A#=E2U^V58L6}R0L zt;!pe#HZ#Cbe?hij_9_`0ZB~$pZ0g2wUhrRo_))0N#D=&Z$2LUzZOsR4F2DS$Da)T zpZKvSo(TS*_=*Du68V28<|i8$P6+;=<{Ne6&kp|I;noTNuVTi);Qx)P>>l#==Gptx z_R)Ay|0kZg zXt>qqe4)Po;;tbNuE^eRk1lxLdBXYQEU)W1=P7H7qfPhJJC|NKCHQ|@zQX(l{J%Kg zzvU_Cr5B6~{-3tL!T8~*Ez${XkAVND@!;Dn{Mps@U3(;aI=IK4 ztDHF=-|u(8nd5oQ^H(@i?+yP?>zio#NFQ9k-#OGP&c4ir?Y8CuHanv#4|A|j;ov8mSKCRVB!T;0wIK6d~kpHK4I2v8%$Fo~o z%X8j5#ko%xn{Pic$+_PdO@sfZ)`+C_`vvoI^S(_S_c0w&iH>i-vhJS1piN* zKD=Y_|HRqD+Xnwn=VN$&$Kd~o^GbUL|4&?K_3}<^$sYiOC1V|BEyJpLp7)DZ&2}*IrZ_{6F!cO(ntq6LY-r z|HL&LCkOveT)m+<_4(_FGbec$l;eD_B^k{JI_{b|Sl6PKHhjQ>Kj`#5q+~Z_@lf@d(Qk!~fI# zaisZ$_8iOKWB|I_?$%&hd_|A{LsUk?9ITsA8!_Mu>>gGG0^A?YY{_wZEob&DX6#PG}Z}PHH zA^%T2aY-WoPh2)XC-{HjV*9-V|4%%9#-QN;iEFL?HuZn?_Y}tu|4&@Kz@EpO|0f=E zPJZzJ^!MJlWmX@+{68`Ef${&;ztY~%#QziH-{Jp>sn?7DC&uR^|1ZvKuYAVW&--L$p6#&E6lIN|MPaMPl5j@=I;&sKk-zn554Vy*PO{i zo!ImZ=fcG!qgM0YbmsGg|EJ~g{Bg#Ra2{+}2h4*yS#FNgmpo?T@1)Ghx{>z`ru zea$6u9%A)pEj!G|*P(Ck;Q#6T<+be`{6BGSs}8~c6ZdJ=iRXj9e6JQA$PaOz-nMPD z^*fEcbJVD)Q_&^9{oF}5pZutivnS+5|5$XHU$5iGjE+wJ-TopypPMkYAozdcvT;SB z{%@S||8%`qjwuZJe{shDi!=V8j@Q(&MZy0QPak9X-RA$rnfyO7>&O2SlLv_Zr}a-M z8Xf#UG3OKiFV6UXamN1>;|t>diShNmYjtBXd^sTIX?J*V)730|HSyw_%~c z=KCt%p33Cg#@qAra*}vzUUGZIu;lzf{LT3CoS!&XTK;LAQz2fe<}6R*SDt$-`s&@e4Y&NGd&1v)`{n2--5dFjAH5ZQxnz#F|N8ycqA$NS z+xeUCzZC`lPs@M!TEhQ3!N33HdkO#V1pn&Ow}b!p^ILiZ-?08$$AkYT{?6S;g8wJJ z_r@!N|2JfO!v8yRU`tf~MQwxHk6p7p_(|9|+Q=FTf-ZXmZ)B75RcRb#5OSk#{ zQco8DPyNaJ!~YYvY11b7e;RMkR;`2oC+=$XYVrTXtRMeR+`4Ux;Qwj+^8ezD|0izM zzIpKf;*9^N{q1Gz!~YZaY|}jWf7%}YApW10@6ft=@c+a;%+JFAQ~&NQPm4C0|0m}7 z;s2>Wejxr|obmtSjQ=O5J~95EnB$NCCqCWs;i&&B=6K=%Y5Q$X)c+N?viiUHf8O8x z!@?I2`2JI0*xn!U^F@D~UphB$a!T<3bUyI|$^R4M2jc%dKRe<7k(Y`87iauGF@Efj z*83X1_{H{+*9YVOjqScI_<*b*|4+>N@&Cl_PdPRCf8uscnuh#8t*?XakInCW{aI)A z3;v(l(}wor?*nh|+`TpV;Xb~zTbn;>wT-oZg=Z)HKfhiEoE7{(ab)#_`M;RYH~ycv zd*@EU|I_iW>U{?J=-yu3seN?wJv*G!ySI(r*s$HXv)ym-|Fk@Jt6#r0z2Whn&I!KX z@NE12*Yf|wTWhL<|0n*|-iw3(C%${%uHgSo7(6fdfA?R$H~4?zN3Xgh_yeDR8e|0mwDbXM^H#Fw16F!+DsOV=z7{-1d7d5eSpCti2nGAl7y($MV6 z`Jvt{O#YwR*Q{6^{6F!zOXdatPrQ3sUGV?J4_$vr@c+b*AHFR3e>xubUa>9sf8sl? z*d1-CENu8@_w3;JJ$(2;^l*8B^YMcT|4;3=Tz5n8|HLaS?+^b^yz0o&;Qxu|A5Qpx z;)T}Ue0-kw-+1JLM{*Du>0{6F#B z#k+$4C!SinF8F^sJ}awNM(>nn`1Q1+YDKhS@=)ik=k1M}OiXvaYUknT*w`V?`>($< z$}1e4#Q1;OUe!&{-5~HJMIqtpZKPuH;4Q`@wqqO9{fM?O7kOEpM91u zKj-FKga3E`NeTaN$MY`+|4;mrXP*iFpZNOK=Li2!^OFg61;PK*{9$d~Gye7j5V{U(~~^5XFS;*9?%=K0*)&pzzigYo~ged^ob|B0*Z z_j3F{XZyV!|4&T)OZ-1^nLY0xzT}=H{@p+CawcDE)i3X;f3{V^-@nIJ#uprzdQAqGydQH-yU_w|C@N=h%?WJ|2gDF=c#sn zo__O?Gv{Z+%7e~4&(3UigEM(kU*CP5Gd|{Bldg5~p68Y= zxZJtYt|$CI9WSo0=Z{_L?L2?pHhN!-i=w>G_Bz*Ez9ash*3a?pe0+EPlAm-6z8^j& z{$HFwKDe#^PhL`(1Tr~asqTv61aa+6K|COFMG5CMtOv^XH{}XpKKMem* zd|F}K;Qwj;8J1sn!Ttrl{efxCg8!%S4I11$_YrY=Zs*&ya?T`$e{`mPDgK}Cr_;|L5&S>#Z1bz}|Kg1QC$2O9iTpn? zd4%|XV*CyKKk?M{iTpn?`B&us#Toxk%>57lPh7iUBL0;#{uch9+N-P`|4+QYd@B4u zF?nP7f8v@=lY;*zuH7;v_QF?T|NpD(z5zw9J7pC*a%|FrzPjm5$L6VJB#@A!Y>Ip+7^|HT>q zPdwGekN>CnNb!02c#k?Wf587!d$r|@;s1%558(fa`98w`6LY^O|1ZwA{-?$GapwCx zt??-TPmI51?W4pTPrE*x@f-2~)Q-=F|0ky2E&iXF_2K`C@#pP&amJUo^*ghF_=US_ejQ^+hsx`sCED)F5`w`}2IajTpgum&`{J`?koOwUM#_wFSz6hVm8DGw> zALk{TCv$x{FS7fA?XR=^KOJv;O8h@Dei{Csn0EX>G5L!4e`4|#@&Cki_Ibzu6O&hL z$J4jZ`0ewV#P<1h=6u-a+ZjL4j=wYGvHOFw{6B4v>%s0X-VWROa^`x#|5JbbM*Kgq z{6De$KQZSA|4+>M!T%F8Kg0hMGe5)s6XWCI|HT>qPh4)tAOA1T_7j_2>SC|0gE@v+k~5&g3C}d46AK zJ`XGM&T=lX_haz?v^?*};Qz(>q-%yWviXG6|JC?U_|Hj<{}*q^{}b~*4*s8*`6B+G zvwi>J|B0*Z?+5%pXZ!mA|1Zw?e`5aL!2c7Mt+MC!R{z)8?vJuAN798{}bc;;s3>%{6F!8xt6DA`F~>S z-{Sv?$=}2O6Av>#2mepZ@umK+nB$B8C&q8Y|I>W0a8^d}|HL&5@`L{;o_S7D@c+bB z_WJ|=pP1ht@c+a$c75RgiSd>2|HQ?XzlQ%Oram+NpLleQ`HANLX+As3{6+jfG4+-4 z|HOmMKg9nNk6Sn@_uye8HJ7&N7ZD;BmkpHLt1y-LJ|4%Ic zPveDa(!S&E{JzlR;_o_BKlrQ9o^kI!c&iH?E#{Uyno1cdNr}0-=ULO9Rc)Zoy#s3qNhl&3uo@&2;QU6!h1AN8TpCvK= zpRQ-x@&CkCv$BK#C#D_$Pdv%)C-{H=4`uHio>iHyZ!bZmN$*mmNDD0_Ap}AaN{|@b$Stlg5j~d{J%Kk|B3Md@&DrU!~YZG1LFUQ<^PHC z5%K@T^8dv0|Ki-@i&H~?`G4{D)>oev#z!9E@+VIZjDLgwr}4x1e`2;L{+}5C1OHFV z^6>w}!_tSi|0hn%80z(ZH6G@V|0l-3q5iL!Ji@L+F9|$h)adBO*_Q^!&uVt{s=)YM zHftEor}fJlmleJC$`#>w%o&sE{-2Ild^Ym`#Q1df`(@yQF=L~j`duBS zFD#fq{j|WPW5&7vr|HYaj`#dO@zn9T(XMN*3EQW7TuyXSuWJLBjZ5VJ>3o6l{{kQJ z|Kg1Qr}^VUk^d*gPs9HczMxdf9g*@A^xA1C;v|@|4)pMi2tYU z&Gh(xVy4Ici!=UTobms(|M2_p|HR|7)7<|P=Z{Wz|4+>N;s0qoF#ewy{|^68%>42H z#3M7)BK$vb&ZtcH|Fk`(jvDU%pW3Pai~lEP`{Dn^8UIgAej)y!nEv>GVthXQzc^F> zSKEj2~u2=YfamN1>vwZwNoxcTHsqX*98UHWN_lf$onaTd$|CN8v|EpgQ8Gk;${Q7x*^|`*!SD)+W z{nh8JA<21(_45Gh*9)%CBl;&lU)1MD6s(N-ULN-r zC-L*IzLLbRfAF6Bf45Ia_hi{}YG^K8QZ+jWHB*!_h2f9n7KzCG^$ ziJ#xU*ZsdZzq_R@jCa4)4}RyX(!hsaf7$&%t^en5zv}*<`1?=ai{5^|IQ0L|i@THd z&wDprmBgDDjZNbG)`qd;qhaG@CNB{Guj|Tnp2ugezuf;5cQC&R|L@xsm(}(g)?*C$ zZ}@*=d?)-rG5LG=e`508sQ)XDQciIHPxJ3Ty(IeXsC&cm=TDgu9bS4*;87_lUjJA9 zTiN#weWJT+%hs>;yg>5#sQ-(zgb#?{M*ZJ7{q-Gz@#Wr{P{+#u)ACzb zJ~R1$amN1>w{OwX{XcPsmaV-0ueg7!=3f6d&eZ?a`mlXoo|McF@7faDd$wxp{-63E z-{d&=|HO=U?kAf=e;EHy%WG=BApV~ipAY{}%=+X1iJ2b%PmJG)|0l+WeChg)fyp;K z^p_1ujQ^+p$J+Yi|7rgo)vU4mfA&p|`=9uP_v8WN|X% z|JgIW=l?adddc{IamN1>H?{Uj4U>8G1(zqy-}1GSxPM6_p2&*!1NeWOJEUyZMu z`FQw$;$FvD{pY`}4cxNV3GV-?y`A}d_N>^21a~KA&$&P zzI5${6Dqlv~A)3pSVxQHtzq4@l*eje@W;+xM@T8|H{6c z<^JELv#Q+x6K_9hq5FU0y;rXF`oDAg&T-%G-pg0J|0jNG^9J|-0^hpP{Xg;Jo3D5O zPyEc4Yux`6KXU2$p8qGl{)|QL|B0_XE#d!(uUfvq{Xg-##k1W16Q8tbj{AR?T|U?S zzs2)rxc{g2bLY=;|4)3=stcn5oAPV5z7JowK6>GX@qwS)W_f(qjtl(64HrcXE63Ch zSToc8zI)f48s(Jd1>SejV)y^l4&(occdb3&^Z&#Ttv=WNKXLUfo812s&)u=j{Xg-X zZFhM7pLpKwJKg^iFW!2$`+wpEx9s%%Kds-A4LjZc6ED7Dhx>oxEvs*J|4)3@%(LD9 z6PM3A+x)iiS`z_bp=Ki1f(N#CP{}*TcKk>zvZ*>1peAdNR zc>bSw`qkID|0iDe-=wP#QXNtMB{$^b&Z}!mMvTyjo9;fO^3TXyWcmnpnddI`DcMoHQ$c< zziO{oFg)6^{#P~sH9q0*O+B${!-1C|L)+vU*U?;?*EC4Ps?@xFR=L~_zdVq4{Cd z{}tn>;QxuqzoGuG#zVda{-3zSd`SF1G2f%(|HT>qPh7lYsQZ87qQyga{~OwwAO4?~ zPyJW?KQX_5%}#Q&@OLtFR%$dg?8Ys>q4p^f`~JrcfOsrgRi|J8A>`+o~> zZSDSFv7Jxk|9$+oRtf)aMI!%CoLX-0C(Zv8w=L@F{+~D+(cJw%&41{in)asN-8Ir#+l|HOSN`@8=q?prm${Xg-5S%cjF z6Av+8`_1PY)rd!0{lMp&91}QeNow@ViUxrvTmIU_5&zk%{?rdmIrvlHN#>v6|LJ-L z|H}M7G1sqG=KL`*KHoF1eHVDP<#FDh{dHh`K>R;lkICc2{}YoJi2o$| z_56nL?)7$pQ*7}oo*rwNG zf$^8jmmRHk*!l-%`{Vy@R&ud9+`!_J#zxU%$2cBZrKf8W}`QroP|7rd({+}2>)coYYoKJTB3XD%@*SEk- zZ~HfJsa=oEj}A;eqvfXtW_pO!~{DgK{$j_>b5f$^R3|1^Hsj{hXa|BJWd|A~42 z#{UyjpBev8Onxo?pSa4dhxmVi?fk+26IWP1F8-gG?}PCF;*9?%CV!CpKdm2sPmup7 zrv5ShpE%$Ce!>3}ms&m-{-1b?{r!UfC!V-;l>2{T^3(oZuqbTrF$>c@|4;jKl=*Aa z{}mUQ&x8Lb9yhh0`+s8m8~i^p{tf=0SpJ`Qgyr9n|0l+Gd27VQfhSe;_544zGd=#F zo)_^A@&ClR#`u4FzJu}q#Pa{*+|TO&#+m#-J^#@k|4%%|d^`NVIOG3`N80yx_eQx5|FPh4pA3Gn~KvyJip#53&t#{U!J^Wp!Ar&~TL{-1c}vXRm3$u9(+ zz9fkGyFes`K(m; z|HR}k;{S>9h!+JE?W_|I_=9N!jV{|B1(D*!OQ+=I4n$ zAISVay{}169pwI>7$1-NzhZno{6D?#A>Ro9FV6UXV)CW_*>G`Se7lOFO9E5h@u8VZ z17{EE8#TCmSzz*s@c*>@w4s)_Yx#d-e21ouPYL}Q@51yIf$<-noqK9v{0aO&jSn9K z|1Zw?e`4m3|0ibs@&CkZPy9bI{to`1m^>=-|Kd#kpT>_5ga0SSKf?cuGyY$k@&Cm5 zNA~}~P-6PA~eGa|CAufTn*{v`gN#xtl--{^0JtMi)tc#-FYbZ*l&+VpuH;6_@lKqcKCl{{7n2m@l?z6!~fItF#exd`G4xK{6Dpm z_elPqSpJ{5DmTadKdnz?&S>}l#PrAi6Ei>jKk?YyQJ(*&{fB>t|0m{nCI3&%`jP)9 zt{yeY{XdPT;)wqzR{oz@{+~G2>iOdTiOJ);`KoP!nLqh|YG?lVe`5K6VthaRKQaCq z{$HH&|HR`mv)um^j~zZD!vE9uVf^@iV$MhWKXHYP7ynO8ePaASG1HU(Cnhhj=E^(6 z_M2ipDE^*w*+=lcF# z_Mqf^zEJ~{^Z7CdC3AhBuRhnGfBp9Q{vh|W`1+1aA)&4Ac_OP{@BfvpF{%CM_=KLx z-!m*stuOECPiNAa6!2iSK|83vU+4KLtd)@MAEdNjZUsk`D{6F!J?;UdgPyDAN z`G4Z?K77OdKk@HAI_&z-H-p${Xg|T_`*K- z|HLo7RO9}ic>n(ABK$v%ci;Zq?*EAoyi)7_pZK#^_q+cm{{H%BLkx0)7* z`F;89=htzMHqAZ%Ps_s}#Q%#k{-3z_ zaV^~c6ZdSI@c+crH^%>qGyb2(M?N3^pSao43I9)wUx)uE?$D-{`+wq2ZJWFQ7iavx zz^&W3|0m}8c);u%!v10V;Qwj=wQJeL{lArM6aF80gZO`9_6Po7+Km^x|3^L{{$HH& z|Lhsx{lBP5!v7N=)%55H|4&R_B>tZm|MA)tR|IBxmaiR{@mT(LV2+0w_peXl?XBw= ze--~vTsy6K6I*#{IwVKAq|Q-<>PZ zbpKDhWA&Nt|B3Iva;5u!D|^m%|L=}|A|+ev)uhZ@im*Sa{o`fX!B~r1!6Hly6 z_v>HeR1#|@j@{}a!#JWKpP@yxZW-TxC8UU{Yaf4|$% z#r?naFT4zk_?bNUf8yzjM!Wwfo@(E#}#xgqG@1wqLs|E)G zPqp_=_OIr9JF{A}w7YU~}T`+jT>{68`IC-{GX?R_r(Uuu(t|A&8o|2J=KJI|wAU_Jx> zpLo9c3;2Ix@>B5t#B6W;KQaCR{+}2>0{>6U`%wJ9I4>V}OJID9#b4bV7#{=wPyKm6 zjsF*C{68_i9{!&gUl9LKOnwvopVpu8;QxskKmK2w@&DqC{}*TcKQZ&`xo~}0-c&nY z@&B~^DOOJy|1Zw?f46+m*8M+x2mHUoxe5P|_qX_eBRVAfzlke`N1d|IsoDOAR_^yv zuddOxX9k{cz7zR>YM*28bMXJ(FG~1-r7OmJ{-1bg$%*d&iQ5$RaQ{ynr8jZ^@APw8 zd%j@Dl!X7M@pK;4!u>yux7Uzn?*D0foS16gdzk+x?l-iR`+wpty^r?%KOLVPI~?o& zUz}gQyCNLFZMrmyay~B$+_tNI5M}i|0nL9 z)5-lmamu)^p8u!q4Ue<@Kda$e+j8(@d8y+&y8jpF6PtAk?L#Id>i>rJ!i4`PPMgx# z{XcPr*W85huQmO{6F!i1tZ-56O&i+@kd96<2TRl7h8(|y;sN2c&j(R z^4I?eJlTBY*%$sfFh1;$zyD#c=10BBcP{-di5oZmcCWV2?6dOS|I_tx#_40tKlp5~ znCn0OpRUg^{-3zmnEXF6`Jd+B1m=2&|EG5HqwxR4TyMz#i?jJZVfo~*+4Ve$%^wPk zKWO#V1LGqf{`9uM_++)kn*(#b#Q)Rs@Wb%`;*9?%mj4%L{6F!+3kt|v3iBs_5dTlx zkLmIM#Q1~wf8x0|J^o*u@&Cm5Irx8K#%uXpf$=->|1=)_PW(SH`KJ2{sp%E zhySPb=l+KO7ub9*{J%Kk|B1=Y~N?#|A}YX`H24~CO;JaPdxns&%X@J@r?hc_Ib8_9(`^@jVM<^i5J-Voc>Ll zTsqPh5GySoi~ zc$(#ri>$1<_&cJPn>V{DDnTq1v3Y@{}coS&|(c&fOH4deHcPYA>+7Nc=xB^<}@d`oCi8%i{lu`F;uiPmEuN|0kYq)06)v zp1O2|`+s$u>HeR%!v5Z#lDZ>T&xh5E?Dr1K{}UI@NOk{D%=X0pi!=V8IMw`0{6BHJ z6&{0i|A~i9Pxyc0G&|n$|HSyA_i>!>?0JIx zKQZ-}ssAg^w|W%#e{shD6H}j={68^1AO2sQ@&Cm5cze%!CyDX@w1273jsF*C{6BHI zG;BrtLXW0Xs?)+5#4&xCrP~Z&d)-B`G1-o#{U!J!=^s@Rbc7~Ki%ryA z`NMc$I`D01ryh54@81TVGA}K{|5JaS@9_V`ldb)VQGW=`_rdsoYKQUv#MJ-B{}Y$a zNsaLT#N~E=;{WM-R94;J{XeyrRS$LlPh46x#Qi_<*eNN|3#)z#^UE0DEjskcKLZzx z?qN^kb?@sZ}8G0UI%%aa0+9@;N@?30rN zXQlRY|4;o#XAE@zPdq#$#r;1q>xcg*9+N)M{l7Tl|B3N8@c+c*Q{n%KSs(mAF?oLY ze`4|$@&DqC|EKLK|4%IcPmKSC{}*Tbf8cSWhDGM`)Xm@W*YN+eJo5eU|HSP&w2mHM zu`2Ja0~fmQcfxV)qRT$HG;e9Am9+zAcO28ZRj25SqgDs**s67O@y*HHdBB>`KFacA zPTIaU%x{s6_vo~Bfya)`puSk(f&$9}GyhM=+vKr{{6BHwxRKE<^REo;)ZfMb)BC#e z(IcWE8?FlN_*VFTVfryS?*ECY&x`*j#s|dz6PJw};9h@pAY{})3d+v|HK>*9nQTmFn%5Re`;6$pBR6S z`oH2TtG7J<-DD>JPwPjXBL1Hk9}xd9ur2?y6E_Fuc)j(xI>z6suDB(%yQ5@o-jPi{XcO*#)t_2PmJ$(){Z*Hm&5-sJ_2f-}kGZ&sX2q`#I)*6kp!YG1vQe|N4GjeLoH#KHk56{oS9- z>%)JJPhUS@FKa+@z1{l$U45?a2iC9e`+w#7{$c&)rS(tt|LU`?T+;g0=lKJZkB^V; zc_^uW&A!?se(T-0llZr99ZKSF-gw3H|F(V9$^E}?kJSGa|M;uJ?*EDZ{?Xg+|B3(l z;bE`;EB?yr1^;pOjM|$uEy?46*C;sIF z_a^fHx+eU;NAJ7a{l8sDnD#yARMv_Q)F$%(G`;fw#QR>TasN-_d1+t5{}UfNknsP+ zUmSSe{Xg+Huf62{pZEi-4~+jO{^s-d-T%|_{`uBH_y5FSKJ$xc)Qv@9yfxRJ8~yh^ z#kHGOcB%c-+k5k7^lO#0zoX*}W6!sdy&l8=n=vfm14d1vXwP*I)t-``@Z%aB*UR;3`F5R(>X`gE{68)4D67wk|0izH z=$HuqPt5wy`Pa52#{W}$d-KQ0{}XpM-wXdwj1RbP-K}9f_b}^{6CFf{-3y0 zyEg9siQBes;r^evL#Nh!zY)gYwPWk3-Cu7A+__x~_y4rMZQ3>G`LK5O-!JvNzZR_$ z{+}2>6aO#H_WT(b|Bm{|m@jXu|spI~~w|Dc?MeM#?eB?}xAW!Omjr%d{n_sSUG~uo_W?I=y21TF@pV^U?*89RU1z!fclR}y zx&J4A>EV0a|EuGB-TxCmf8S2`|HOOl+V1|J`03lXc>bSw*S4+h|A`;ky2brJ@m-s5 ziiWl>uDxjGZ1)9s-gIO1P}8Eo_iowb{-4_K-+HtAf13WmJMV~Y*j!Mn^?Ul!hu!}Z z*WA6;{Xg-}D=vv%tr}aq?UL#4`#pX63itoSk6f}S+G(!?uFsxk_p^p$4y>9V&CJLN zd}v)F|4;p2TD{c$Kk@aGhr0hKKBa$S_y5EbY=7P|VPshTQVSS$p4gpI~_i_P#bS@3TKIeJU`&hu-%66M-`p4vVH;{&?U_dw*r`e*-K3Ps>yOpSa5W zNc=xB`5)syc&KiD?fu`Xa~=#_ZtuT;nt6ZCb<^85bZ=nt`cB(&Phjd# zZol)cnmKQ`b>ENrllXt)xz>*VC!S?K-7D|jUQ;zJ;iuvMjXQ69VEKRQ&--Qkzc}On ziRJ&r8UIhr`)B;WIOG3`@d@$&#PrAi6ElDOzc}OniKz!Y{?6+H&$Rc?IpeMkj1M{D ztE&T7Sw0W`pSCaCZ*Z?GLwkvBAA5fnxcZE2_y4rKDW_z*|0kyY6VLX+Me9n^ZqKW{`RllJin&dE3MqWn{4%yE=W1M=ItFVJi>#67xZxdPkijycJBX)qcnRy9=|XwztNyZ zp8u!uwXpiMy|UYQ{a>wb-@Fd)|7rVmHJ^?AKXH4jXG{HGo!>)xHF5t>+{g0y z@c+cUx*o&(>2QAZ>~geSpGpGb2Yx!FC~&)OO`@IGPYlzy>ve3@@nC-74ktGD{6CGS zRo_PL|HT>qPu!+|BlrKrZ3i@tcJ<2)?OjtEx&Np2?`8hu;RdPU_`vsjaopg*_<+0D zrUV{3s%^Auf4{)vO8UD0r}M9m)vKfaueSFIlTNVrqum2%PU_+QU%?++yAPN#p}Xh* ziPI)@^!z_@#-z@k|0fRwGwpx&>UbVy^}Bxc=HCO4v-`s{EB+L?5Z|fE9|D(H9@ho;{wDC$Rg>-b z{3`I`i_5JZ^=ErEzWEoFM3-j#DlmS?<(+@ESJzkk=<}|8CotDDyWa)IAGiBg9h+Z^ z|EK%g3}gI1F?n)!zX<(d{68&kqFt}>|HS0e;s1%pT76smzc}OniOa1W|4)q1X8uxO zuIG28ToahQK=Z=_lW%rO|0kZZGU5M;7u)ji|Fk_9SUws4pO}0x%Y)pb{`h(3cLt{3rumwC z)E~zG+x1BY|6W4=pO|+1Kk*pL)58CYGyb2L>GA)>><|1uaj_k*_<0WvV9q;&mT0Zrt$^VNp{-3zQ^7HWj#Fghya{o_U zX!jTL|HKo{9Pj?0xb&<<{a_ zz7YPOxO|yiKYlnTN9#|!9p8bgtbVC&pTKjB?feM5$b2dMKTSX3!UFgI;*9?%o^;V9 z_y6LI|0kY&K|beq;E9&UhySN`{5Sl+IOG4t8UHWN_o|`kXd9LpF@V6(l3e5W9|EZnzGgm9dW8D9%YqxsW=KqPwTgCqq<6q+c ziP?YT|A{A=Pl^90E;64G|4&?OzBB%x)}QO;)iZ_$o^Q{K_P{dHzqKCA^xBGbN|Bs6DRIplVY6B^HE@YL3@5mV)Fm$rq6c&Pt5mMWy`C> z`t$ddJ--E>ZN3lwpZd?U?@xaB?3~bEd1`ia?&|r0%dMX1{n?8{|B3dzO#NR?KYm%7 z`+wTrr3(`Ef5k;}2f6HrV|?F?oXa_eE%j@&EMvhtGrmCoZ&n zFY^Dy)Dy=46Azne{)+j3foBi#{6BG;ZLb$D+mNg0$rQ_v!~YWxSvJc3KXLl<(eD3= zGwkmR{68_r1OA_Qvi&`a|0l-p#QziXy&(QyoS*HsEmzNPw2xc4J&6y#dwXEMm&5;4 zfBs&_{}boh_bKH6iL>XXyZ1amN1>%m0fr{-3ze@+R^B#QEl5;{S<@XAE@zPdv{4e!>3}XIAv^{6BHdjDGI_ ziHoWSxc?_EF@F&MPfYz^{6BG(`L~xJdN**j{T^3(;`@Q8+ws%kk`Dq`&L12#J@Bh= zyi_l=d^hv|bo^8-9_{|0xN2!`^woQxhIZ;}3`qSv@M!b*&b<1Iz!moQ*E3&#nZ!}v zuLGCb_Q_rGO*p~{1E&p$7 z#Eg&pKQaCg`G4ZP5kuVn6OYNVdhq7|iA#qk>i@P@c-hB|0ia8{J%Kk|B3Ni z@c-hB|EKMVFGT*I7@v#$Kk-!ax9tCc$u~21C(Muj_|SRed6>i_Ea!_UM26VJ5zy!d~5e>cs1K>RH_D^~uW znC0RBiShfW|Eui{Q~y_7FwVZmH~&xl$-~3{6OYNUdi3W1iStHhMcpsGAuxX8Z`*H3 z;wN_1F@7KZpQgw6!v7PKcZmNdrhYU2Utp`RO8%di`QiVGSw8-snBxuqPwU6|hW{s~ z9sf^EejEOunDZb1Pt5s^{}*TcKQTTX^?$Ye()4t%|0|aN7w7+s-x{XJ7klobI_7$D z-kGR z!~YYL?}z^vXZ$}g^@ZE~d1p9Zv$GQUe>z{~|A`qd{-2obf&V9FeE5H2{6_Ns#B6{3 zKQY%Q>i_Eegz^8x^8du-=TZMxjQhb6Vw&+Dtt_4E4b`+)V^ z>-&F`QFaa-dc5_yeqLXFuJ7Yz_DjB>XQU+i zgZ1+QhYm{i4}Xq_3{0Nipp<0)Z^)qJk0qw2>~J`Mp=8)HX9~ zD=+Kl`83~|zlQ%O{>GM9v~5~#)xi$_{`%eLe;IxEo2h}fUv;7Tf9ikz5&uto`&H*h z558R;=C^&r^$Gv)$ar?`IO6{u;d}0~ydm@dzJ9Tj`+s-exz+tY@x$hW?EQ6B?Vu%{ zJ^$~)ZJXWy6W?&pPWS)B_wC*7`G1=J#XY+{|4;nt{@R59cVzjm?0e4h|FnHxf7yJ$ zL8W1Pe)O{WfajG2{@8p#>i??$hXlZs~agOl)CRlzj^?${)yEb?KPh8#pSoiy+8)K0xx{68`N+u+Bx2gV08KfdR;# z|F$g>^?$|qbNGK^{JBg2ac!6$|8LX0I%fUufBBlw-k@ot=9OwriRJ&rnfyQT%ziyR|F8Q8)7|&0xn{llf8qyky4L+a@%AfL zx&QZQ$C>W`?YiM=_y5Fi{Nf?^|HKD=`GEU>;+p$+xc?{KbN^2F|HO~qk?{Y-yS8t4 z|4;nzwr%eJiSONZtLOiT@4x*v&;JuYv~!#Le}6k`mivK^-G7(+e`-JU%SYV*)A}9Q z^`QHI;zK)bcK=WO(CTyD|9k(UY3~2+y=k*S{-1c+pqB3ciF1$me`5S_{6BHi&duHb6HlF1>i(bjs;k$y|0h0p z-4*WtiT7LnA^Cq=-qrb%eO|Y(uV}T zf7Pa_aM<9$k6pFh{XZ@L#oH48pZL~$9(4aN&iH@g%N~3*THe2Z6661=ednDIyZZN`C`;Tgl8<2Q^J<0q%{J$5kZ14Gf6YTeV{6Fz{`#v21 zPds_9y%&4+bu=dCo%nxZ>doN)iK$I6~;g9jIr+jX?Cs z^8ezzr{lKJ&imuc-CL9R(V4dfrhX>*e;VIB^XKsY#JnHI|BEyJpP2W-_8+V$WkS|1Zw?e`4zC;s1%ri^2aB^S(WO?Nv#P|EG5HYw-WX_#x!~iHoeBV#!(S z!unHR8vjq*k33BLzk^@4cK>gR)lbC#`{Q%1-2W@L`l$oHKd+|!=9ZrKhp&qN_xfL3 zxc@iX)*t^*Ont-3w@(dRYWWKIe`+5-cev;Oi93($?Eas)%kWmwFMBKw%WIW#Otj<7 z1%aCnO!$8qU)NC`-2c<~`)9Xw|4-{bEWeZce>y$~PweXcpSWkXecxmLpN{YTL)*Il zCvM+0;s1$Sb!_7PpU#)ootpCgI-Ea^Iv?x)pW2&QzPRO+h4!w!Te$zH`N7vW92b^< ze7}VMr}1^}d#vaGiQ66V|HSQ&_3A46HR1n>hg%*A{-2op5B}f1 zT@pU)m__zJ)cim3cst(l|HOq>pA`R3Tw?yr{x`qftMj4a!ijc#ei^v>qT=Y1wx0y9 zy09pk_2m13t1p}!jhyyY;7aq;UcUS7y*eJ2nD6v>=hp)-Fn?+1^#=mur<;!+nEK&% zf7z?!jXXH~zc^1__{-2AAJBa6B({9kz~s+$-?t-)n`Pb>m^{Fr9=th;@&B|u@=x*q z#MB?g{}Wf4KZ*Y*#s|dz6VEc=8UIf_+w!;Y|HSj{dWiogCQpt0Kk+>C3Gx5pjQ=NI z;CX3%1JAeRlmDmo>E>TO`dq8P(=30@{Gq_)vEl!zf4N=%@c+c*kKzC6`Gt1#-vZCG z`=90G1)gQw)AA7mPxL&zd4Z|Fj{m3UuY@mnY+(6+YUloh|EJ}{{L}dGjixRfmaXHh z)chSgJ_2+6>}zt&Xtm>~TK~Y@AIbmI{9yb)apifrV)FFJ{}ba|;s3>%{68_r)8mi#3ryY_{-4^ZUyA=HF1Pa=|4&SQ6#ieF@&Cl! zKkfL;(fUp?Ul9LK%=0P!pBSG2|4)oRkN+nwH=harPt5qq|BEyJpP1_n`G0Z7{}WTM z7XMF-Z-)OD*nO|31G7Ky|I|L$o{#YV;*9?%#vjE0i?jL5f!RO!e`=Ti7ub$JtB+pS zZjAq@cAlT`|HSxZ_P@c+bRR^J%^Pdw$^9QXgk7Pt5+u{}V5<=SloO@nYLv_KJo)ostNBmTIi3zME;-J z3+AM_|0kYcejNUvn0lD_f8z1xpWy$A$Icky`G0!8%QWAP{68^ydiZ~0=7;|$W_kF3 zV&(to`EIn;6Slt}a>Wy>2D<+zo_xgr)87l^d*T0yCz+pw|0kyYG5();tmPNt|A|Lb z^>zPGoM*ou;Q#6Qaontd?*EC4?e7Qj|HN#6^8dvAJ%axi*sj0$e{shD6U+Y-%l{K| z{l@>(^Cpb{C!V<|Bf|d^&#=F@@&Cl73v7Jm|A~vtzrz0$%l{LPoIT9_KXK};!O_X{ z@6FZo>M+|r_C0r-Dn#)tnWF0uN{_JQA=lFl>PyJr}zc}OniRn-M-#Gtu z>&sz&_+^*;=|JF7R=*biPyHuW^mhMGoL|<%{Xg;O%HHn(iN{Xw@BW{7l=-sc|A}*L z`{DnIxjx|ki6>gVBL1Iv>ipsE|HT>qPh4iduYLC3hk?tjp7y;%J_@|Rd|UGWbbQS< ze-!^uOkU!@vpx&`%jOM@Uf%e5;7apd@&DAH?}hRI#N_Wyy7lY8%1^9KFOyO79}zHe`~TYbU$!JM#BFS z z-2c=3$a};86XVa||A|kqe5s4ZUz#`X+zZ_Iiy9y6{-3ygqsH$4{pH|!?*DbR_j~03 ziF>qc5u;>rhYH}pT+~@|A`ANPw>Ru zb*p5VI3FdCj3A3FUm{! zf8vVV5$^xRIU{{jm>+q8e>_;n9B=r4T0a>7FV6UXamN1>bH3pJiSf(u|Kg1QC+2*8 zZPk{*_<&b*xHT~6TmG&(=6u8d)AU@A@c+d0$Nv*^{^S3}8UIhr`Hue=XY&8VED!%r z%=&%uQysJa@c*=ZSswnM`r{Yk|B3Pa@c-hB|0iaC%jWD1=O_K~|8#!9qPfT7P{-2os_TRXeA+nI_xl5!^-v_MkBi65XTc4>PAD`dP<^R>s53KM1)t_H| zuI~em9-QnK*7pJH`+dU)Ci{K$eZczd^`{@-KY9B4oIc>hr0tQBlI;JDYhb=l?0Ms@ zjkhQ9^H1$g;?LjvFo}QjR&u@HZx6qo)c*P5oz)x1H9}^8&wr_mKO4YX5_^rSh3|4)4N+Lh7C-KxX0T1 z`v3I)o6)l$6^8!5du3mAPv@fAL(4jQ-q723Z*c!lydpQ*=WROZ=;+iY57a(>T*CK@ z+C}dFi5oU*=>DI$k@;5me`4|i@&CjPn;-4|-_mXg|F38^d@ybm-vue;RM!4jtY96Zf%txA=eJuEzL(+P>_+ zAG_Bv>x2KNcIxNi|7m*i9`XOgjgC7y`cuudVg0H9i~pzb9^E|Q{{?Q9@c-hB|0iaD zHs5_VGUjJA8z(}h<@>+H6Gw)1u|L;GWu6F-V{EMwOMj8L9s(rQ14EOz>xP7zx zf8y8gy50Rh@z>8j>HeSi&@)fC|0h21#4p_c6Tf8q?w6%u{_r0^DG9vqiO1akQ~&)> zKJNaX_~qTtxc?_UxaT?d|HLouc{V!t#Ytg)uf4cG`s=L|!ur0mzsCJPt?$#8KTG{z zaqZ1(qYYEX)waBFs{4NTU9#N$Kk-YK%yIuu{L1S2p8xlsQPuAMy}WvX`+wqBFI(dN zpZdSF{$%(6#5?BayZP3wvx&No_@x=UT?*EB*&Y$J}pLp-Z=ez%>`R%p( z(D;9G#{Uz)xPFcMf8zb?R(bxP_^Bl`-TxCmIHNSe{}UIUJS`eGq+hMJZ{=C@qyHY< zH}Lw?mqt$v?i2W~>n?NuPyM%T-s=9J_=Uau-2W5*_KDhP-dA7M==tZ>%{!y*E58g} ze#6@6qgG!8jz$f3|4;q#|N2#ZQnUQr_MTT$HS0w8|HS-0jsN%6d+pr+OSj*{@c+d8 zzK8!OuD0I~@&Ckpe~bSYXZ$}gz90UdxXgZ^#Q&R_nehMkeHQ;uJnfXx?*EAk%~!+! z6PK7jf&V9-f5t@j|HQMc9x49c+nd{Zz8~*@@c-gW{-2od%klrjMfUq3{-1ctf+6nz zi6_sr-*Yb56WY7Z>FfD_T7J)k13mvwJjwDF@&Ckyi-zEH1STI5|4;3_U%>wpS6KZX z{6Fywdw+%hCoViaH`@50N5goEtzP8o+a3u#mnf&)Q?)O!kJ2_g{?V-Tb zhr|CmON z-*@7ORW*Azweq|+^8Zd=b79T+(_4DpAB_K3{(TGg|HxOt|2tTi@c)+D`(OM&F~<-7 zpE$?fFX8`*qq!OG{{E23AAdJ;eP#9Zy3h_j3PFoHwzH`+wrx3CFwtC+ApSWLj!v7NwuzZ{5MMs6>ImOlU*7229|KRCH7xpO@b3fXSsn@gpZXWs^#K1*oNay%{-1cX<#j#!(tCS#e3!4B z5M6WX;lTJj`P1LntMyy4vM3s}?$BOs?^7-)j0QA(IWT@y+jY+eF1PEq-Cy?V_#v-# zSHGwB>Ubc3Y0I6z2+aA9|EK;i{-3z`i2oO7{6De$zc}On>G;M!#{Y{m{+}3s4gXI( z`4so30#8_x=Ki1B^Og*B|4%$)*)aG2#M77B_w45XiL;jWbN?^S__UWgQ z4?QVId_ep^G4)09|HR}2;{S>B?fZ^*Zn`>0+p}P4 zy7^@r0#{mp{6F4?NBM&%;x?1)gK) zFaDqAU$P?0{Xg+!n;-dq;tJc}_6Y#HD9s*z^35z!m3YasCD-fARBv8G*^O zJ^2rrftTC%{L^D21D|BicldwW{__9C_H_woPYjQ1^|V$N^;Kk;0<-{Jp>=bLYc|0h1x_BZ~Yc=>5#-2W4EJ;47HPqqC) z{a-QrXY1xu0+XMO|EKoxmj8+WC(d3l*!@3o@vI^4|B1=V$Nv-a{DJ=`&bQ~6S^sls z;K4Kcx&No*FV*U^;{S=s7sUUIGyb2LJU{aP^n3y1|A~vL%s;aHKXGB@K+pfv^WIp? zTgLwr=b0~v|0f<@(Z~J2IOG3`Gs{kJ|1Zw?e|ml#ZQpy4|0m8a?dJZUcue^T?*EC$ zRrYlMPduTzm-~O>iBo%f{-2n9HuC?()eAE`|4)qXhX1GMvGGCK{ zbIm`){}WHN@4N8-;*9?%o-{Ah{Xg;K`6Jx_)AMqvZ7=*k@f6#h_FIKk?EPdG7ydezVN?#Qzgl+4ocUf9hXp z$0PoqxZI9!{6F=F@&Ck}ANYUbN~`aI|0kZc(CTNK|0kZgV5IwhVtzlw|I_&ce>ME~ zfyv`szVQ!9jQ^+e8-Ef1Pdv@?Bk}*lr&wMf{$HH&|HSj>X1o6<9+TU}{XcPfMq~H? z#91Sod;XtzTvku_|8)H;$Uf2Y|HRd41EYT*W3LE~{5}T9-yc%1m;67yZ^7SqsC+@- zv8m~v|EKpkzv04~YLK#s|Uwi!=V882<$S zPmKSA|0l-p!T*ah{+}3M1^-XX^!R^b=8yj;rXBxJ%=qyC#P~bMU3z9-zvA=Vr=z}U z{(WZ!t}tKmlEY^QF33vt{69@E|4)o>Wd9HI$L}#WCoto)tggWLfmSOtZ10>=neP8- zeqB4acmGe^_LxTQ|7pA}k80@tpSXqP-H`wH?49Sj|3|(C{-1bI!^ZCaiF4X@jt(_m z8`f`dN?-T?G{1@YW8D7}&ng)0{-4HEl{?)1KOHaBzs3I(SB@Ix{-2IV+VTIy)W^mD zi!=V8nEvGd#W{2C)k*XJ(_iYC{`h}dK8*h-#=pY<6LWmv|A|X7hPeM1XZ$}cpW_Gr zPmJG%|0l-J!~fItF#eyI`oc$@zAUD*M_#b4j`1V$|1`b)KQZfr|0m{n z!vBji{$HH&|Kg1QC!RK9r2Bv3shReCYyO{@<>CK{IiBxpuq7PNaOIX{{?FiBL%Uy( zUZ`WPSJP%}4eiu(ZScoB=KR9{)AE%6C+2#A|0iaD;Qxv7Gx7h#Y@b^;+!2`b6aP=` zoWJ;gV*0mC+Y!dc{GU5e$IKu9Pv-;YFaDo6H+zKpe`4mh;BPy_`3C>b)psT_{$IR5 z{-2obkN+2E{6BG-)eFY|)AJ;VPKbNt8eC-{VMX8-+{d~eZwv9Ha@=*Y01kQotC^k>idBODak%leXd`h zw?6-zA2_mq-=y(nrzHD+h5eKB4JY+Y&i~8mmz@7spL3ff&;NxD4<#+{ji;0Szi-|+ zoYel+o5}fp-@a2XAMmZ0llp)2_5t_*HqLKf`@&zJ$@~2g|4;mb`F;3*Z*@-if8W3R zn)`oSpXuQK-|yag-Tgnc|K`n?-2W4Q@k)*Rf12M%NBlqWqc^ROu1cR;E8cnWY3~1N z`c0?JcmGek>WroC|A}u{eV+S&8qcZgFLeKJ(X@`9|99Hu7rFl@K6UNciTuC6b#(u) zXnuJj|L+J-Sy-0H|2x9>K68)zf13WlvyZv|Cw~9nKKK8${C8flyuYtXYvbJb*s@yn z$M>65RvP$2^Ybp>QWBW?;s2@s$8Wss^?${mym`R=Kk={Mf5ZJh@n1eT?Ec@NBjf++ zllP)gy)EzW2><86<4OB}@2XRhc->eNLSp{uRP+Dhe6;07oznDy+Lz|7G5?^)n5IpR zjnYoLKX7C7lkop;J#)3^1vYEe%<~I&^p7#vMDm|3{`6{@IJ0BRDC5PQVScHto7ndib=<2pD^&MAPxt1nl9>EB{J*Uy zU6hpnCvIWici{ht@%`}s;%xc6f#v_H9sdyjPu#xMaS{HXnEJ)!|7m?%cWB}MpBSGE z|4&T4So}XRzTlW2ZcgIr>N;-O+Vbf3+!Wf$d%Qd4=2~jFR{gr$n4>Kp4*yU43&#Hw zx3&7nPt4vF`uFb8&iy}4-=p*K?*C~#F!_JtejPfy{}*TcKk*>TzsCR5_88E%mHU5U zd_Vj@aVPUNssAfh{-5Tj{68^ymH2-eFZq7<{2Qi+?fE!xi&o7%|4;qdfB1jm4y~KJ z|EJ}%fAIgr>>u*~#Q2)GpS(Va@&7Et+PHO+C;GxxlGy0w2{-3tbkP}ac$Yxgm<8A%Rxc?`{A8h)e<*Oc9{%gCRbpKEM`ksXU zCw^n^ZukGhhmG<7#2>!2&;38G-?z^{=l-Ag7gw*3rcEDTJNbfY_x+x^a;5u!;)gFj z)%`zl?ZvaA-)7|1?jBX;zTXS0=ehqU#s{2f^?${O)-7`XPt(7=ZlU{s;_Wl7K51cg zSpJ2j8Sek7J=gSA{68`A!}x#VUVVDI|0lk+4a{o_!c-0K||HQAZtaSfR zTzgh^lrkzU%>S_^lcGgg!vb%gnI3J=ObxteWrh2Hn*ODWtK9z+@4H}%=l_XczM$Ow zKXJ_&limLlUtQ76{Xg;QNk_T=CqB09IQRdwecR9N;{Kob+y(jW|B0`^aE|+b;>R~# z@BW|ovzp!R|B3(d3Qdo)6aDOPds*Rh5LWvzLxJ#{a;s1&AmSnmACmw6R$KwBqOYHkx z{6BHI`9}DEBQ9&}`G0dy$#wrP&gB1z%TBl7FU|iGSDNpI|0kYz=D6sSfiKrshKKup zvn=lp|4&SQU)N3hYwR7L`)}04eSg@#!2G_r@o;Tm##?lHO<=x{Z`5LM-~xN!ga4=b zr_4_He;Uuw1quI8Txj)J@c-hB|0m}6c>F&x%lo|F6Jh@R9@^!l#{!qE7=!;2#zX#7 z<=969lLyq|i(P@Kzgzp&Lp4?VTf5IU$KKcNUi)BR{IAN|q|No?=G0#7xc!SXSZ z82?Y(kLmIM#N+|u|A~1Yj{g^D{68_<7ynP=n`%DL>aW(;yl`17&-cR*N%{NgnxDRD z>Aqj(X(OX8#h2FHx1gox{oyy@|9!Tc1B@z!e3SdPAwnk{-64{sTkz`pE$~H@A-e?{^`fL|EJ~k z9@5DDKXGbmBL7e0&Cl=R{-4&T|D=xY|7rbGrzHG8Z6EUE@c(pvr-tPa2hfM0`{-5~7+_vuj1s>Ve{Xd_y5Fw3%a}ir|mJkYOwo%;(W_2rrzK44@OKg4c|Fr%v{$Jp;#^6f@#y>LuDlk5kZO_2&Tiv>TkFEz*R=?PMv%vUT z=JN%fZTAQKKRq9D|HS_j7n;9`|EKvC*!JX~c#J*I;Qwj7tRMcLnC*}MC&q8V{}bcK z;s1%Nm(zcJVEW_#X?fM==ivW|RsUDxh4KHy)9rXC|4+>QlKek0ei{B>obms}+&}UE z#N-#^|B1;PGoL9(_`6Lb9H|B1PO;{S=MUx@!F#t*{( z)Aob$|HK^M_b9`DpX<&{|%P$RFaXvoQhk?n@!~fIt)X&EM6XS2<|B2b(y=VUrnD0yM ze2ejT_y5$N=SBQKF+Mc@pP1td|4+Q=+=Txpo^SP{@&Cj;Z{h!mIexla)-qSuPyAT> zf8gS!8Sek7o$r_M|HOR1g#RbzdWHWd#!s2qwnrVGk{x~XUa!DKi!xivK5`Vg57zpLoj2_I}#@KXIYu zNm2h-Ony80e`5Zg!~YZKTOJ(#pLm?*7gPUN$4j35{Z0N~obms})aS+j6O-46|0h=d zpPnCJ{6Fz{s~7ymbywu-`A+qJ#bfOG2>(w!y1c*pe`21m$^R1%DemR@f8wFVecb;O z54PuP{6GDD!t)*epLlpl5BLAXX+>S#{}ZPdcXR(wJkau>$^VNp`G4Y()hX`(iO2f$ z>TRJN{|x_6&zms*pLq77Z1?}f)8~zF|4&?E-{ax`>G>1J{}UHjz0{8$x-0Ow8CH+k z{6Do1w!BCDzc}OniOJ8y|I_npmibfoe`4kTiIx8+W<2EoiHq#}7xMqa#r8cX{-3zW z>a*hii5dT2Rz8-i=Usfii{E-YiShr`pLYB|afxj&^8dueb2Hul)BHF;@c+c6_WdaS zpE%ci>a5JYNsRxecCN4Ze`4;Z?~L9Tc((bRvu@fSc&_<pNIb^#@EIFQ~wISH!}ZETxIR}f8uic{s{k1Jk5SD!~YXcx9?lY{}a!$?_0_L z6Z3rq`F~>kaq|Df%T68R{+}41kNiLJoYTj+|0kY(TAurV;*+et_UTuA9Qx0lpB80) z@k!vac`081SI1+;!ognuS3G^*aQFY>jQ=ObKgIuxGyb2L?^p5v#FdNF-2W4EeBl3u z^UdmoPuIWP(I>e7Cmugyko$jej=xW= zpU?FF$K?O%{SH18{+}2>qj1-PJj=9m-*4ieLGJ&F@e}a>#7vL>C&mxK|BEyJU!3v( z#P}Zge`0(b{68`C!~YYrJp4Z~J_!DwnEB!ViJ2b%PmDi=|0kCJ_d~Dq-2baIUk3kA zEdNi;_^AJ@>0$eS;Hr#7{-4?_(=*)v6O(U+|0l-B!T;0tCohrwKee}O+|>O)@i9jo z>-B%dM@Pp*uiUXZ^l#MQ=;&{StHb!=O`q3sZ!4fR^qe)JJ-17D_y4qhse=c&|0kwC zF775WlLMnukkX}eAp$e!JDFV_|5X3I(*u~z)E_Q(= z6cI%od#^KR=1g&_dd@h`%<=zR&&R#^_?Le`59@{-2oj!~YYrfAIgroWJD%#Toxk zoNs<0{-2n=E<-#6>9s-TxDl_lEx`=6b>Z)AG2!$^VNp z{+}4%4gXKf_TvAE*?;(dV&?Z;%R9sJI6voXYhwE2|AqB2-w*#U&iH>~)&Gq%`F~>O zhySPR3C916Gyb3Y7g{}N{6F#7^il5r#Toxk%=Y5{X?`&NpP2Ix|4+>J;{S=8*Z<}C z#h)*n?{Q}OIFmOR=jQ%kbN{a@Jw2&E`y)Pm^W_&0AC%PIydE&mtN8Q zZGS9@cQous;y2!YBZd!>(RHvn)vHC54!)S_FujAs{4Pp zv`F}WU;W~M`+sVG*XsR}|0n*1<=IjHci5v{-7oyl-OqUbpZM1ePr3gm{`A3{-2c<` zd#}F0{Xg-BOP9I-C$5`Y;{Ko3Cu7z`_y6v_tGoMu=`#!6{}V^k3!|bVs~ZE)E=lD7 zzyJB|?*ED3dwI9}e_H%d)@!j z^dB93$^Ad^+Xwf#|0jOW>if1FP#o6hE!*GYRul#P;Jr88|5JaCujl_A+MeHj`hoj@ zj~?Rxe)E-R$HKx!@f#1^nRI@D#~l~F z_x9${KIG)CQL9l+Jn)20?*FNO%VWB@{}<;6mtPd7Z+ps#?*FO1bFUum|A{A@cDnn2 z;>>QxL~FWi2-D|x>gN8R+J_%@r2Bv30WC~-H2+V0!=eQdF5LedUF$yIa~sx2{9F9i ztv5!;9Z?hbscqN0|EKo1cRua@pZNWkcDw%<=gohu2-CmcxXb-NwZGS})BQj3N5O=cf12N(3zob8C$3+6j{AS&Yu0UY|4)3&<}2O*6HmQxgZqEtk#*DE{}Vqm z$HoIkr-k+X?DEC#|Ec}$D_6V!Cq8)bGWY+)4I37^|0jNWCq7{HtEvAh{@#30>i>$rcxGob{BOT(=+i#o?_E4?PW0Ey zz6w0X@~$53@nzt$X(`cyou3DuJU=b^;jB*^PF~u@^ZjO6eO&xM@%Y7Kqx@$-Z0Pn* zXZP_YE-Q%sr~HG!)0T~O|4;p=F3tD+KXK8LyeOsTJE4E6jlcb=@vXr4dk;-}GjRFR zJoo>!JpR5({-2n?Z{q)nsb7o#C$6#O+4yBcyVQj5$NcgC#Dz9qga0Sy@4xtehu_%A z{l8Khf5rb3i%EgL;jzb@9FXXH2<;YL;mHr7@2+RCG@G zesd1_e`0(&{6De$KQaEvpV~awP_Uw-=lN0p3;$0%%i8h(#Ek#p|A`qN?DEUI8gf7A z;C@<}jo-E1d}rWt%dO z_y4s1sS{3e|4*E2KT|5JNeb;AD>51E>%|Ev8= z9xVQ!IL-1c@c(o?VEjLwfBClmssAe;WBVWfPn>1r$2N8oIJ2~;=l`iaf8z1(|LOSW zj_>aNpLlfPG12Y+Iy{^&+2gvn|EKf2RoO{Valyapb$)f2bh`V0;_Ry4?*EC&v%&up zkDJop{XcO*-Jt0Em0#8C{2gO?P56J}appte|A|ML|APM~&RH|g{Xa224E|r7@&Ck= zR*s8)XuC6Tt>vX%vGB!u?eCeZ3!|lfe>#af=RZ-e<3oOy-OuZFJjnyG`s{(HoRe)n z%3bw3U#437xT|jsjPEzJ)eV91Bk=!pzS55WC&oX){}Yq1g#Q<3{6F#Z#o6xviR|HRZsw*3>h$es_jy@5+SKQLvN-e+d7DvpQW)bba(lku|7rPU=11ZGiOG+}{}bbf;{Si>%IQ}O@Az0jj|4&?SZnpb>;-Xb~?*EA=TK!u5zc}On ziMjvb|HT>qPt5Tl|1Zw?e`4y(;{U}N|4&?N?d1Q7D=fbe|4)ohckQ0GIl8`K{68_r z$6Ttw>|gT#)ShF$3jUv%@0;-d#Pa{dMRSI^|0k|G!+dk||Kg1QC+7DD{-2oNANYS^ z{mq}i{}Wft8Orq=c!K$A_9v(oZc@&Clt_B=i7{WAm4u-{kT+_WHYwfQpV zPhA|C^9BD;+t2qi_i>$6wH zFV58e756Q-dIjeHi3eF88~&e|_c`+a;%vVk1COol<^G@EH~AhC|4&?Ee=i~bPh2)V zk^d(iZ%qAPF}@u2f8&h*r}x!-%iG5P6XSQ{|B16|`g#7Jn0n9ne|n$IF@FsIPmJ$J z{$HHQ{}apq6Bk?lApW1YWTyRn%KSeuJ|O;Iobmtk{#$B(82+D_d_ep^_0OA~=Ki0U zdc)m6dOq~0o&oiLHT`I-|BC-79y2Gy{Xa4HSNy*?*M~Pc=FWV?*EBvt-ZA82VweYGY7c;r}nB@gWUfU zS6jUb^8dt>t)4IbpSarUapV7q$uA}UPfYz@^8ds$XQsRVr}K5j3>)t^|4&?P=Lh~@ zobms}UO(IXzc^F>S6pKL<@^?ZNMigyU0)n;^8ezD|JTHpzh(ZPxbp10=*N5i7Pw$u zj{ASQKb)G~-TgoD;H#hx=(x)@knl z>He9QG06SDIFEid$`y|qIXt>}?qNwx{omX*t3BT#BQ3@A|HPT;snNF^XXTpH=DuI0 zzBw`kGA{XZR_!z~XG|4%%^>UpidVMA^~^|_u8Sas@YUjJ8o z+Mu59|EWLqy72$R<$X_g|4+-CJajkMf^W8^>Fe3;*9?% z=J@0PiCI4WU!3v(#Q074e{shD6KB}=;Qxs;59R-f@dNSy#Q1^ue`5SD^8ezD|0ibs z@c+c}|HNGX_JAPXd1^|;+nLC|0ibt_<7ZO;S3E8=-Ru8~IX?J*V%8V`Pt5Yk{}XdQ;s1#_{`h~oUSa${ zaY0U|`+s82AN)Tt=U3b(qdm^}h;e3p;#@Hz+5am~P0q_}?*BDs>Pg4v$MYu6&GY=4 z`+d!QyXO6y*XwOwpSRzz!AZ*-&@5jtbI7oy_U6p>5?|j^yC256dH!I=kYr!6xewU9 zzHjsP<~(XZa{ga)Ztf2@=jQd7H?2A+Y5kY1S(?OKtp06$`)+ygfh2ySepeE|`)YFj z-^Xvh?)iUj{=JL)dA~G2Y)r<~#w}C3c)rXRukVlUx_C<9_g~u+Ej=)`vFwSi?hC$m zaJTz^;y3s2bpKEM_JR87@dqb|{_nqBA1(f-Ht>7F}Gv{5p5;9Nl-@je(Er+$H+> z@FqUKOV_CVq8mcH*E=@L1 zX?|VWwu>$tcWr2=Ua#dZ2kvuRSNH$azuyUo`oH2+Pw3|UpZJvHySo1;?%%bO`+wp- zof7_^_NVIqipl?@{;&GW{}Z=q*~07p>U=ufwio|Te5CoCHXatH$N&4?KQ9YRUM2N^ z)&Hcn9o+vDpV-FE7pwoP_33E-9R8oUbC+Y>{}Xfk$o~_c(6yWUe`0)8{J%Jp|0nKz z;_>ePiQ9DR;`x7K>N|h>$;QyXTeoiR|EWE@OBeV5#2I$J;s1&IwCm*lpZLTUE#3bU zXPO_1|0mvi#pMxMcUxYqcK>b14VQTSpLoxxc?{q z((?2c{8we8_|rZ0UjJA8;qD#o|A{|ne9`?svHU;r$L0%C|5uDJi2o=4?B#v#|B1ga z|2p><6GQt~_Wav@S3%gm|1ke=+U*kpvwpvxHmXCvIFb)%`#5o^^HZ|A}8-U*rCtc=xJA{-5~8 z)#tkZCw}FUi`@Sc-?iZe_y5FKEZpG!pSWWBH243+B~xnM|I_}iKc~?BKk>`wRl5Ht z{@s+SgCdr55d!2**9g#V}hrB<&A|4%Ic zPb~jWJk$ID{6Fz@^WpIS#N_wk|HT>q?~#i-dEQ^`!tCgQN&6dS|E8n+eHHUYMzg-# z7r1=(5cmJo4&(ocC(P>a{$HHQ{}Y#5fAast754q|-bZ%^F1PWy=ez9;>r-XcPH0XM02GoQ|H~2fx+g$-v}c z9K7f8z|}VXhX1Gj_-z;Vd8FZp{Th|NVjKTTVjCX|j1Tzpj#nfx z{-5?2?f8G<88%*t|0gC75&ut&pMd|T{R7+cx?$E)3EvMN;qqT!*wB4JJJ0tcUy zeZvvIZR@@t`AztLV$Lu8znz5%|Bw24<0mX{`1#9i-1nP*?l|}V#5Ie?yZ-T%}4qT!w0{}Ug3$p6#wPaV<8{Xea5N=_H||Fk{%Wj#IrPscyA;`C_b z7j?9gAozc}Udacse3`(bY`oL*X95qm@f;hU4m`^8 z4s857F!hb_|8zZpLkSFFZch%BddD2|0f=7d3WUhi3b&*>i(a2z_{bx{}T_I zaH8EG(!%lwmz?7MpSCBps+aqJV#aUr|Fr!u{-1b)<>TT1iN{x2K7i%_iHA=f5Fx&J55u=U6P)A=&Iw2%9L;^Xc2JN}=}uhTgGmj5RnP~Fq&S^u?O=i}ho zKIX4}9XPwz#?ycCo51%jjL^ZX{J%Kk z|A|Y?PsaZfS6aT{`_DWZc(&!IE$p#9Y!CHR3txI9@XR%(j3?J?f7L7<$M|%;_IK@) zG0~M5-C3{W4X1W?AO4@X#PZni|HR~_;s1$CR_D9_7iaT# zLi-uiXEpy%?>BSI=fnRKSFJ5{|4&@KF5&-)sW*-Pr}{-3yFVTRZL)%1myCx`zh9&h8}_9dEq|EK+3Zr>x||HT>qPt5Vh{}Wd)Ncex^iFQB6 z|BEyJpSaS#mm>d9%&yE+{-2old;C8!^?ULE#Ix;s!vE9r z2!9X%PfWf${-2odiSYl#{Jy~d3%o4h|B0tse)X-JW`}lu-`t-+H!yzo_QTH%Og(b^ zKds*+^V9MF#QZ*MdD7Cr)C;!fTVVV^{6Fm<@=@Pdv)}FZ@3-`Gfd>dcVuI_apqjz*UL*zv8sw-k$##*xs-3 z|HAv9G5(*J_gnlw@i6oC$o~^(l=pG}Pdv)<1@Zp^m)raNZPy1*xA!~zKehL(=;i*O zxPN7D_y5GaKjQz1d4IIuk2!k(;rkEr|HPy1eGmUnoM-+P{-1dC)D+ME6SM#D|Kg1Q zC#L=@^?&1x|EKpc`G4ZfNqyb_6Zfne=>DJHXZzXpkN+pmviwo}zc}OniMjsC{}c0l zBL1J4dd2vE;xfw%wD-vzy&o5t4~YLKE;L^d|4&SPU;IB!4_~$6xzLV(i2tYlid%aC+7UX{}boh@xlKS^Lz8^yAK8)Yu`)Z|7m{|)s6K0Kk@k5 z6!-tc)DOo06IWZFC;5Nkswu42B^Lx1er~BoY zF$w=qoRvAu{XcO|_V5V*Pn?&UoX-Rw=+Yvzlb?56&CFbL+T8ae4-fxOjK7n6-HhD! zgO7PmKS9|0kCJCuV(a9k3+K58v;d>ZO5c$Ny7*wio|TjDKSP4qQAW)${+< zUNSV1|0k}s{5t$UarGhpPngnSDiK#b?{}*TS|HMp>|0ia8{68`EcJcqjlWczYe`2P`|BEyJpP2sme{shD z6XRFm|B3Ox@c+cQS?TWo#hLs+G3$%}7iauGadCF0`+sr9{}VGk{-2oZhy1@dfq`F}e8T<_%ni8;RH|A{ANkMR7zIOG2Xw*8C$7iauGG4sR! zi!=V8)(;;P|1Zwu|B0C%|4+>JV)wiF^v(1C(#&6uw>S6wn)6Tjip~AM=JkVz4NhL4 zlpzC>mY+U2nVb8A&F9y=y}3`=oOz#!Z|~YQOOkl;`ejKxWAU6MuDNVu5-+=NTM|FE zGr4|n{cEqf|94J)!vA~o)dTMT{rZ8PyE_}M)&_Z{LsaH!p|C?cmFTW55F_1QT*itH@W{Oe(8$! z?*H9)#qR(07@qJ2 z$#cU06TjK;tmprUzk2g!_y08i*Darq{J$hN|4;n+tBL$SP5pTiy8kC$HLW=5 z{Af3`GKr&3MGrf0hUC!U%&*8M+mUhn?VfERBM z{d12!#{ECFXLU>D|A~+9)*)&8sMi|bUh?Ot|EvDw&*A@xqqc{;|0izI{z&)#Do$SI z{vUoB{-2oo$oPL^{4M-HO%LP$iSYyR|HK_Tc69$wOn>tKw7*)nZteb`+BqKhe`0(< z{6BGr)-B!ti!=V8=0`jJpW3NkjQ=NYYxR5o(EHlZzx}b@JpWJAAA9Vv?*ECqTize_ zf5kn!C;UG#J|_8pn!o%%@di>$B|0h2DsKed=)A@E}t0Ue2Q#Lcxh-qu48xi|Fk|`%&)`$6LWmX{}bc0;{S=+f8_s(`-I$cpZGryG`RmK{>1W7 z@&Cm5)#U$)KYFR&{Xg-C`*yki7kE#D=l_X6v3x)LKk<9}8r}aBllOP!gA*IIzMq?~ z-TS`6z+b)gvipB(|I++<{6F!*XSPQZ)5bRbCZodrzB``0Cpsc6Kky>+-SGd^{`|(- z?*EB*ZJF=>pLoxu^W6UvzjVb}?*EDRZ=UP^pSXT~UDPEtE6o3y^Ai5w-U4takrT{OOhr?*EA|Td~CbKk=EB zCGP);*H0^T|4)4BnN!{W6F;(SuKR!DCsv;2{-5|c^94H&AKWN@Z1GIb{}VrQ&T9An z#ElnS>HeR1(M8v}|0kZm{z~`%#CO{J)`Gr$!~AbQZ?XG-+TZW4JH!1y@t<$J!2Lh* zcRzo~{Xg-KPe0@SpLo&shoVp0f7S5z;!d8=7iFa~z8bh+QMagS{O5slt^RELUws;Q zihU1^|2M65!XG@#e7!BleH_}yEzNWPPxFWI|HSxx_*xNTxTG%O z|B1_H40HcaJZk1(_y5Eh_V-o%KQVtl$Nv*o+21Ge|HPG+|FFJjN8lP8e;oOT7XmZB zi~pzoj89uV$A;pkI=Iir`1@Bqo(W8z-=}+@3QYf7?tZdikNpvR{Buv|lFw)PPk|YK zyW-c61!nxM<(5YSGd=#FribzW#4I2GPt5Z1|HR}6_WAz4hKx1sJ5p#;`-AaAdtNtWO>LK`?`zi&{@+veZ4>o<=MRq_AH1&NxjWi; zz90Ez+b&uixY+VwKKkp5hWrx~zTZU4lf?fMk6D}>b-d=Bh8-8SZhZdR$8sy?=SS;* zzc6s$?1cZP{(Vx~ME|(!%rJe=AxFFar{y0%?C9vX-^~r{H^Bb>PX3?PH_ht(F1vhI z*q+g4z1{!Q@y-}p_3;Q!=@&Nb$ zw7(f&#{Y{m{-3zN`R4e4I$ne3XSn|-PPO_>_uasN+TIB&H1t^ZZ8^KaDL9QXg?jQ=N2xAOu2PfUIe z`G4ZPn$z9?6OXR#>HeR%*y_LI|A~vH^>Y7DOuiHTpO}0n{6BGl)f4@}{68^175<-? z=P&-BwvTrFKk<|$nNgql4k|8#!U zEgkLtpLm)*&+-4n_>K5~amN1>^S)qtOM%%QtKS%y`oeZSCb3;#NsRxe`7u5IpP22z z|BEyJpBTRq|1Zw?e`5SD{68`E)ye-8XImcN*U!BiIM2S1u=>k^nZM;J20rA^?b7v} zvBd5dmj4%L{6F!Ob4KFl1txzD|4;8b|1`e@Zx4)Li2tW{ z82?XPy0*amKXLi`iSGZ2@eA?)#O13!UobHBkn#VtK0Lqh|HSxWAOHEgz!S{hGT$*< z?c`VD|HT>qPt5xb{-2oVt*w8y)@Q2iAM=?4PqF!%KN=YS%>2?Mw&M|)`I(=Z#Q1-j z|8#p_!2c81SzagppO`#D{68^%BmSS5_bL28tv~w<|4)pcg#Q<3^8Ymb1bd&t{}Ye1 z>jnQ$Jkfki{6Fz{yPx3yiOZ~BHvXTu^vo3Z|HNZ0Uy%Giahl!V@c+aE=h*nC`G4ZU zbNjjfr|YBI@(1z%#C29r75`6MuoR!_Pl4tCslCvSFaDpH?Zy8Sm)h~f|BEyJpO|{Z z_bN%A~iMf99|HRyH@&Cj{=6B)$iOCPd|BEyJpBR4=|4%&5 z^5E=#6*$fEnaKZBJ52tc_BZ)m_w|5JONi|u)a|0m}C{DgZ}2Il?zfw`*#7n^@Mtk1f@MT^tj|I_pn%{RpV6Bn3& ziT@`aXL;S^|B1((IfCbJ;L&HKy8ox`$(k|5{XcR3w4u?U9+!sg8CBWG{Xe}A>fct;qk=4E3|BEyEe`5SC{6BG?HU)LTk!wHeBXlqCmv?|2meo;V()+D zL+=VasxFcLr*;_sPb~j0&iH@&ea8DU`G4X*6Hj*kPu#Ea#ONPg9}4Xw?R&($B@YK4 zV)X^^|MdQwVtID>e`50U@c-hB|0gc9-#7Sw;*wcu?*Hlik$gY=KXH!zUc&zq;|JpZ zX?hs{Pwf+Jf8hU#3#TRgKfS*)fBe5V+xu=4&rWgwPwivo+IYD6f8z1;68>MD@&Clr z=Ucv@`G4XmbF6-Qr+tC>{g!d&OM&_QX7A&H@gJImh)Jkj#x`~LhFfv4H`QQLofGw>|)=kWiuKda5hqyDeB(#}8X|B7jUcl!Hb z`dafRr#<^YVEoBnxBVzE`HJ{|n!d`~@&DqC{}*TS|HPHEET72yKXL6L|4-*Dz90Ud zxXS8nlm90!v+E20Ph2o{fct;ql9~4V$NWDre_zA@i!=V8xYF`b@&Cm9y$}CSOg(G- zKk<0WN5%gWm)iB;<?vlnMYr5x=C;0VIb8_E5a+&*r_!m8goDmp* z2>;J&>IOfM{J%Jp|0kwiF8-gGJhJDvEC`I>hyQ1ep8Jb1{-2obqyDcr+x$EHKh2MJ z{68_<-}ZuKf!Tg*3!FD>NM!CzVEhit$_k7xNdBLeM_wZSU!2MR6K4;9iOb8v6> z|HRZEqyDdWkmdK`|A|w~?<4}>b{#Q1>te`4l` z|0ia8{6F#J+&uUH#5LJDUjJ8Il9lWJU!3v(#Q8b7?*EC$*!1{+VzwXuFV6UXV%CrR zKQa5`&JEXx<5QTM6%}>AAuxUy{-64f$<2)J9erbH&(F(>%06sjdoZ~Fr{g^;Yoz;s zV*Ez@KQZfz{}*TK|B6{3{J%Kk|HT>qPt5k=|Hb*JC!4r3D>Hg}-0h(qp807Lvp-rd zyCbx7{P6!YzmmLk_y6LI|0l*T#s7;l{-4;-5A*-ToWJ;gVwR8pr|YXMFUS2qah>h& zTTi(+v`;o46#q}{_Z>nGYQO&08djFS`FH-n;t+_y5E%nLqdY-_|sW51Jo% z+3+TQW8aI>XA5c@Z~Cf>`+Ns?Kj-;>Z;Va&f$#2k#{EC>Q@8xg{Xg}8k{}XRr za<=<_;u+^Hb^lMiYU`!$|A}wE?RxkBX0Pw+d4csipKo0li@{|@nGOQ$FD{|@o8$>XAoX9~jf;|h}R2kkoA=@RX> zBGifhwKrc%|K|V6vpYHc!Nysw*SqhB-xhDjKl}Y*4}|uPty)J*I^Wy4?flij@7uiQ zp1^I|c8pGc@~+0*hgZ4Z*VgjLCLbH))*amcQ+wau1Kj@;bN?s*Pt5%Y|4*EMY8Uta z#2MXNMT4HYJuJUR*JS_i)XvHNA3h-dpQi89{%H6A#D}#z!u`KElmGYeUsojM|HT>q zPmIro|EKB6AH@F?cWu|+{l7Sq|0iy1{qg^_f2luA{-4_MCUjtBmq)(1bc*Ckg5 z=6K-$sXyyS{alV-d6aUftXZ|fFe-Hmp{K?CW?*EBD+SlOz zpZLSQ_3rq{-5~ceY@TN3;a@J^v%OXjaol^Km0%Om*!vN|A~M7#sT;L#9!I{ z7ynQE;yt&!|95*vx%+?jUUPx_f8wjxo$dag_!+DJJLX@xjh%m2YWIT{c{{e872Wpl zoWQ#-PUQco|K2OkcK=WO+9hYZ|0jOQ=7;|$eqqge&;J{`tit`j=gbE@ePU*#c*Vkm z|0iC%>}JpZ6Q8%@0{8#KOBSti|4;nvh3nk^6K`L4p8J2|EwdK7|0mu!ZNB?|;;nUc z?*EBzJ@ZWW|HMCEzQX-K@gpnGbN^3#|C$Z%|A}u~vdaBG@s$fMaQ{zy|E8PV{}Z3P zIg$S-o`2q@?*EDJT0PJGKk-dV>Z1F4_X+#&?RC?m&wKU`{Nr;sN5`DrE5?sUTVMN+ z2CISQ`F=ki@=>{68_@r&Iq| zoI7Wv`+s8o-i!YyE}NI`{-3zewg>-DTx8>i_oKM()U#yt_|T9C6WjRk*6)87nEa2UZ@;dI&l~Oj zpVohpG5(*Jd=mUWG4;jp|HRcR%wI77PfUIZ{+}4X1phD2_2nM=>D{24c$Iy<-T9BjVIy%iPL9hy8kEcmUV3O`!Q#S_Ff}8yZ@*8 zoie1YUEg!V^7^JG>i=r}vaP-^{-4%ArRYTW|BidCt^154ZG7?8duD{~&9M4nUt`${0#g*G2>%4z8pB)d^HiE}Ma$;QV6=a~=j!LZSRi)Qq(`$)p#HCz{1g1Yu>Xzm z|HS0ueg1v7z>MFK|EKeH?EGQw|Haw<9on;P|2NER70w5E@Z&9$82?Y_ORo6|_(pQ7L0cPPn>7tWB7k!#{2O9#0BPuqPt5xT{$HH&|HSyt z_V2)@EASVO2uyw4FAo1^m$nz)bogh1@zwDEG(Ymt@c+c6=VrP8CngWj{EX0^V}2k0 zpRV`ZCF%G(f!SXCKefZ=ckL99Uy?!pz-6n)@CO!Z8vFau-)8HR9p-0j z{|?OigVk?N;$g+T15dJgv-p3Sex~{K_ z^F0CnpP2LAzE8>4`AGhoz3&DdcQ*d|%YjGF&$Q>=>w&Y(FX*=C?Z5+PTRzJ84+9S} zzk>Wf%^x2G|4%&8>PO=LiSftq|HOs%y#o1vVy-9rzc}OniSe`W|Kg1QC+7Va|1Zw? zf8t{M{sjL|Tw>p!*uMkwzFEDuQ;x2Ge*et8sB2*ALF4~v`fAHN#s3peUYzCrpLmkx z1>*mS$s@%76Z8In|0fQldp`+WZ28Cb{t_5}2>(y(S32A7XXgKj3(bGT{}WF%|1@t? zQP_XvD;DLK1}1M1|4;k7*!(yAzc@GCGAT#zANYd@YbFP-wfm!e{}Fhq`KABy*7PL) z%T=?I_@5Kc2#ha(^wIMJ^Ze|(|E$2Z_I`cpMGFJte-6w&Cos>e^nWc4Tx`#`-|brw z)*t`*yG`c>#t)3fu1(_BN1UI;-CnvdFu#xS|Fl0V$cs1sPh4*MkNiLFFZM6_f8rv` zlO+F7OubtCKXG>T0G{W8N0#<-|4;inv$CK2f8un@i~jzotHSoCRrHT8oPTxTl=6iC zr}u}{%D(RZiJ89BMc0M?F#ey~^Q!E79?SoWGx>jkCk=G}FV6UXamN3PGyb36H%Hs| zGx&dT#{U!N)DCw4PneWd$;V*D@i|HQ>pQoR1Je$UAN6Avsq z-TgoDsTC)=|0f>3uhS`at*p#JP5V!2c5~|4&>rJJs|5#QgmO|4&T*8ufq0 zd>@7Xr}t+V|4+>C5&S>(=l2T!pW4S+`xmXB&(ZrTO#Yvk`pNizamN1>^Y<0<|HLKs z`wagtu-$*i{}Y$l_eA)A;z{#Hxc?`vI%Bx|e`5ZAg#Q<3{J%Kk|HT>qPt5%A|Fpf8 zc75UhiOcQ#+NBF$Z|ZOL2|;iL)}IMRPw6?e?sQ{%fbz13vWk0r>nbR{!@9PclCc z|4+vk#{Uyfo;fnw`iHLq*IGUx{-4g*Np`;A|A{Nir^Wvh^ZSVWKXH-yg!q4A{6_pg zF+L&wpP27;@&Cky_WKL}Pt5g=|0f<}*E9Z~SpJ`w^~3)YlMi_Bd*217{x|-guIK8h zsqX*j{!%u{d|vbabbqX_9P0j`cw#|s_x}Rt^>zPGJU*+Z`+s8cm8kzK&K{9mUy%Hv z*YoRgw|%k1eLWceui?%`?*F9@8|40(xv4~PFZDEA!q|L_~||1>}RIs8Ad z{6BN--2cN*#Qzi1j{hgd=fM9HQy&ulPt5fAf0o&o$S<_z;s1%#h7XBmw>T&CXM6Df zG(GzR|1Zw=??KKlp%PfUOOKXF#-0QdjI=|lUt|0gD| z3I9*rwe?Z%|B2fk%KwY=D|c=P{W~0)$p2G&PxJlo|FpjS`}cSMPdv>0Mf^YUkYNMe z|BEyJpXQf4*z#PTZ{jh-Qr-VkJN^#-pO|{hzn)`aq^ZT0ngw2=NeEQ~o-%oMbgt1Bc zXVbdXNqp(L}>T<^LtI<^PG_d~Kimf13Vn+dlk1@yD<3bN^5L+3PR6|M$qOuAb-j!t1-;{}cc0 z!Q0&b6W@C6`HB3$L;dGW8JEcaJH(5s(i8cAhj`iKZ1?{(eN}N@()n?Gm!qN!Uz^yt zF*>I4&+8j=@yFuV@3CEyeL3>+$~)ZK`0(15?(cQ&&?>t4yn6!UXYKg%?!e@g{n_&U z)c>$nE#3bUA7OcA_w;J|4-b>o-g=+;^T)6jgBq4qw#>% z<9*}x6Z4|(-Q52Z_io=NY5V$i{NMgx^7bdUcj(mG{XZ?QZTq7<|8LH|bCdi(G5Kux zf8t*4TD$+J=})(OHvB&^`;YuTF~$OeQ+uzj$GHC| z?rC|C_tJd+xp2^Z#)AsQ>%HBlo!f zC;t2E``rH%e`)uB{w@C4@?y#V3%qxi`+srX@t-U-Y zeE5IjPY=HA{-5~Gh8^zziFa(@9z8sLeB**8H!X4hPu#Hn zT=)O9eh-~F!~H+;+^Nev|4+R5jJ59niPz6QGkP**WLV#Gs-{F|r=$hmFs<7CKlR@< zqc-|%SZZj$_3Q=F4a0^9ZoGPHR5~mr@XOa<>HeRl-+lEK_y5EV=I`I0HZ<(t7q@J1 z|4;3AZn?z$Kk)-sUG4s#c%$X}Z5}c(On>o~8{Pj?`&k<=_545a-X%c znrO`6K7pTJQSJVp`oFbdq5FU09~&Qb|4;nw3-#{*-E?0^_y6`^zBPJn-me-YYSy#BAa{H(!V|5sc+H#ItV{wEDrwMzJeQ*Ar}|4&@EBq!?n#s>|X z&*|Xf$&5diEqFh${6F=tT$srJ6Ei-8{}*TczrdC+g8wJ3uskIEKQVv*#QziX_fPyk zG4((2|FnMmJ=exB8`iwrK2h)2zURjO6H~7f|1Yrh$Nv-KL*oAhw(&UpKXL6M8z0(N z-!Q(iz321cU)bNL15dL27xMqqpZt=)-}7QpW4X>TsP_G4ShDY zb)S#rfBTOI0+Zjj=#Kl782>NcAOBB`FJbkOk{JI_?Tm-x|HT>qPfT9Rz^iX-`0mFx z?tj6*8GdVE)_>c_HwR|@CtY|`VEVW3bz>6a|HbEz{}*TcKQZI;8%JLonCJ zcrCyD>cDKz*MqML%=qElcdrOsy&x_6{JhHpPg-QY*@>40u01C`dUN+Bfu~rWO2ND> zf%)EjcdLs77tI~){-4&j(tJPszdy`v<9UD7_r?Ev{y$oWdcXgZzqVn`fmZJOQJ)O| zPh4mFFXQub88+zSJW8GjFqKY{d3})A^8PJ|6yGobmtSjQ^+eJ;&;!JwEuK^*XI5pLmpw_u>DEORXL-{-3yb+Ff6f$&pxj(vU-8_Iv-|Oz3`Idn*x{G{nvbkdYxaz<}-b9 z`0~K`OP043m^?enZwgF4lldTl3(S|W>nkw%OZa~}-^pLX{}apqi!=V87(c_@iNGxH z#1=<{`E!5A|I_-z_G zAOBB`uVvdCc#ipZ_=?KQZ-%@&DqC|0k}q%Xj}zT)8sa{l7Tl|B1Q2@&Cl7c0J?&>G)2t z{e%A}9&6`6{-1cFy-(u*iHq!g6aP<~W9K9OpE%w8HvB*FG|Mx^{}WHO_j~+5G4J#E zf8uiceh2?gJZ9cN_y5F2=Zx_DKXJbKy7+(M33h+N{}bb%;{S=stH%EmlfR7rC+2=< z_k$$H|I_u3Pl^90#)n=o=9s`aCv=nEMU>pOz1se;?Wl zZU5TyIf*x&G$8aRkG=g@g97KDL;mQ{z%^Dc*4_^Sm(}&<{ULCb`9$`95x9D$egAC! zpVp_$zNf(d6Bk|J0speiHtlc%=D^_qCoY?x?f##* z$i9ET{}Y#*FZ9QWmxtw-nNLLipSEw5`JVWH;uP~m@&CjV%y&Ct|JJ~T(^8`=PQNzr z@M$C5|5N{=_Im>VPw$W9VdMYB8UL?|hq(V2XZ$~L(d1#C|0f=guej*8&_1TBPxRxf z+XClVJz>kA51dum%l$vSpOPm?{+~G2=1=`!ahB~b^8dt@R-YUHPh5J)|I_ao@)ybf z6X)9ZI8W|)Fz}el9$x=f@3-S?db|H8#@{9XPn=O_{*3v5V&31${}Yd}`p@M5iTQp9 z|4)pchyN!|v-f%YKfO=G_ zahdt%uN+mMqxVv~NNaAVR8w2zApk6KaBr*AanxFhXF@I0O{}c231piN5Zoen+ z|HM-*Uvoy|t4VC{_krn;|EK;H_WJ|>PmG_4|0m|}arl4Qe>@-Y|Kg1QC!TypmivEk z#{Uzu{^b9O@w4&&#P+V_{$HH&{{q|hN%(&{zBR`9e`4|j@&Cl+1LFVbd@eCR5dTk1 zJz@MmakZVV_FiW zqjxg?6*#{jk^iUrU3qT8{}Y#F^>Y7DJSJ^``+wrmBa-V0;t$~e&3XPD_y6z*S}vR( znEJ2e|7}{o(0xFBF#JC;({H!>zwznu|HQQ8|B2=QnRDmWjQ=Ob$FqMYvAHyXbBB*`|4;p4{J%Kk z|A})_QlmfjSQVIj#6HF61*Tpq{-4&5JgJZ8uS;U;|Eit-_AN6YS z|Kd#kpBVoL|1Zw?e;U6dAB_CJIOG3`%j|gL|B3PO$o~_M8)H6{`G4Z^`MK`@iKpa^ zcK=UYYknU7pSWmrj{ARN{3iTAF+Sa||MSYQ{_xiIR|O{TF0=F1fwOZ*MZbHniSgO+ z|1>}H-KhT?XX^io@!`n-6O#|PdRsE%|7m~9{}baw;{S=MAB+DduE`$h{-3xaJI(#S zIOG3`@!jzM#Q0|9|B2au_CLu8UHV^ z?O*&qG5Z()PdsHzw)=nL8aqDte`5K6amN1>b3Ca38)y7KG3OippLoL9Joo>^C8P7b z{;#+wcXYIW_TAxn;`rhJ>H1>*|9$yAf${79+47!n|E$WkzYpEo#D$j6H)8O;p`HA{ zvHa*)u6O)DG1JHWlAmJEzj%MH|No0C zvy=V6(u`z3Z+u3wpVyr6!Q=C9&OhY`HqQ?vzcoHT@?zuMyk75w!F`k3n{#vDFKbY8 zz24^Bynl1wuQ?YEPR_Zcewv2e*Kl*?*ED3e{GM~|JC|@@cLf&|HSXU+UWkDnErjw zs%{j2Ve|X#Q&oZAt$#Lp;NO*j_dNShG_RnEcR%y<==7geg!Y%VAM*cJboTtg1J69< z{@+*a6aL@s=Mw&(nDx2r-10{8tL8Jlva2lc8|M2R-Li>4v3x7?|J46us|Sq#Cw|ZT zmz^(^H1>a}i~D{s`G4Y9cRdj8A5+peaC+Cq+V=Iicm3@AXx`<;fj6(793A;iQQ$MD zWk&ZO*TiR46-2v+7d5W>d)LNq-l@-BJh>#=wsvCRiV0a!&X%Iaz2myO?{{2>Bi#QJ zlP?y(K07wc$0J`X-i}X(|JS8xh5LXo{+}2>5dTknq~+<6|0h18-BIrUiSeDN|0~AV z+WWgZ0=MYY#r;3E_s__5|4*Dga+K%)iMw|@HoD=mZDIQ6zF+^&$$n$=dcenZZJ)Hg zCwENVe(Kf6_eXPo5}z;LPJPxmQ=c`?_+$8gT7T->;{S=shr|E-+i|PhZ*0}7mHU5c z$2TMYPfUIv{+}5C5dTk%e~AAlW_|JhG=J*Z;{U0g{e%A}ChzaZtF8(CmH(&d;Y&)d z4*gF)=GbW0b5{jE<=EqRe{B5vhUM;0_C3BE@0UsZ&3BgvCU4N*PXiy-ss-<_f!iN- zH1D^8Ie+Z^H!$^>@&B~`SGoTu-evWG|M>c(M)5n3-sS!u4j=yC zCr{n){-5}pgZ1wJiGO8zfVg_%FRk7${}z8{^?vXCx;*eFdvj^9ewvd*`fdKo3=#7 zQ4>FW@hbQKw7mN+T-X4-iSGZ2pIBAw{-37*WXn?b|HMD;dn~FP_M3+1{?@^L zzu)g}aQ{zy!=eT5|A|ZH&36A!e9Fk-?*EBTD(>X|pE!HbFwg&6Slhw#0~sH{{}Wf6 z&xZdeuCx3F{J+!c+q?e<WWr_pd$}mQVde{6DQvv3*~S|Mx+U_KCbd`};5cpSWs%s{4Q9a;vw6|0gDI z5dTli_!9n~xcHF&mw!(?_y1}v?*so&Txb5mzgp}JOr8z?pW5NHwa+(ve^kQnBOhk_ z3C|_*(!W35@WkS_p5Mp#_Sv^SmBeRcZx76PX5Cj$1jhHcdEa9VbKh;_{vPAu9nX3+ zi7#vWNMQ2+T5NwPF!h7+|1>@0?f8FU{6qXd@fqePeDcV>4R2Q_{Jh!bi(Xf8PhiHc z@c+~w#{Y{m{$HF|{BB#A9{&OVPxFWI|HO=!;{U}N|4)qHf&V9_|H}uj56t}V|HATZ zycPdXOg|Ev1wJqYZo2u z`F@-)__X;u#m|4+v+y=s8_e_?;vcr*T=xYX*Kk^iUbr+7v`#)rf8RcrZ1Hhvtq z(DD>*d^s?ANcW#op2YZnx_)WL{}b2P@x%WUPgR zD7fhGaDErgO!53bo$u63#Q)Rzh0lloCr+_E6#PH&P@5kAPn>DnkN+pmH-8lWPh4w^ z|0gcD<3awP*z-}${}bbD;{S=$Esv7?KXLZ_H243+O>3W;w{^65>$y3Dt zQ#;QS{68`CGruk{`^Uy)cj0$go zG1m|NpLnW0@A3b{9Dn>jajl(?_Mh5sk!eHH&t z%=ZrXf8vRjw~7BJt}`DH|4%&itVI1^G4)~b|HS3z+-AKCLaNB2Xv?@w*|1TI>ZZO3~+SYO`X@c*>F#peIo z`5&0~OZ-2z^SuZDpSao>|4&?D-z(t%i4VP>1Rg)Lzx#h`A2+4H`+wpwHGSOw6Vs0W zC!R2Ep!)OSGyb0#{|)~y&iH?E#{Uynn_ruG z*c)Me@b`|W`9X$i6`0jQTTu2 z8Rm21|A`l#GuHh-@ig-R@&Cl-=GVUURy&HvN#@dHyX`+MNhNrT+~)BQvKpIH81xZjQL z;rV~!3Av}b|0f=sJ}7CtE`MaQA3#1}d^``v|Lb?nV)p^b*E`U0dhUzgEp(p*J}hlU zVCv`M|EWLz9sZw~cKknaURt95uQ_<`|B=Up|0gEz4gXIp|4%IcPmJ$@|F`$6rSAX1 zH{Y=)iQhi3Hi=vPZCw)M|7m{sh4_DBd_nxbz-d|EG5L z&yW=xLpwec`G0E9ACn&SymC|1{u({f{Xgwbd>{NjF@8|D+%35pPo({=_nVk@{6DpG zeDVLp)#d}@|B3TQW<;AaE)DY^KPoF4`eqXsXXZqo&AlwNlc#pc4^3P9 zlaUjB)$5AD}{^qlh|0l+$!v7QF`{DnIt23>hyygFitIQ81|4&?= zF+9Tm6Vs0WC!Um(@c+d4YxsX+{5A6b#N^lE|A{LzM!Emj#2N1Y#Toxk%<}R7#H=6w zpP2S`Ki(S7SJv<0pWPOi`n2QwZVQax_N!e@jGuO4#qFUTKH)!`nCs#BwRePe@&WPx zw0yP~|1Zwu|B3M*$^VNp{-3Td`G0Z7|BEyJpYET&zc<_+?!Wk%w{*ED@Wkv9?*Hk2 zO&%crU!3v(#Q2}>X51IJJZnVs@L!uayIDP7eBk)=V(h5@oAHC={hM<^=J2HU<~%Na zXj1#wkwgC9xLH0R_xJevlv};>I9Ciy&KGQ+uh-nq8)x~c@#*vXCi{S+2K7v8&m7z< znFpSp#97VylLs50e{-gOe7wCm|5UzUbDyv|mlPKy&41166-m5y?YT+3YE^Q+-^TM6 zCABx_i&vhV)V^WqTz+pi-q6s=eYf)$pXvVJ@0NA+{J(Vz=ehqUF1dJ<`+wra_uuRO zpZJPrpLPFFyzS+eJ^xQk9w7OD;@4l@9}Uc|ZEW2u;U9i!zT6)!sY&98-RX6kbe;>U3tk3^b zfAQ84_kZd)?E3M4>bKuM;{H$l&0DXy|5LNx<)9@+iF^Li%)Q?;haYkOr`~e)CDGac zDNMX^pt*a$`)B4x15YhVjLA&;y_<@AMW;O-BFV@zkGD`-|T|KaaXo*@0T-Tko!M%-3G_H|5Gzh?#orhiG5eJO5CyQ zg{(&A-OhTVC^YNSGXHN~>*Y!B*Ql}kKQ(>{{}*rkU%c^uYJ3y(|I{rTH*x=`mj6>9 z-=MMkKXu3Mz1;t)>)Yqilr#5)>x)iq=JWqr|8|9YxsJBpaQywr@H@BGj9+7r*2)ZVZ{2sx;}0n{x9D6zp%gEKm4DX^?Tb~xGglkulzS# zQyTxL{ads>!~LJS&AA=i|E-v_)cs%AGf#K_r#{ObZ~ULSLCfau|J0Gq@5cYB@sjvI zH69QDr*7D=q5D7m{6>u$x&Ko)Z{FPfpSneh7ViJlt(rA=|EKHY^@{&fw?4Ur`#&|l z5&x&lGv5&Zr^ZL(|J2M=#Q*8>XWk)vNo?;{!jhoi#6{5)E^z4|EK=oaMJ(P_S5eF)Sub<==eYN zr!PJ4{!h1$^@8z#>O;>w>HbfB@kQ(0|EX8cTkZZ&kI&@N$^{Qo;x&KqITXmKDKlP?*E8YL8*Nt1`{!hJX>a6I%F@wX;+qUMy=)cDf z3jOGX>)rny8BpjR@wM&OyZ=)ky7n6Pf9l7tyds)>QvY!Ihp)UedZKQ>(7)Jtq5D7W z|H1P4?*G&;OsRJNr@m=Ysrx_muBjF7|I`QOR77=p_Dra6n_V6q?$IOkJ+q44|7rU# zW|z4CQ{O*ty!*d+AFz3U>bvGmbN{F3=gzrPqf@$f4%>IFndAOX`#-qtLic~_r>fl+Xt7Q;p_kA-QLK(U)kK=?*G*JbFKQ-r%@PE2IjsH{UnpZd`=bdnQ=3fo@;;qnpzj^h#H&goIR&Ru69^aoHdo476 z1plX>kDtK*shQ7&|Le1?q5D7neY5>-FVtlJwSjxR@@f6d<2)al^^sbA^K9r!^Nr0n z9uA#v-k@RoMCbzZV$A>3^-Z(wM{an!=F#c~KCh1+*8i!{oF6{);S-@bKfM0I$7;?? z)OX)kYV%%JRXm!~_&;sOW8weejsH_mGJnyw?ZKM;=On$~#H0RC&3qI5U%c^uYOeoZ zC*NIj-|h8$z8>Dt<`0DC{I{K-2tCRC-ORTjsH`Rw)3O-zj)*S)P;7w9{;CiUKIXM z&H2-dmRz6G{aaoa8ZU?c)8j?oIdxmg_9=C?rgW?Ou1e{5%B~DuZ1b45{Buia?*Gue zmxnGiPx|j+mxX4&*F(SCoYMF|-TquVAO8Mr8*0vKko11|wEpj2T+{ukx<2oZ^N)u= zUSD(jUr%yhM^Ej%rl!M3b=>>O|EXEuZp%NG)$|%$$G$IqUslng{AhXklF)rBdPb8E zE(~3#qMMz6njc#8|8#w)^=lAS?w%EXUfV%U-TytX>?EH**gvze&;Qfy8&%ZS=l|*c z3@Gm4{!jNe!@l3o`oDTUnBRf_Qy19zD*T_`ADmyp|LOf%KG)A5haPU{KkeAIG>6CQ}?#U|HT{sr|v(chx$UT|IBG`#<%_xtTuyPn|p8zF%zqPd#X!&F?b*r|v&%p!+{H>to{o)Y-P482(S) zYgUiwcaI-D6y8tf0r7uoUVr#Mb)n6t!~cc0^=R>b>H?bwhyPRK*YJO8{Mr{wuL#Zh zichrJ9GdkL@qfB~_&ofdn%^%&JIoJVvT9^Bxxvgsdi@mJ??Ze4hUWLv{|qWl=@sXV zIHcF#So1gdKfQiw{GWP)eV*a})Z^{;;Q!RD---WISDP=x|Ecjk_`i7L|J3*m{GZ-` z6YTha`G0CIkN;D%{xSY9w5>mi|5LO6sJ(wfGrt!9r|ryl#Q&-BWVU}w+n->Ow&NLX z`ye&G2>++%_W}M-&FjVX56wJU{GYa0EyN3M3XO-t|7knE&#pgo*&3Vo_t;CJOKl#T z`LNLC<_B%wTj&b&gZMvPUxE2S{GU44JfF>P44rR}m#vo?y3p1?w%Z@NY!&mE2cGD}r{hc3x5ode$Ju;5{GXcd&*1;mqwM{F|5N9g-(vos zy3mfFnE$6Pw(Dp9pPJ)C=KsYT|EJr}@g4q8&3sOK{6kN$_YeM0+xh+m^Z(T4_WHyB z#T);p##`e5)c8~UpIZJ;jUUGUspr`J!T-gZ`G0DBFaA$mX8wu!e`@C2;s4Y_?06mj zr!FzikN;B_&*{zkH&gG=3VXeFeD1{1W6Z<$-cUC*>v0dsX%HI!XP*b5C$1dn{!iC8 z-sT_T|I~%{d4~T}<2~_zY92rQpPJ8K{9kB0KE?mV8~>-zH;!NNe`@A^;{SAiIX=e! zsrkN%z5YXUe24$jcIL<7|J0-H_yzwLZ~HtAw}<)1c6<_=`Nz!v)Bc%r26KE9w)Zh_ zXFfYL^KbEg+Ml-Lr?8#l2mGJzfBv|x?*G(%C)s==^MAVk{65D2sqz2J|5J~$?;qg* z)cF&;yZ?(f{!e|b%~NLnpSrWn7i0dP8ZU$YQ;)Xeg$pj8m#N=Z9qjg9ma#DOxpw<* z`1|6}d>`$$`PJ!`GNR9HQx`!|EY`Z{fGZk^Zhvd zU%Z+Br!KPjXZSyLp7|a8pBn#z|BE;NPmk|tn{S8zQ{(%X|EC^R)ye%|yzzf(*8jx+ zsWZzvyZ=)&Ul0GM9#-Do{hvCsMZQozZ)bVP!!ZY3fse76qWd5Hzx2&W4 zKXsnX8?(QkGxhh(FuOhYKXs0+uZ;iG@vZ!yTK-Qxu(GrJKlLEPd(JUFaA%B55)he^X>aR_&+s&|NLp(bD{BT zPaJ$cH1qK`9RFfy_8&d=rO>QDeDeJ-hnD}-{iE@JYOa6jy|0D+M^EhS{!h1O%;c`_ z|I}mc-?#98x;%gX;s4@2rQ(<2`burSW9Pfy4P9)XzxY4x&)>iJzj!~p^uy51|9ti3 zk3yHs_P=LB^Y4S7E&nuh-s~aK*5^JC&+pKgL)`!A`R`%#`SE}1+^Tb;w!6OxU1)#b ze)soZhpw={&kh#;CiIk9wtlnuKfNC&%}M${b@{}B?*G)xBgFsd=h65-HR~Va|Kg4R zQ#0Qb|EFfYDgH0s_&+uCOY_?NPw0}P{!h1OWO2u+^O1jr_kU6Gc|QM7pC@^vJJ{#> zf5YcV{;;#%|LOBD&phDJN24tD$Uz-^{-1i(;8ah5uVDV)pXV%a?>8!=m-|0;b^kt5 z)^(G@_A%!7RzEp8H0!tG|Fl1z5C0e1t{?vw?}=42LgV#zte=_E_&-~-*L@)KnVA0< zZ`S{f_n!~W56%3hb3a;;(yafh{rP!jYf>8j7vGNmQ!_t`^?%jO3uOMEn)yr2|5N97 z?dtRY)OZT~U%c^uYA%oeQ*-rW{x9D6zt97^yZ=+;H}QY!e4F=&|5F$B?e6|h zJ=C6G{GS@%g#S}BUl0E`@6pBXD~Asq;{H!vG;C0`|D}y#|Iy}=29Mtqnt5Z){|oz@ zXS;ayrJ*O9x9Za9ve4sf{^N(Y)i$>e|EJ62hwy)D*0;s~shJOm|5M`&@qcQ3A^uNY zJfN5Rzj)*SLfia7{GYmXfO%!}e`-7<{x9D6KQ*@x|EI+@_-_m(Ehwbc- z|I_Q0#{Y%x*VFxxdZ#V|5NuH&^yI*^iP}5$Gq0K_xQPHUTb{+^y^RWoQ$3+`)AwdUHtMt zH{XxX&-ng$>v&goPwk3ssowDC=If=;`%CY1FPPpLy*j1bp7ieBE7kY)>7BNJk5u2E z?)`qQ)4gB%yui{l|F`!1r75@fq7@7OUwdPk|J%G~QOf@5+b>);+x_46lal`LeDi>R z>p3BDWN{Op2e@#~1owZJ9ct_zu+NgY?*G(cdCO&)NFF>i29tNc^9E{@br4eEy&M!z0P{f7PGA^^*HPHS+?Q|EK=sotNGJsXu+= z1^0jIPweM0|4;qZt1r0!)8p}l`4s%$lv|p*|NHRe=iUFQKYt_X|I{D8dBpvn`jdBF zcmJpU@~s!$|Eb@5{z>KIb-wO|MlP8+~@aA zDIMzmPd&A~(EXo!{=_lv|J19dO?3ZvY@4M2n_X7u{%`o(C%gY+-eHw6NpB z!&xos9uwWRwIET_x@F?`9iGjKY`z)(@2gi&b^mul^Lp<8)XkbTbN~14|FzWpAIa%>PrL*`&GqKlSPL8@d0} z8JYqKXtoy?U)Z8p0BoT+q(bL z^V_%SDenK&eVVj%|EF%yw66O<^$GQo^Z(S$N5ucBd41yl;?4X&-JX^$Te|;KvtBXt z|J3bTo#y^e&3wYXJ1-5}JK6o8cT8=!Yn}9e`g!f!oEmlb^~Uh?d$n!t{!iD(t{!f>`#nz9<|EYIwIX`Mrzi;Tr zH?DU7r|a7>J?a0{myD}+|EIom@g#5XbN{ElcE(uuf9kyxM!Nq~-!rGo{h#{b zWo7RF)c4NMkMMu$gZA(9le(W5`X2lDZ~ULO?^-iH+IIT6;r=|hZE5t|GdhO8cgx}^ zyKRTi4_~t~+S%@$(0|*1Ys%;Ak9YsV{oh}&Y~=I*9=iQ*_kZdIlc&4?Q;!(a&;6ge zUv9@}$336dbog6C_kQihp6C8g-F;3*H0^&ru9-Nlq0jTnoi*6jm;WeqiGAM||EKL0 z^M<+qQsy0XrDDgDxcUxv=Hc?kGF?LW-+$N#CBw}<~zvtASaPtE!% z_&+uOK8ycT_nq1=>UrubH8#V;yLOb| z3;(C)e98M|H8sobu5X`l4`*>crTFj9gvJ-(|FoUP|EbIDeCeh}Pt@GiB+an9s9gUPZetJ417M{GayEw|N)%KQ-sC@PF~f|EVi&ei!~v&3p^| zpSpbZfap(8UlW?`_&;rDz9s%I-uOQ?KOg@WZ~UJ+-@F+9FW&e+b(wiv{9nBH{J1gP zf7bWK|LO6;C*uF+eR)!f|Jyez>HiAMSK|LJ>7Mj|_#Ni|smGg7!2fl9;6(R-BbSVJ z|EKO$-qrn|x^-bk_kZfTgIf6fKV9EhgPOVjQ=gOB!u?>HUd+!T+i8 zFZe$-K4a&!!q7#_hDBH3K00*uqM^|xza162YC%?HJ}ETUkN?x>30@Qbr^ZX;|I`KM z?d<$}XwF~#HD^F*&OiNTL*LL@_IdWnbG<@mn;$d(6q@;Y_`h)dw%#rNPtE1=fAPlu z>He46=W+9|+J(oj(ALj8p<|oStY3@&)8n0E^L_At>Y?WKnE$8eXRw_=W&WS~oRZe= z|I}Tp+q?f$Gv9>yf8q6DzK{8TYR+FW|4*;?Y+Jv{er46@_0-em_u&8HjsH{2|EYV~ zd=vbin(fU0QxCTDQ}{nM?|-Dn!ubTC1@qg-~CAseZ)FbC)yZ=+O z-XZ=^U1alW@qg;xGyA#!)BCBfeO}@J)c8UCpPJ8C{GS^Cw)N1?LwbK!+ULW}CEG*u z`Hlb6{&*AopBlf6|5M|)&)IQNX#C2De_j!q^;YqJy8Q*KM%j8{(+}zWop0Xe`32RX z@kE<%E(~319t{7d*XKA}Zx;Wj*Y8-HCx`!2SFRfB{!fi}!vCr9Klnd&(elCOCyoo( z&pfXIKmPd{{X81~r~UD7_&*(QFhAG)RcQG?Z7(zrg#T0Hh46oBJdydG&|E+MPuq`P z|I=!&-}X;wJD_BynI8|~vuyhyHGTyDr!KSgWbuFMLi4P)e`tQc;QzFp-!J&T(Dr)5 z|EW2i!2hZ9&EMhw;*I}PSFRcE{!d-KZWOm?h`Mt9X!n2WQky@B|5Nk);{W1pw?A~n z>S6Bx!gl+4_&@a+Yy6+O%J#?qsi)ZMbI$v-Lr*$?gx%g{p)0MQ{@wb}W#)10@d?fM z6YBi5B{cr8^`>p1neWx3?hT9sf+D+6aS}X9w+`Uw7tIYe`;R;_&+u8XXgLK8~>-CX!A(%e`?lK#{a1~ zKF0s4OU%dO|I{2W;{VjlPsabLIX-KWb4;e*k7c%gI{r`1cKlzw@qg-U`@V(!cj%FJ z|L}j>K7Qp;_kU`9G5$}@`w#yYZ~ULy=SQ3Wi#PsH&G%98e`X zV*7lx-|wOMe7DcP&|JSAAB4`c<6}F12wh;F-HtC(8vhq=kG=o#fAPlu>G9|I7XPR1 zqwV`w_&;@}&AY|_Y5xjaFBJc$?M3G6@PBIN^)dfXjrYU<>HhP5FZ`cc{!cCcr)HiU z^Z(TO=Fjkd>hsLo;Q!P;XZOXUXX^Nc`?v6=*`bSO_jmuN?R{+hO#Gj^_td2SQ;!hs+HsWYwdf9j#;ZJGb4mj6@d*zq;~FC0%>eFy)iWo(Vl=!BF>q+CI^~&-9xkpM~wEbF!jSPW!U<^)RMew14SWq4B%;KfOK*%=_a1 z)Fns#pSs$zaXa7FJ`oH@87?Ef5Le2lF z3q~gA|LOB@)X+2B|EY%#>FEAXos*gB3Gfm4zsH8ocmIdaVE&)Fym!+7smppL{hu0t zf&Ys){!h*I1Kb zG(Hjkr~O%97XPQlC*l9pTp#{Vo!zs$`#&}7CFB3pte?pGzv}*7JG=i=<16rgYJ3L% zPt80&{GXcVV}I7#@OaUz7p%t%ui0$ty3lw|{GTq52gLuW@iW(dQQOS#!vASI>$l?n z)c7LS|5f9=j_@qadxF*%>n=H21{)T}>>|5M}D@PBI7GsXX@ zS??78r^Zj=|I~OV{GYngJRts0U11&#|EK2l%>2K2l>dl%>AF5^^Wm>YSxd% z|EXC&7XPQ_`NaRl8~>+fyJx8bB6dIqo``+3f zW6u}5)8YTrWtsim|An@Bhx7ivGraywZ9V2Xm){&34|rSaU7_)Y*#~Qz_tU32 zyTf+;2|_|EHG!8*$HE_kV21|HT{sr~P@oG5;@Yx7Q={|J2M2#Q&-D2KRCQ zrye{o)$66t|HBK$eMox$+z6veHm7f@hvV}*e);q+?w;!Xin^ux zLcDkU@_gRMJKgi8&kIanFZlm&vtE4s=l|UGrQhE4PWOTQzKUP}_`JN7-n494N?*Jz zb-v%)1+!ANU$k_7N^e@ZB&FA_O5MK3)(2+(-}PlpeE#3XOXj)%yZouf?*Etv$ojt> z>L&f)?B(;^|EZ@fn(6*e-D>?R_kZf%<_%c?SAEkRx4ZvSKl=Q0?*G(J**w6G7gdJ+ zpD=It(yJArKYiudXhzH0{`Q?$qvNNQhwbm$yuVxTD+~R>`)@=;|5Y0LlV85({!jPs zv-jR`|EK=;mv6ZL)8p}L^Ly_fUm6~tk8OTmUgy%pzTY=-5BQl~AM5|BKX~_5_kZd) zUwzj7pZbyK9*LgmSe&?LLsOskcfpnmlJozL_U-e>M4KNjN;K?~^nO>C4vEITQHi}0Ld^eDAA9Vv(eU91 z5=%BMb5D2NamTs;D|u##dqC!|;s4Yvn>O_If7KmMZSMY0%{)E)pZc`sC%gYsGj9$5 zx4GeB_kZ|1{GWQH9sl9~)O^0+|8)6|r?&L@f4aRH^_!=>U;3ZaB&E~m`JLXVZp!xb zPM`OezTPj7NBsTY=(yB*ehrU3CT06c$EVHo~&Pt|5NvCcZT~vb>^98 zy8lxTXx-ZVpPKoA_&+^gcuUs*RdfBU|Eq3qzLNQWYWY9)iS>{3`G0EGPsabLdHv!4 z)D2HL+2{Z1_B1jd%KE=*ZXfF|Kg4RQ=fgtDL(&CKd(dER__1QL(XX9 z{!ja7oYva?pZcuUr@Q~t^LeIi$N#DEhWI~qJ6oTd`G0EG2gd)YGwl0G_`k<$a^3%3 zW8dGv|Ed3Q{Z{vXZ~QUO{oj52cDny7nN#5Y@6Mgc`G4w{cHijp|7spAO!0qe=BeWU z;?4ZO_r5Aht`GdeGw%P?AKH5H_&@c>&pz$`FW%Tb^?T1JeEy&M{TB}V{6F>cHBY(! z)6c*3lJ)NYbo;MbxXk^Z`il8Wq7VCxOk@nmcTZO^^J4dZdOU_tTsMSFRUMy^ zQ2*kpz0v(A3=BQ>`WxK;Y5TP8H~RcP^|HM?-2bUp-nz^EpZdV=ozdI|eZuwKd*GJn z*@nGqd-rble|o%bzu^Y=f9iX8-r)XE{lK1`?*G(>cV6fIPo22w+UUI&UBmUif79hr z*HgNLerNk8_kY^|$o7le|EUjMzTEwv`uQ!Z-2dtRym9>{?*G*H+<2M$KlSqm_q+d7 z|Ly*R(Y(#SttDYgn)7S>Hog~{`F;35U0<2~`y~EPoiV*@^w#9J!~R)wdPP_K@0+3VeMENTiT_h`eiHwu=KLi7FSL0}{GS?+iT_jc_~ZY^J$#b;Kh96#|J2oU`$yG1 zZVJu$scj$J7`k$1U-y5yJ{te0F1PcQ_`i7L|J3*={9nBBe`@A=;Q!Rc=56qQq3!jJ z|5M|4@PBINtKt9Dc{bk*|EC^j+wp(u$#(ttKi&V*d3~cq=M6P?^htWZvibeo|EbGu zJ=*L3u&(C2Gm_q}%FYMl|32M(qR;=EX77)^yUwpUw@%XgO||vK@PF!F3v%55sauwG zaQ~<7mEYd|pSu0vlimO6`nwHG`agBQp{Ke3)9o3Y)587VuHAKfKH;dsc6RHShQu1j=bpRwWn!}@LbKfV9(fQ=uh2+jPx<9;X&U25wS z+PtyQ%wPQOl7i68|NP|TyxLweG!;!W^!dd4PxwDI>zCvI)T|GS|5LL*EdEc;`5pY9y2?Jk@qg-}vj#C= zsP^aE=YP9h?ZfRKYd#kLr^k=WPs4@9bPlc)jEA@PB&!bG{G%r`P+yv9_L>`9Hm$x{dAR{!iWA)_21HsR!8k zDCYmEnHPxvQ+G1Yi2qY}v-8*ZKlPwl1Kj_qhnO$L|EY8B@xlM8N7?Pi|EY)1>*xMY zJ#vAqe>L-P*p5H2^Pz|Iekn0;*tq_qp_#wL{6B5y@xlM8`Fz6vsq?4zh#srA?~vY) z{JzHjsrh}5|5I1k`kO=AZwp;*pEvkFT_3M+{9nBBf9m1p3-N#I9P>6;jhUE%)A&C%J`n$>uCmty{!cx5b*}qAHS^%`e`@9n;{Vh< zzW6^i$9wocHOGVaKQ+D&|EK2o3IC^No+kcJU1gsSw;g+XxPQZz;<@h$ox3vA?*9X! zIsW_2hDTHS$77!k%{)c>zDwvlyFYgP92y^(z45isydSELdnYv4kN?x{qw#-g=3nFg z;*I}Pmzsyg|EclBHg7Xrf2GZz{QJg#gl3)}{!jalvEP6AKfPWmZN51EPhDZ3fA~Lj znSK7@|I`C!cXj`#9IPU8*lud8V`&AQ)VcQh zxB0r6`g~ztB>qp$@iX)P)OaxbpDxeq3I7*w{GXcjgYkdrQFeRre`@!<=Ks{(U;LjM z|BL^Nck_+ep*jA<|7m;C?Bx7E^%(PTHXk``ue9}c@qgN0V#mAqKQ+$}{!h((V*H=( zKaKxW<7=4zr^eSX|4)ri!T+f%=I6NoQ|HVxpISC8Q@;B) ze`&tv|dn(wdR|Kg4RQ{w~ie`@|7!T+iGegyt6-aEd$KJ@U}gWdn>@!|2u|Ec-@ z3jQzN_&;@~c^~|rdeD@9KL1Z$Y=18>|4&_H--yx8u#f{p*gD#{cQ>o8h)T@RMWj%GB}h5SuT!;i0=jpJ(d< zv;MEP_psw#=KragpN;=h54Zb^|5MBVsad}l|EJ?=8vhq>*8kQ1_&)rf8t+=(`SFy- z|LOR4M0Gb`|5x3^-XE<0tL|fepV{|aLJzd}H~vq@k2L;Ion`ah@PFz|dw%eLYJ4&N zPhDb{Xa1jhoXro!|Eb5?{6PGlTK-RspJV=?x^jAk`#-h(pIZJ;U1;ZRk?_`{bnR--pKM;s3NhjsH{Q`|yA9#{a3u*z@kD+t(&WXPG+y92olVQV? z>;LNWFem#Q_kZf4S!bu5zr%;&|JI*2&;6g)|5f89nEw}V=Ksa}LGyp{#{a4De)vB% z-Uk1tuCV!1%>Ps4bMSv=`oj9a_`i7L|J1BciT{hY*_zPIqr(4bJKhBUr)C};{!h*N z!uUTmm&gC9@r;eSE(^Ceqkr!xw_||EK2m=RdkWbaB5P(WXx?3|(sT?!G+c;?Q^<{GWb4^Uv^qYCIJF zFW&e+HT(bZn+@Um=&M$33_WT{M)c92HiiB1ROfHn92#%fwAH1dnXh*LeW{KAvo)UG z53)c0PhB`7$NitWXyh>Wf9mnM`R@PXjsH`Z49#-?r)K?W{GXcjbn$=c%IrZt|4)rS z#Q((`{}*rkpBfK{|5Fdm?&tnbonz}O{!fi}!~ew_|EFgCVf>$7FO{}lFaA%>cKlzw z@qcRhKQ;dE%_%#>>x;|d|MdFj`tg72vG#t)|Eb5Bx5WRc@p1S+HIL7SFYU^zzj==P zI)A;6-5r|O^TYq$6ZU7mVez$lL-Tmy|8#rtrs)@@lk{xr+JuiqjYkJ|8^+8#c*cgpXJ^kyDo z+>4}lx(8%E?fCxboxVTs$N2vE?Rew6_)dgH<4KR>+(_c{h#{E`|frBr@r%XZ4!vk%f%`vg zpFb|o{og;ECH>#z@#XIShTYT5{onM-W8D9#XH6dK{!hJd))e=D>Lqih`}{w3ac)jj z|Hq<4%kmb9(G8xU`S1ooA*sacq?*G)RU&{PHHS+*J{ny?^qc0b_@55i6 zIlZ>=e{~+%otV~pfgi85Z`L9je_Cx1>fDv}>%(^Za<7wihwJNg&Kc3lrMp6(*Stw| z* z+I5J2y84>Xea||_{hyxSF0D>?|EE5+MLl2tSABBR6W#ym`Nv=4|I|GG_&+tit>2{D zZd5nv|Fr$Yh7H{RsT;L8+5MlI^>vy5r=Nf7Y0cgLsadZV|EHG!Q{(TL|EKPJ`YAsD zPc8qapLfpD`G4x3ZBBFlr~P}J(aQaw8t=#aKfS-?|J3bIKg0c>8b3L0@VLa^`;T_N z#`F8bC+4yLoa>&Cd9y{IRfXO#eSCE1=jN}EZhw0BcK3hkCwA{}|F>mUzWcw&Zoa|i z|EUk(w%h$*_5B6z|Gs+Rkk9{9e_@UPQ-A*aGd};1HF}x<$M$*uQhho1d_iXUsXu<<*$CUGe(TA{BK}+b&^>qB`Bq!+_vr24uy&REKlR%A>!P;( zM}^00-NFmq|LO4?H*TH#KRq5a>;I}JPe}Sd_3HDlb^oWnZSz*2|EIoj^(F5A)XSHw zb^oWHG=8T0KXqYga{XWR%C+0v|EYIhw!{6O`nIh}|EC^z_4V%m)U$8i@BUA{X5Rt# zf9lnHZ*%{rzWC-n?*G(VZo9+%pL+ML2cpv&_X>~4O?&sd|I_2Q`);L{!e}LwoBaq z>GHSSc)9z(&^K>)|EE6m*aPnW)PH{BN%wy`o_Kxx4etNCbx8WZ?VC15Gd}pb=IgBu ze4gKuDO244smmsfa{s69KIm-sf9g&n>%0HE=^ypo|BasA#r>a}`9k==f+_WVUJQ-@ zQ_KIUOKsi|{!h*KlktDLKD>&}2MOB;PCG9uz3r`<{$JN~pO-nihn??vGc-SM{?*V`=D{xc?aMXak4}0$&OiTq%S$P};=C6_GoS8{uRkA}`E(EOe75G6 zhwHl6<9x`ygAa%1e97%!)P&~z+rABlQu>Rkr)#QCPx`&;r9-3Y|2!EQ5BJW#Cqgqn zZ}jlTLo+{b{m@5ihVDJd=j~0f^RIosdpPt&JOBE}s~!q1|EK+F{GXch<@mpNmT0q!>u(xoS5`^_{g{S+!C7eJtvLW zpVHai?+wlRV)#E@AM1-9%-9{avz{6LPuI`-RQSKpc76%}r)K^H{!fj6Vg8@4pT_^G zS)U94r)E3;PtCvI-iKf}&v;s5mb`aI?H5&su&^G{)aeD#T!b_tEI{`V`LLbDz_ z{!c%Dl)b+2fBJkJWBwcer>?ZmfBc`C`LWFZQ;)RsCHCE|+WT+k$MJu9KA2~S|5J~c zF~HtWjl=VqZRhJ+-Pa&=zscR*|LOhAJRtm^n)Sr+e|o*-9QA)Y{&J#w(mu9c8T0?* zjsH{2|EUKao&TrqX6p&!|J1$g_T&H5gYEt?|4+^QMf{%{?}z_WkF?JRn-6kGuYcOk zH-^Rw+WE`StjC4_)BZI6PtEyp{9nBBe`=n8{GXcVAOENKBVGaj7jOKZI&Yf!81sK> zyhn>)Z3&GZ`NQR#LgPoathz8XpWg#NTOOMEUBAnj8+wqf*O`4_a=3j%&Hv;!stDVe zXZDZfd7)W9cKm}`VgCa2VU6qe4PCM>&yL4ChaS5o&*mMr4L!!Z*ne(o5uOix*#+C` zAJXdwf7dYom_vGfvEJ!lzW?Jhdc79ee6sV-{`eWa-b-zsnR%&a!u!wGM>c;In)P;9 z9(!|W{NL%vZVElxe3W^!XLLM8o4*UqJYn-pVSn1L|7rcaG3J5rf4V&0ivOwk{cqa` zsVnUFJ^oKUb5*YUKlQW~BiMhinxBXNi#PsHU3LB__kU{U*Wv%v_$K_Hnt6EmKQ)gJ z{!fiJ#Q*93<)82CGlwo-)@|EckV%>PrD*!P$4e`;<&{!g869t{7duC(KO z{GYnq9)ITlsqvZkKXsKIzu^DW%zMZG#T);p#;@T2^!OCm{CE6cX#4$(|BE;NPhBx9 z)BT^ia(0&cKQ+fM_&+_~qh=0r|EK2r75G0j$M5(*HS=}xf9m1(_XGY<&F#nksfU?= zYB+vHrhcDvsO}iGZni3=@qgOhZ$i7M-c1)|>Uek9T$?vkaA9bUAGcq8acI`Jez0sq zxIC{P{GWb)$+D#XQ;)abAKU+RY1q!^{jRFZL(jI)>sub)5_*=+FTJbDm7!T5{@}u^ zLRZZ1Yo7k<+P352XF6_6>E}0H6Po$hN4~l?rJ4Vy+c$dNK=*&@T>E|w{!h){SNK2m zNPGP8e`?l)#s9_op9^+{X5J+JPuuZf_&;^2z2EVF>SFsoBK}W3cxrO~pPsLQlRCQp zQ{(sWf9hQOz6t(M&HOUv|LOTHvEyI-pE`F^5BGmM9vNmn5&x&|H0B)lf9mtbc69%z z?qloo;{W1}|5In!_iN@YdLX5Hz5HNkj)(u<_TiMq|LO9~^TYqC<^R<9!j>OCo~h$2 z<_mr|<%vuk5BHkb-Tj}s@04Ed|J2L_#Q*8|mB#<6Iex|esquRFzj)*S;*I}P^Z4Wc z;*I}PMA^& z&Hq#L?-TexHNFu4r`G(xc;o-n+<*LEyzzf(d?fx)J>LA`z5o6+G~RAy@#mqLkB9%$ z^T&F;$GrYk=u&$<)IaN+(7fIUuKqT>KDa&jKfQkVeiHsK-uOQ?&kz1jjSs~CspbFF zcuo9YyzzhPG3FWZf9kQ*v)uowD<);Q|5LLbG5$|Ix}rz)(OdrrU0BvVIy~gxweRP` z&h~l!pV~J6m-ytr;qxG8SX=YmKh<_lyJ&V^l%>y$?Cdttn$5>#>GNmcfTaH${GJY_YWY7k_Xq!{W<6#6pRO;*ejff$Ju+jk`#&{a2>+*Mej)x(&Gq5`;*I}{ z_qrQu8-LTP()*N5l9|Ecj*_&?o0yd3^djUU7Rso9SI3vKJ4 z;{S9$y*Sh6otytt0>)y6CU3&<`MTjRoj)B1EX*At_%Bf`|*Feea!R2|EYO?@qcQbFZ`c+?7-ywKlQ{R zwtkWMKQ$f_|EI3V%JB7n)!cvlUwA(4`NjXK@s;>LHS_!Me`>s2k2h`#_m}mP@qc=K zjmb>T|5I0I4Rrsf=Jw$K;*I}P4^|EHG!Q!^hC|EI<$-ru#n{|EEr$x5s?ZxaTP8pE{opUmV{)Y*1?dAAZnoUwnU`4;k|(e165Z z|D6B(IS-ib_tJe}y5Gy`ndS|9r+P#_-{ZG0-S4Gu|5@*sKHo3R`=$H8(LGarVS1;} zC;Ykjf9XE3q_`mE{;gWMJf+vB`Ms5k=cH^;?^U*5Z~XCEzc{row0VE{zw3U}$o=1H zn;-b~X|;X9ibd}KPAqBU^8lBb4_y4@*u?bx4c-4Owx5sxQ!igI)BT@%$=qq~|J40g zE^z;+9`-f8I_!=KfFp#-Rt@|LO6dS^u}q`o=!*?~6wcxc^hXd)H0w|I{yDzdm~A#*)O{ z&6D2mp4HRb|EYJ*9_{|G;Q1!*|F(?DaQ~;Stg`hFuP9D@IJT+J`7en zH%)rK303a@)H5elNB=&rI8kSRv&0|QC9Q8;sw#V#|lHwnm;W%^q+#z z12g;j{6Ag(tW%DS#{I)?|CKF$ecvYL({}f-?V1tVJ6`TFOw_N>1sI&NKl=m}HH-T$36agqDKdX0~9|EF$a+ztPyZfE`t|F`3z z1@8ZtuZRCrw{OwJ{a?M4=DYtJ)VQ(xKXvxWC%gYscRjaLbnKsQPN;jF*CiS=wzj*p zX%{{H@y+4-&u)2Y^wY4~#uxT}?&jLt*SJ|Ur*myLJGo)X`>k(?^>PmRCC|EZa8hyPRKNAZ8^#`TW(`G4wTZT)KI|EU|E(#ZXvy4mTcx&PDcYko%S z=&A*mh5gSwy=CID2W#RVY`|y9dJoEjS|EFfX->=th3YXXVzxw%HzHY{* zus_ZEzq&k)|I_2!p4(&d|I|&-INAN5x=!Zt|)N- zr@nJ?(*LQyylHzhYEV@|mw#fHdBBXy&@bG%-~At^?uT=a&wlOh{qFz%dQZOlzu&!F z43*7&y zi>sIU{6F=T+wXV(r@njteeVC%dvCba=l`kKY}?`fPrc!$r2kVd+qvKUpL+3)d))u2 z$KSNe{hxZup8f9s)GKe^>;6x@e8(>Le|r5)IB=``KW(3M#{u_$>IFM*bpNOQ=k3_; z{!iQUY(63L|I}sn`osUJue)VW^m(h!p|_eJ?BBXm==HmIxc}4sTkg8e{h#{gyY6)V zr@rg4N8SIaKRx)c`#&8|JhtU(_kRV;8~FUcJ1^Vd{_pUo_1*tnGIfIcKlP}BPVWEI znZw$-|5HyZYT^E`-^ir@TRE+h`#&}3FYteNAFSv85C4JxQ_KIUHUCe|`7!*Tu8+q5 zX*=Kl$N%;1mGpn5_V4xhKXtBoG5nu;w0S=KpSr+&(ut#v)ZD$RuFvNyUOwFYpPKVm z_&;@-&Bww2sb|^xolpMoTuqx3lHPB|V)IYt|J0m6$N$9}|EK1B*sO=1skv^^Ny&MA z*7!d)=W8oUo~&u}mpbnG#w{NfHT>c6(9HLHVb^1!neT`H)Beocv43B$xprI~pKnLo zzrTm({HXo=d`jd0bosHi9u)ph&G}LMpL&dW1^i#U?fgNwzKJ$}%H|7%u9|ND9v|Hq zy42>Qbh_*I&=vD~L{p0ogywu6{!h1``78K8b@}Yx?*G&kwjMP8PtE+R)z|L{&3qF4 zpSI&m@PF~f|EW3ui~ox^{!fiRdHKQ{LNnj-r*pQ4X5L``H?B)<^M880SRWYwr)K@% z&!5{G_UHB9a^BUU%gx&rHN7hINb{i=yw05p~o(; z^SK{ws%i7tiSGTX=VwJ1{AokYbt99$iTQN@YH@K*n@5j#-$#FT+4|7jzg<79skys< z()Z#2W(`_d)8>}r5(~fkMONODQPEqwmxmr~|2{t8f0u;rIel<6Y{}wq`PPLUqWj)l z5W3H(Gu;2_=XV&`*!|yiy^{W~&!7hG|J0cyTDt!`2|L-YYqw@qRzPkR3iR@KJwgm>HV+m0wg1 z3SDLE&)Gb)(D=Uf5B3Y6M|9^yeZuD(pWkhwUZMH?#{cQ_PySC`Wc~sFr)K`7`GRo$ zH2zPYe|YYa9__;I$(ztQ%2{(pXwI+V|Fl2zD)4{$e5CPzYWDBnvRQb1a;J82|EK4Z z#{a3A2gv+CJ^#aOULgKYJ#bQ2_kVi5(EZ9|EK2nH~vrWM{YmPhDW^wchzrX6TXT0jsk5gw9`I z5M`dw>5x8;rmiW7e!rqk=<&-(MmPStdFavR@fZK{q(l0A%rl?V^QIr4QRDyYeBv{D zy%pQ-!T;&?j=#bG>3D_4|HT{s7jOKZn(NUue5N=Kray?eh-*SKArx|J2Ou!~dzP%o8#HFW&e+ zHS@~wfAKaSHdwbGpJd)ErSX5-j&EcBU%Z+Br^bij|J37c{bBr{I^TRA{x9CT3JBlPSwqoW6pn;jZ2iT~66!T;4eetpQbA}_wQHk9-`0lq7~Wh|I}s6Gu;2FN6yBVKNa>rbNK-G zf7;$*was5P|EFesTl}Az^{a1h`*!H+6*eEu{GV>m_*K3>c4++N%^SZ8jkkR8xbH%< ze)G#4zYkrtI>-H=u5X6T@5KM9XWIPFddL4abitZ@_kY?xa`_1Ne`@|d!2hZF`vCu^ z=JkpHQ;#;!hW}GD-wgk!#<%VGvU#Q+k9_k^x9w>ex(E+t{!iOEe#QT(^X+&S|EK2o z75}H^_Tc~Y`NH>;@PBHK=kb5qpLwI^`$O}7!vE>^%KxeHw)j6aKM(&GZ~UJckBI+M z7uo*!KQ;5BZN72%`4i_2W_|Y1eE$dkr~Uc+5C5lT{xSYfjqk$$srmhh|I_`&Z{q*d z98ci?)Whui3HU#CkjUHe)FT%TcmJo(T|CnLpN@xy*yD@;Q)k-ayXKqKnL7UA?*sgwI+O2j^je>(-$zr; z&tLKDi$c$_`MRHcd`Z|JKit0W#?TY&c=d4I&Ee;Hq$N#Cvo8QC##T);pX5KsgPtEHc|EK2o8vhq>{GXb?XITGNookN={!h*O3;(C) z_!|GG=KD|hKQ({<;Q!QP7U#JCQ&%k->i$p7&&U6%N7&zQ_&+trZ_NMG^T+pDnE$8d z^@jgb<5%&2YWx=dPtPy&EAfBo9P?hx|I_o$ylecQx~nzw|I{7F^>qKIW}fvgTi=(d z<6pk-GH&_(p|j27ee>$U(8KL`m-&C%A8*I}zj(9$ubO#p_&@zTn)!e6#{X%5zORG- z)A2C-GygB%%>Row{!hoR?2rFb7feeg2>JA6(Vm{hxZ+#Ln*j)cN-O;Q!PG=H>8zYP=i%FW&e+ z^`vQo-T$d4Ov!Nnr{?nbzj)*S)bfAv#{a4Dd-y*!UJn1KX1xUbU%c^u>M{2Di~oyv z_JJ=#SK9nn{GXoBqH&$v|Ea4cb#ecv*T*>fd-J)seiL3V_`lH|f1A?yKfS)V|M)+3 zxqUzL+pgb-{h8mlaPuEh`iD>d7@GTcVV^&TuC~u}{GYCG!puzff9f$)2D<-KmrU&E z{!h(%-}pZ@{_mD^{}npl<^kgW^!^@E)W!XuJ`Xa6o$3BhJ#=W>=!aiLS^B)m$~wdS zpSoxNEvFr|xI-1@V9C-hF%c{6BT) zo;}?Esk`>+?fy@V-@yOr_Te{}{}*rkpPKa)@qfBJ-Koi%ES=xQhcN$7+wmv(KQ;3f z@qfBL8vm!pw=n-tjgP_qsoDPRe=o?|kul5t63<_|_Ul9Ab?|@MA5Vk-i#Pr+-uS=$y+^`ZvF-?GZVd(Z>0g zhwUS69v=QrmoG9ehyROrb*C#*`tOHoyTH8KHDy<>zT(F{}*rO|EZZji2u{=p~p9~ z{f~a$(Eqr-wt2j_546i4-A?2G)ObStpL)ElAIj&fi)ObMrpZ3Q~;{W1}|5MBV#T)+@Z|480<^R<3e`@A?-gNV=VgE9F zfA#HlTS~M3ulDEtx47~^O5^`@e^~z<|995iGu;2-hw*>v;xx~f-sv8Y^~mF1gL$U$ zPG9er^_k<_nFky1bpMy$!~3Vs-%DTrH{JK~c@@8YJbS$Jx}~lsobLDV+wuK>&J$+# zOI?pP$}8w|?=E9_OZ9e|o2Tzw|CGD^9umlBJ7MdY#SVi$5M~ z)BN9xC8-`Tz0-Xlece-&5|dtPCx)rsuKOG8ki?~BCBfo?C68y%Fun-*Er^?*G)cJoS|OKlLlmKIQ&T{Ziry_kZfw5|6n5)9t63|EGTL z>HFRP>HgO|evkVe3ip4T`z8I~RP%pN+Ip9{ z-!^scH^b)r;s4ZArcQGIr=B-|j{86L;zg6(|EYWSXcs;9=iZ(^v&Yp#J?{+HF0jwSF$qd924DnZ&BzW=C|;F?KaPM|JU8T9R5$;v;K+h{~r2u zuKPdMqhpK8Ee3AA!_Gh~O@eCBK z-9NpV{}ON8QwUg6V#-q0QrC{@?f=OWgl450LqPfBNGh_n`Pd{GaY` z^9Bvw|EW)InDl?@Q<^k&|EI^h^~o*V|EZbJi2sW>{!cCcrn?Mr|p@ix&PC4=JVnI)V`#*JuGh4g=Q+H|CI@&vTb9g-H z_uknQ`ni^Uq9QA+d&k|3$|5JZ*=n3;2B?!x4i{!d+6wa)#Yx}bEG`#<%BiR;||sdwJ|r29Yh z9d|zH{!e}V_T>CO^|EV{>;I}R*tyr||EcBw)T{R1?*31`Zr|PsFBqz62HWHIOx2 ze(IjjYt;D_9o+xDyS<*z{~J54PxSCfAJ^3RsjhoJ{(Thx7jOKZy3FSDvHq{R+|JK1 z|4%*6=3|XJ>)p`fZT^_e2dS}hY(DP~e}(^3ld!ymYHM^=#^7(z7-+TFi7eiN>uS=A_5PJHu5$^xA|I{URKKO;h zHE$iR|;s4ak{ z3(cFD|I_uA%N4|u_&;^2c|ZK0n)!|=+5A6snVs*$ z|EZa;hW}G*{-2uLkN=A|{!h*83;(CCwDk$`e`@9t;{VjFCyf77=h-|9{GS@nwRpv~ zq45oOw7w>#@qgN%?f5@6KOg_6W_}9(FW&gS&~|G z_`j{YPVo6=%+J98o!TJj|3=%-!~dz}|AucnF2Q`iGMi6{|6BF1W8MFaT$=0tPuKuE0;{VimQ~aNLl&zPH|5F#*`F8xDn)#pjKQ-se@qh8g|EYPs;{VjcZM{PLpFTfE z*?boKpL&A5KJkC*Dtmw6|I~x+{rUWF`-aZ2_4Stgqj&gxt*5p)I+A*`qbwC^!PA8h53K#jLGM^|5J1R691>?pSJ%Fjo;hz<8djC|I_P-^`G&7 z@y7q@^@jJu|HT{sr|xg(WAT4#)*r+FshR)D{6F;C@qc=M;xqAo>a3|r|EC^k z^Gxu6>K-Kg0j&^Nhy-squc7 zT=`w-Qu}@0a{UL-==E4?$1C_h9pBLSKQ+Jq@qcQ5|KtDE{C>y(sX3m&|EV?qPmRyR z|EWhW?$7?A3zucs-`^3&$&bHAFSql@=KplOmh1;YGY<;?r|pG{-3x}!Uoz1BpSIKZ zKQ%ue|EJDhV)JUu|Ec*r#Q&-BAoxGsKKv5?FW&e+HU8+LS&fG1_>VSU6&eqP|I_|7 z{!d+Kz6JlME;8SO|5MBV#T);p=6DkS7w^xHTNWCBhyT-d8vm!BV6RX7pPG5gdB<+6 zZJU=jdBgV5%nQW-X@C6REAQv=s@TyzCU9APmfQzegA~{f9lee$@zcr#{a4F z?e;MLFW&gS&^CV&{}*rkpStAyA?C5(4_&@G+x*ohwQctw|EK#?ZjJv_%m2lj`G4vu z<_YnC>KPXdcmJmzyKc1mKlQlv`R@PJ)7KTa|5Hz}^`Y&*Gu6}V`#JbOHNTJT^_Hpo zS7GzZu58~lbd|lH@qgOR-vjtRbsqDp&Ht(KNccZ>sU5H5|I}O_|EK2tfdA9)Upz7X zFW&e+?ay}npPKoO_&?nr=94o2PtE%s|EI_r>skYJUIW|8#vL&FA6&)HyS{yZ=)Ux4&QTf9ir6 zN&gpb{GS?+|DVy*L*otce|o$}&+Fsapg>e!6XGrjCF3 z`-Ay^YWy4iPtE$!_&**0RGH_Sd&$~N{l2NT=L`R*o?*xH_&@bjTR$BCr_1yAA^uN| z|C_&UQ|O5{Px7JPZBA*MKOTCv{XVn#*2FiSA^Tk-&Zr0O~>+{Hadqea3Ea|a7G~XX;m3eEpe%3R_|LOVU?_d01yzzf( z=9RJjubO#g_&+^g93SET^!(EJKQ;3K@qg-(cD&2_ziQ_1;s12}%ltk3pPKc3@qg-E zo7aZ_Q{(OMfAPlushQt~|I^Pawt08>KXvZpem?(C`_uS89Us&9KQ%uO|EJdcKOMhn z{+~K;axeFPYUYdM|J3+5{GYne{{F!Kg|_4I&F?;!spHELwtg}GPtE$w_&;@Cb(d)R z8!v?(I<9kcU%OXAkDT1yj#rO_E|}EM{hxjwjsH{g_~HNJjsH_KKacr;@n-&CyzzhP zG4}l={GXcjfm#1ojfcbk#T)+@Z~ULS%I00-|I}m5H{<`*lWl%J{!cy89$);Q8vj@K zUtfkUnQ)%X`~Nz0kP-3x!0()d5U-dLXj|EK-& zjQBrw)r>(A{x7uMKm1?3>sDFJICnD*fw^;r%`$_iUT*`oE!bZ2sRDcl;DOGxKzt_ZnsC^PykAPSF!x zj|n|szCJ=J_lX#C$_2Tu*1)vI%K-mGaU&HTT24$N{-$o}|0 zbzYCo?*G)ix+nc#yzRfk{>&>f%aYRgKixk31^zGI_&+sX0{^GR<1znF-K(qlW}E+~ z?$f=8`#<&I9=+WE>Gsk1KQ$f@|EHG!)8*-o1*^jK)A&Da$CKdy)T{@L|I_u!|EcBw z)Mb6TyZ=*{nxDk~O>8kU>Hm87cK;V|{Gayc=i&d<%tOTgsf+CL_&;?)&z=$fPmQl( z{-2uL%lyC4=6}wuzbQ2H)n43N+xV%ey*7vKcsl%_9uIsV{!h*Nrue^j2dP>f4_kU`9 zAO0`i%>PrD4$pD_7jOKZ9^bJ!w!V=0KegunX@71%{x9D6KXsMO)5HI%@tOEP^?37_ z_&+uGXWNUl&Et38xEsTE`sF{?c3#$C_kX&4;jnD?f8q9KCH-H#@qg-~p#$CjsaX#h z|EC_8nc@B~-mL$tuC(jN|HT{sr^X)+>a#1nUzmS~|I_;gzlQ%)bl|J1x6@PF}U{+}A}$NWDv-jDfzx;^E+`}q7nbwwZh{&MT>uRq-{rhCJ5|CfGy)93%C&kG#b^Z(rg z;`igXr?5QL|IJ-IKV>`f`QrPpSeUy0@6v@cQ?@T#G%KZ-+xorn%d;K-x2JK^|1GoY z`{i+|{nd;KiEGw2^!b42+j_%a-9J7w>jUHeZt0)&f9n>_asQ{j$Zl``?lECIo)G`H z{nq;K{}$T%!T3LQm2JoW>GD(7t#JRRo_ocm?*G&q5A1jUr@rBlgVA>nl_xfR+rYiz ztzeqyKfE9F|J2hajC22YdFQ16n>A%pbhfQ0yx_y8cKmoaYy6bS(WW`Yp{LB8 z5&gzIowhHwc|?ilixR6BHcR}z!?Rf>_WKO~mwlwU`@aEpefYob4U+zE(T&^P|EVv0 zTNH+;{H$l>fz_38UHK{mw)Zq7otIV1&RDgC%gCi)iY1H|5HC@zO&1d`C0Tk4a3v8e{7J{d^Cv&)(VpIm!8XPR_~m+`H3uX7&#EG4Id!xuIv}rALpA zZ0y=0U8Bb*Y){laI^VtD1REI0`oHSVHn0%?r#`N08~1-|d=&Hl)Pwt-?fy@F(kb12 z{@=Y-3*8&GKBk5HKlLfCj&lE}KBH}G_kZe>%(LPD)ZJUQa{m{)d9$dZ^p>!_o6YmP zZU2_gc)d@1Gz*`NE-FH%p!W*RIKY!2e%2Ss%FPX{V>WADnhdkCblR zvTaH?^@I35{NKD;%iRAR-LakfzvB-sasNl-|Gxd#BKMBW11$U1wV^wA?(Fmbw7rYX zYwWRab9g+ub?fH-Pmf>kPF>yqse5+l;`9I1r*>)O^Z(Q*v`^0eQ?s5h{!e}4amo3A zYWY9io)b>$>i$pL@qYL}HS6;-|4;kl_n7||Z|480@qzfic;o-#&HTT3GyhNB!{!O% z|Md9c3z`3?9&~Eb|Eas%I7s{-GwtwyojNu5`G4w7n^wF3Q$Kpc)zP)-RSDL>t()C! zY{QOQ-T$fY-gblgKlMxdA94RTe8yz=e;*&(=l<`kJ9FIseg0B%{-652=acLIs()hM zkNJPHpMM+dM)1pZezA_qqSmp-2I>W;#Kq9|EUYJ?B4^<{i5OgwXJ;~;EB22-T$da%pL0fPn|P2Gx~nP z#|^U!lin|Pp3T2A|EJEGXa7F`mt!RC2{E}w1df0+N%{``9&{!h(( zjQUwW3Hx(?8vm!uJeeOpMXN*aDKN|n1=KKi$PhDs8^*(;()rM|+k9OaO$9ret z4^tZdr|o#a8-My@Lz~V?&xZ$Wv*Cr%b#{Ja)2Yv=^s}80HN3y&D4*BI`L-4N8bag! zdQUqT8Xxv$^8=yrVfa7&e3k8g!X?i%ym~~^_f^~ZJp1?W(5wfH{|npA8`{60H{5(_ z3!mpU#k`>X`+8{3_uId}hn`}Or~UhU=z8;e_V4$hng4_T3zu(=|5M|^@PBH&82(Sq z`8ekPsaekp|EFet2mVi8Vb_oUQ!~E|{}*rkpPJ_f{!i`a|IGiX@oD%!HU5qHe`?Oh z;Q!Q|-@*UI8~>-~d=CCkJ;k0+_&;^c;&k_a>U8rC_&;@qogc;jsq^jkjsH^@*m}$O zKXvU=TYuU7pPKb^@qcR0@8SRAjsH_KUjqN9X1)dfPtEyJ{GXmL^qH$JZYW>b+~?;_ zUYr)aJo3VZPk(i!`#yf(gKpgrn)6-%`fzQ-PfC*BkM;HNf9lL-6Wsr)`%fL}{!iVj zKI#9|$7G)5{!iC8FujZWzs|Fo`TW8DBRjeOoBUZb_kVpdI=TPT?HxAxMEm#sISp5S z-Q4}+sDcyS|EVX~dT97R-QV6euLA$4$D@y}M}_~>>#wk`zxzLRrJa9Z{-0X&|I{PR z2jc(K+4Bat|5Fz(AL;&2ooBC4{9nBBe`?OZ!0EO)SM5+|EV*kC;eZ%*EH-5+ege8S1<15&x%7 zn`QGdZT(+09+LHc)uZhE8|(k7S^tdnf7SW6-W>i<&G~NppSsMBU#^*0c2MspoIfA= z)a1|w=2!85+CFUl0QZ0D^riNF?>RjW>iwzG)+;{wvy(!X+q|S#sym0ySTxZ6pZ1?< z^U&~rYWxiTPhGw`>HqY6W4;;wPscmVH^cv_@m}~pb**_o{GXb?_pJY`<0;l-G_MyL zA80-=rOnsv*Zw)ld3XDDdAa7>_)pDt{GaxpWbbFp|5LNxG5$}Tlf3@WS?8p?|I_wt zd;h@ysS9jAAO25W=-%*=(D)*Id`9c`;Pdc*YWcr-7p!PDM#qErDEwc%@qcPA?~B47 zp)2h6;{SActbd9BQ?q_*FY|wD=07t3PtCkQ^F!hCiq>RDEnCh_Y5bq|XZ`2}U!Rw< zyThvxNy|I_1BV}Ea%|EK2XS^rnf z{6^OQRdfHD|EK2nX|^o%JoA4m?roEy+dIcTKj8n=tY`efrVbhU`^fEoJEL>xf>l}W z|Fl1!7w~^-<|o>G+^~PCJ-=Fw3Hs7HY#+veSe|oo6(^wY`$UrqnV-k{DJ=q*Kdvgi}yvp znUvDk+?5*|Pk7tRg3x%wyG|(%&G9V$PnXB%7yMsn^LNbuQ%|zL7x+Ilo{#x|@y7qD z`TN5BKRv!B=Iil)YUXh>|4*H7&ky{cn)TZ8e`<~wng6He^9TM<$2)xf!2hW^p2z>G z`Fw@{)A5h|pZ?x3zZL(do@d8j_&@a=yS;7mE($%>j{o1=b8+bD_V{l9=Ov-}do#D< z(v-H(AE9U3?Z^M=_RO;DyYg>WhOW2cL;Rm^KYiSTo5S`J+kg7e*M`PN-ZSI6(0m@m z|LNy_zODH`J$~|k@y7qD`S%3;pPJ8$_&>G$pIZJ;*GJ?3)a;M{Q}cNf|EK2rSNK1* z&nL9`f9ia@zxY2j+wp(uY=Z= z{xtqi$HyEW;{W1}|5J1P%KX3h@hkKH)cNKgS^rmEX!EP_e`>yOg#S}>Jf6PsxeOg| zay*XzQ;)XC8~>*+vCp6QKXsWMzvBPYB{Rpk|5F#w814Q~&HWws%4=bN9#8zAZV&zq z|EJEk&$IYHHJ?}Te`-F@;Q!R+_IVipr>;J{{;#^&{yh)>rKHg31y-`wwh5gH$PR*zqY z=L0=p{clpb{{7#D=NIz;@qc>0asTmuYVJS&Pp$cX@y7qDc|5NF@-LzBgx%A>3C-{K zjvK!XJ+8cO)a!SD4P8;%FM2HNZz+xc)9YhG`2hESdc9{B_HzHH&Y#%R{hxaLm{Z*U zsSDG3xc`gy#~&S$sm3ed|Jt^h=N^#8|Eci}_`i7L|7=ZP_kR`U+wgztQuA`m|5LNx zBJ2OEnfGT_B{cH_@qh8{_&;4A-U0uo#uwuM)D!#kasL-@{GS?Mi2qY_d$xVLELA;Q!S4OZ=aj`-lHi zGk*;Kr!F_|ga1?G`S5>gyx+fHN^Sg~9zWK5#{a4DgYRv;Jp4Spyvr4#@qg|1HZ~sa zzVs`@cDx(@PnTC}J`4Y+WW7_p&^H@PBIVAO26xJibm} zH8%4TAHHCF%J%$@J3`C1-2cTJ z|EK-&y{!MM?Y!Rce`@)^2WHN6|Hu7j{$IS~K8xp5yqo&Hrp@KW_iy_1O}GEAZt4Li zjA^ny@8}^Z*H=1x(0}cwez0jbop0FG`|?-gQ!ej+bkp^Vo31z9 zw43hF-^2Lz)s~m0^r~e`Qu@4Q3sZW{qEz44)c-a0e$3;GU*FPYbM5$VTB7G4+PZI( z|NEr6t4mb1v26n1Vj31cvcJ!a>YeF+G5dSy!k~Tgc zaOJAx`oHRPme2R~f7R2L&T{{!p1y2$bl*=Z!sV5%Ul}bpsj(N`xH;-MzdUR|Z}%Se zf4V(4A2{g#PyOotCzJl~@a=!;=|_|P?{FV@?4IbgTS^nU|2JQ~(fywupH1i1yZ=+y zi$pt z!o|y?U1#PcR(;&WZ$|%PqSej7O=k>KWUl@OVw>{DpRQ@mX z0DGU2>iyDsoSm}&iLH)FX*^>5^6-H8zvTm#y8mO|AM^jRuU_o_uf46ujQ^YVqlNDO z+I4Q@{!iVpYrE+4qHDtACI6@U-?eL3_kZdhos<4g%{)ft|EW72mt6l>-O|>VUjNFK zVSCFiZQTE9d;1eQ`TRdM{%>-#E5iPGP}cv|cINTn|I|HC>=qrH+1S0UYxZ6mw)Zm+ zxV>Xz;{)-3y8kr(PtE1y|Kg4RQ=fVADenLD_|o`4b-&{~`20V0H{+rINV_;}A9qTp zsKd^SLN{!^HhM3;I`P5qiSGTL+i`>YKlP#Q*Sr5yKfLWm_kZel4n5`mZ~3%I?*D%N z`~mlWhjvX)&i}JMxUwvv?H}8E?BA^@P3eKlOG1D8d_%NwS#ju}zx;f(XGu}$4{UxQ z{!f>;{fbMXi$~;#+rNCxy6DY6<|J6N7w=eHSsk7A_2keMMH%k@w7sgtz7J%x5!H89 z<+}gF{Neu+%V)d)Q~!AB0{4H~|BVH+-T$fYo`2c4Q_tSL+x?$<;oiOO|I|0!agX~y^<`VOx&KqIv-yLp|Eu1({m$sx z6MH7~`&)ZQ(*LP%Zg|f9pZcAB2i*Uu@7{b}bla(CHeTL^7e#+Qtw-o{SFCjZcTa6= zp9gs9ilqNjS7ncM|5x{NEBAjL@;bWzQx9G;#QmSTXz>L1f6r}i>GS^Rwc|f*=y!V3 z`;{#i=l)NfKQrC^pE_^Wz-ay%?}hz~ZNAXV7v2di|EK-=_j@}(*zox^NBev~&j0@D z(>EJ#`u-^QeDv@;UT>H@=O~}QSGR0z^w5OYQu^%Q{V+7XYS*=|gl7K_HoVmE*l%07 z-(!8=>ra0%beWx>$@$^)q1pe)rO%}_{!c&8`3d}=n#;rgsqujLKQ-s0zx;S#!`zA% zKF^Q&f%rc)-tU@?Pc^*#VRQF=bcPkC*g#Qa| z=a2Az>MA>bhW}GDpA!G4=JqlFPn~663je1bXXiWdf9hO2pN9Wa7npDQ)cl{id`WWt zpPKuN|5I~53I7*w{GXcjtMGsEt{HS$_@$h_w~D;Ulkrt&i7pQdU@z{n-B5raiyV$&bE1GHvdmQ z&*R7ZKQ;4F@PF#*wq7CrPtANN{GYnWo-g=6^+fZf_&;@y`BMC!dYZkT;Q!Qh_Iktr zsd;{$pEWFWhIv2ypWZ*m&+YI2Po2BO=0&{FFKp-hCjL+FzxYr5pPKn*i+7yaxW9Rt zslPrwrSX5deAXw$|EZZLhW}GfUOvkGpBfK@|5GzRjQM}Me?0%0|EC^5)8=j1`oHR4 z=KJt}>b`dV%VsHr-`@nA$ASOT^JB7|ufzZ8`Gb$c|EVX~`8DSM>G?L?=5;XtPd#jE ze_#Js&HA^@|BE;C|3cgI5C5kgWApTw|JT^V-T&$N&-q3CpW5fS*!({=&u9Ffn)9E` z|5J~#^{w%LYSt&l|HT{s7jNeO#T);p=KeGPPp?;hJk0;a8~>+Hn?BI}pPJj-{g_P$ z^?t$UJ!ww5`#&{ak@Ogle` z|I_Uwj!J3#pZ1?&-VXn#{ioY}QT(48Uy1+I-^+a4j{j4$zVgrhc5LY4<;nGb z_46fm`|*F;zkE%m`#*J=J>NQiacbD^kB9j`ZO4b=|Kg4R)8*HhPsIPJYwY!c|5Nk) z!vCr9gZMvnjlDnM|J2ME$N#DEwD`Yxw>X&b9Sf`}C*{j~DCnrhQtU(i3i-7Ml6F_&+_q zdG>uJ{GXcdKjHt>)%N({|J2NP#s8`K{s;a~&G9?_Pscwr{!gv>e`@BN;{SBK!}|gA z|8#tVkHr6}r`YE={9nBBe`>xzhyPPo+I&F#pPJ8q_`i7L|J2j$`yTfBB&F^1OX#|l z+0lpU-bCx8E2ZAC6zI``Zsf^LXI@!sBb7 z&+&ip#{a4Ld&&GiHJ^W(|EKHY@x=eBxqSSen$Oetzj)*S)OOnJ0(;Q?vdu{x7uo zH2j|$Ux@!xm)m?k=Krb7Y`tXW|EZa0i2sZC)yKaPn%j^6)9o#&AK?B^&3s4vpE}1L zfBc`C#|!_bF1P!~{697R4*#dFnlswx|EbGnXS)AWm(I$F&Z+w_+&;eV`|Lv>g~tCi zKk}1UkBkZ{ewNa=?)@}$#T@(o>_0vWU1(meZ_yW_OX`P3t9SoArSX5dJ>0*6`M*kO z{GXm5xi&vC?d{)&W_@M*{#IzbUhamkLgV?$e)5OLw)|yg?kH}OrkEq!V%`)}=hkwBTz4yf&_kcA1FW$4Rn-#jqJP`iR z%%6Ke8vm!p$C*`0Y5bqId6CoMcMy1KXmcne(wKt{RIP({!fh`Wd5IebiY16 z|4)stnECY5aC!27x<1YSi#PsHoi$*X`#<&gLAKuNc`L*A`~gFwXLqj(T`+K1bmhsb zGJpHpO!r3PM%cXl@vBq%U-Q?5o;b{oKdxPy(#s!T7n*rn_kXZHG@gg~f4Y499qa$9 zOUxhP|8#rtF8Dt+>v!V+;*I}Pvp@b%&3d5tKQ$f+|EI?Du>P+eZyNun?aa@^|EbH( zqv8M5ct8A~ex7-3_&;^-m|^b!v_C!!{}jvnOp%>B>hNoAqe_FZ-IXoxbja#xBns<^E5%hsOVfHt&c3i#PsH zT{&)?`#*JArv3Yz`9HP%pPKb_@qcQr5C5kwvGr~7e`@ASGXGDHN13gkjsH{g`^W#q zoB4lgJXFI4Tf*hxJ@J3KeEB~$>-*yWLLZ+0r!F!N$oxNbh51O<|BW~PPmPac{$ITD zf9j%)EMNauou8iJ{!gzL{3re|-uOSY{9nBBf9lfoVbO2*G&Zk~%ZBd^+cVPBqBCA? zY}O+_RJSW^Xa3^UKQ?wv`WW|ry8QgiH1~gMUJv*`-5)$2{!iO!{GXcVbK9wRhISwO zbz?X6dTft-i>i#&d43h6Q`h@#>H&GZ#ecr(i?Shyr!Oy_2uK&-*o%`YtOANOS!y@&P`qa zx9R%5%NNc{*?-M~)LyqJbsk_-A4uc>_6|$>Kl;#DQ$wG#cy=^)SYt0*G&?HUQlB_+ z_c2KyX!HNB|Ewr%ft4vZMQ@pd{P#A&&}6I zc`eGr?cI69=IE-zvd}kQveNyZ?%&MfEcbtUd}?jIKGy$L&!`yV{_o8%+PeQ+P+sKz zuVz&{pZB-8D(U~!Q!C5e|NW|Es{d2t|I+G960M(XpY(q9HSYh^%X#AhL(&qW$|32H*(f!}DIrF1;A1Y2XFX-g+{vNse-l+T2C5b0CcXsdh z=ralTf9h9$^j>sj?~=p^Ba;5^E%Sa~EhrBC^1g#n(Y-~XpWXjV^w@6-LmxQ!Y_xYo zLAd-^Z9drV*5-$P|IL@(|LOYv`1(uk|I{Cu&&2=f`uE&b@pqeG?*5xYA8YFy z=XGuDMTyH%U!(ZIK^ z2-~|I(>&TVvawI^*53V}uK&2>j&uK~KK}UR`oHSaj!(}2Q=fjqiSGZ@eNH;X{a?KC zfARkL`b{Z~|I_2s$JX=3|Ec?$2gLuWdz^G~w4!xm`|UCRr^owj^OdastL}e%C-;Bq zh2w@rCycI1+%SBCd%qv<`hojD^?^HXcmJn;!sh8sO0Nw2|Hzv4f3^Kvdp+l@tw`KA zWup7P&urf6rq$)4Keu^*_&;sO_u>E4pS_TX@PF#hUwF>_pZcfIKI8sRz2nh`-2bUd zX3uc{r`uCrUf}-k^S_RF|5sI2?EX)^rgFUdKlQ~k3f=#yf4q8?`@fgp8t4A+KTkdB z{!jhRQ%^jNml56v#X-j?~M)pV0B(p^g(9mU8|QzXMLOzdiUCMqyPMD zOz4}IpBKIV`RLGF*Iw-YPq%O5CD*zCQ(u177WaSZ^*7z>{x9ASwHTRDFW#1%|EFGl zM{@q3x@^Zz_kZe&U3a+uQ(tE5?=CoIXt=yh=KY>)J0$eF-FNx?Kka|M{e8jzspsFd z*ZrS*`u1Hu|4%)2SJMBf=im2$`#<%)Hs7#cx4z->cHX|*{hzk4-?G*HpZX%Zz4$-< zzE8!Mr;6f9f00Tju`nrF&Yr|J%G_na}@I zPbnDd{%=H=r2i`@Im7**dZzt*)$gDES;GSxTl#vxlNV-17wq|{q4$cTlk34P9`F87 zjbFPtEy}7g|2vu<`b0KL2c%`5XM7dZwL!$N#B0UylD%Pqp)R_&+u4ZQ=iP z`857d&G{z$pPKcV@PBGQ-)#O*&EtXp)BR)K7yeIOX!FYOe`?MTG5=3pXU`w}pBg`i z|BE;4|Ejq?_&+tb_se^?hTB8emfjv({!jbk5AlC$d>{T#jZek@#T);pX8l+EpPKn1 z_`lFLzXAUjZ~UK{`Gw5?Q|B#8cmJnmz6btK&G|(9U%c^uYWBZ&>!soM%e=>S&tBZn zvSZTwRonT>hyJj!q4Sm_eBR&4#Y3V#-7aXj?8v0=8)xhF-L&?+&@;}>cK@gC%$vji zsqHbe0jp`7!er{3t`J>a5{!h23ZPu~TuzB;t?HxL+7=quX?!6Pr?6%HlK(8Q{(UOe`PsK`osUloB4lg=F#B)^!~)W8vLJn^g{D{=Kr*R z#^NmZf9jgWHjmEypSo_T`FZny`g!IBG5=4^dW+2eQ8qdf2ziQqO@qfDgY=82#wqx}8;Q@dDSohGZ=X~ncGeXzf<=gzz(9GkydeO+x z_`gJ1cIe60-=-IZo?!2f=7&OOo98hP6nc_*N&KH~UygY-{GXcjqw#-go?rOCc;o-n z#WsHq|EDf7e`n8^aD6SsuTPJULeI3n zj}vbFEcA4{ztfKSWoUfjc^iKhn&0=$-~1^we}C|QdVJ^wU;m@A?e~%OWRwxMTjT%K z_(A+%ylw5*(52=F@qgM*+w(0$&$q0V>F)p3nJet|Wd2WGVe4Px|I|EQ_WTUZ<>CLd zz073Q_KIUIex+a zsX2bZ|Ecj;_&+uCv+;j=yz&>1cK@f&SuoO`kJG~T%)|aq+q3NW3je1rvA-YqKQ*2l z|EJDhl;-{~-hcjTX@-t>I6lMwshRJG|5J1P!~8#Wj(Ix#pN@C%%lJPX-_ZC!HIE1W zFW&gSc;o-#jsH{g`4s=B#`EF-)N`%zf9g4Qe1`v1^Zc>THz{r3e+td>$vz*2#+Ty% zbpM$D|EK-ehvxHMTGtyx^Z60~r^knXf9P6%b7=1W_J_BG=KC%9Km9&<|HS{r8~>-v z!@uMI)Ob$(pPIj4`^W7Fw}-!9&9?6h&EG5hpZ3qS+jnEh?yw#I_tE`(LRT&v9i4X6 zU7<_u^WuW(cZV)nILiH>9-mx${^I}ic<0#u_&+uCE%ATqTw8Ay|EDgu<6-9ih2vja ze-;0y#slL2)c8Ku|5Y=e4gaT>|5LNxF7y9%eKh`0oijbn{h#*N`oB7UuCU{2{GYni z)+5IMsrh~j{!hoNH2zOrVP28>fAPlusqtg@KOJA<1Mz=q{2l&JjlaYHsqv8bKXsnX zJH-E~xqkegy39N!{!cx^zK?|eQ;)XeZTz2_+xPyGH&dGVf4cqnMf{(d#~1&nW_{p) zJ^PdJ^R=@_Mw8pU8@hh3t&cI|z0h@Y#zvn!@qTE0-dQa_2wgsVwEI8ZKE9uW|5NjM z3;(B{I49}<)RX3pvg7$r!*=HF;s3Oq^@#C*YUW4c|I|EwhrazXH1iGdf4aZ)_q%=_ zn)&VcKRsV^?fX~wKXvV#4EKNW#{a3S=Gi=3^MC4^1-2gO1z(5e=kb4f{^nN=bpNL= zt?1+aPhD1-od2iJujudd|I~Tr1Mz?A!qPtO|MYq(D6#qWgZ~v?KNE}kx&PDq!Km@4 zMZLd^GWC8lDWga9$2*S*J#ow#_W9z-OugS_ruBFKrye^Z>HoGpGu!Q;Q!){|I_WmZ{4)y z!mu5$G%sgkXy)RBN zcUfrW@v;7|_8&89xcfgfUJC!G=JHwpSIy_RvB7 zQZDa*^{~OI^9GyxzYESuUGJCmb>p{p?ZVk9eeU8^@7J^!FG<~h;i8$*&!3o{SlTP; z*YJdw{Bv4L%Lw?@JQtYdibAz2_PZx&KqYbl^$% zf9eB|Kj8jP{on(4xc^f>@%Y}TOV7e^dHWu}*ZrTa@6{Lfx&KrD`jzM0|EYgr>wn_^ zba@{=dT-RRI4`mBj4p|Jb6?K9Ys1Ru=4*39UwhHIsQa5ap|@Rkx%f<^l{hxYJ>sIdn zN(anw|2M2%TlatJlRLC=|EE5^OMCZ!@n-&?n*HPN2VL8DNa>EPQ@1zuf8CC>0dfDu z2X;Lob)MkSM<4C}Z}77D?*C}~U%c^ux1PPw{a>qAt=#`b_lV{b2Kd>f?`1`agB2wnw}FQ!{@M|EKP9T*v5xJ(q_* z@z}2J|8#p!>3*Eg|5KlO-0?pDPtE*2=KrbjdCdP)_d5LypZ}-scgkrI{!iWa!RAk zFX|?^*L!jM)@as+HKF(K*b;3!zdH1RowvCE%N?Gb^n&;9a{s6P;`yZi)8&0~DCz&= zjsH`B+;G7CpBnFn|5Jbb!Xfv6>iv6m`TD=#-Zs(a3Ep(w_3r<)edd&@?*DXq##UAM z`oHS*(qdo#SG}=dl>5ICe;emM@Q$T*?*G)U+4~1;y<+;9|M#C~A9Mew{{E?_-T$dy z*>tJ3=M7(e)6#w5(6Zy*|8=W9kzP=l$tO_kNro$N#CP+4*JsU%c^u>N=YjhW}I7+In{QKQ$iU=Gq5RdUNyp zL(Bi^_R#o0wXe5p{!d+O=S$9>dv|Egx9n(lS4ww%dQWKPPvHOb_{jgM<^ST1|5MBV z#T);p+av!M?;rpD*03G_m$T=V&{gw?M~CvZg!cI#-`tea_&;6W1oMLUKlLPA-wFSx z=KLQ1FW&e+HS^2xfAMDipPKb~@qh8g|EW2@^TidHhufEDp75EIFKsw;)se}0e|G*0 z|JQu}5kBuP-`2;(|2_1F$o=1_`2*emeO?>+e7_uPr@m}kZRsd;~R zYumY@hm@V}^Z&H{w7fIj|EW8T?&|(eed3r-KL1a*=j6;T?*DXqhh%kh|5x+#Bi#RG z7Mx_BYEF25jx6Zz{!h>6+^N0X|LOP5`~&=-x?t9@X!z&#;qlA2^Bwp`ztF5- zjsMg8F@0V|&(NIz#Q$kKjsH`#ej)xZ-uOQ?9uWT*Z~UJc5BTzHUBc~QfBc_rFXyxI zf9e98SH%23HC~7LfAPlu>G7FvkC*-b(D-NkpPnz1<_+}uf9f3bF!(<`-?Huf1OKO< zX!Al@|5sgM=YyF4r!KI0clbXw^ZW3BdcD&4KlP|-zMfa;kyHD*|I>DS9sV!g_&;@T zTmK9Hr|x%n{-2upd-y*!9uWVhW?l;ZPtEx<{GWQ1&2Pc~>Ge6%&cEXS)ObMrpL&F? zFNXh9kG1o=tpBUdviTdV{~LO4y8AzMw)suw|EW3O{l)uJ4(j~^pO61j7p<5WZTQ=y zgL;3-GauMv#hB3i{d@EGgF{cVd0zNG?a#bU=KrZ@*!;HW(M|{T{#9z8=I-GwLsy)i z^ncpF=&=7&7jDRN|EJqmwPAw$KXvu_6Qhh4_a0EsFb}om7e7d8{GX1mYR{X@ytxB9 z{;IP1Y3BJtGylsxQ)rHF%opz0{v5yH|J1qWOZZPc*1V%_PgjpOZ(~0n8c%1JKU&*q z+rP2x^>4Q?bb))pO`~-@$?=!1Z=BM0`C)&K|7@OIXpY}(K3r)0gw1;kjeo}f>GtH? z>l^>4$E(n;5C5m;@=rDYr{?nUe`@9z;{W1}|5M`w@qcRGkMMu$33fb$|BJWH_X^GB zzy8Vk(5(Mzzu(Y!>aCSmgf6zn^U2q)30<^uoO!Yzgl4^2{GYC`+OO{GI*((8cH4dR*rJv_IE}|5M|W@PGPw=G!v=Pn~0bzwm!*{+{9g)I~Nw z82_i%`oC&CDE?24H^Tp^%WYnwJ)cAK_~QS<_QU>9w|Dyb$?pHOo#Pe!pPKcL@qgOC z(B4n*e`>D({6~j}{keX7y@Z}&&%ayG932`Dh5ysfGyfR>r>?N$P5hs_ZdJPbKXvWO zQSSfLJpTAUHS+OA|rf&Wt%FUxZOr!HDL*8QLEf1SNPnE$6{eii;t z&GVc2fAPlusqud=y)rjL&u99b3l@at`1$9<7N<1+Py6H7@qg+9^NIEA&&>$OGj{)e z-+y&VfB4p#3?1Ka|L}im?jQayv^`((e`<~&@qcR8Kga*6nXifeYi#>GVE#|d?;roC z##iJ2)Kl&EkN;EieK!1`n$NfRKQ%rO|EK2nYoDJ&^Z640r^kbN@c2J9f8Q@W=Leyg z$M^DUH-+Z&WxF%Cgy!;kw7E4r-W(r3F!#2U{^gL{!~Q(~`d+&=rC0uDTWJ2i;Qw@c zX#Ag=??2{#w<|QaAOENAvuqwb{!cw)VY>T2HJ@+o`*q>*pzZs2q51v~{!fn|eiZ+w z=KUN0r^cJ&|J0Q>ZyEomL{K@=3H9ipk zr|V-rp8fkr*j_L#>HoAp^Z)GMPr~*ho1cdN)A4kE&0zO`>fts0-2dr#6;Fr%Qy0`F z{hylkW$*d0Aw$QP_&xlen)QwGe`;<&{!fi>#Q&+8FNgnA=h!?y{GYmHYMT2$HTMVq zr`G(xc;o-nTp#{V&Fwk$xgUitu;c9oUEU7Oyuv5u{Wx@~eV+;cr=PE|e;>gAsW~3N z|EX){rMdr8b{!h=Js#&Al|EcTd+4t+r|EZ@f%Xj~$ zE}xy{{!cy2)_2DL>G@k;*5Cb~n)!Xq|5F#0_xAaJp(_Ts|5F#1_jmuNF1BX=pI$$u zl{Wv<{9ovj!S4U`evzBg+x?&Zp5%`29sO&_k(v5?l|811`#&|_kNJOUJmBS-%|qk= z9{qfJrmgwwzK>@8Up4E0nkC6xwQ+iK-kr@yve{E9ZEI1cH2zQf<0bHaYCOe{r_BqE z2gLvB`tTG_Wi1NL{$I~u92$Sv>-r_3<^S~a+{!fk1Vg8?*d3enKQ{#J>|7RxDy(o?UQ{!v!e`-7u z{!fjsvGb#uIzOuQf3+Q-#`?dyKAQP|YWx!ZFW&e+HQosSr!E<1-_JMyr^ch<|Kg4R zQy1C(_&;@l`7`{Vn)!10KXuu-3GV;Y{5<|I-pv0~SBx9u{!d+%o%DZd{2=~MU7eTX z^Z(Q(`IDnTzr4Qj_i6LxezfL>(D=tit#3?e{GWcF`G9!?Zwk%4z2Cgh*oEWM-T&$L zQ8sz3`#=4B;p9yBfAMDipSo_`c=vzm`tjNB|I|D__`i7L|J0iQ7jOKZ8h^?BKXtXu zN5ucBnYV}kQ|C+^=kx#c{I9de8~>-SvEK*t|J3C+pArA3=J$pFQ!|ee{}*rkpPJ`C z{x9D6KXq;T2w(qKx3Ah>54YaFJKWyvQEAbz{(D06`oRBbe_jvED((!8-(>!uF26J* z&HbOceC$Z~f9gV;zZmxz+@E+?XQa;aD>ttj-`;dyU(=pAD%BTGHs2WkdAw!3@xk$C zUgv*pn}3?Jy-71)HNJgvT9eBklDfUPNf!{ZqZ+&;hAFaf;1*i~s!cbC#s^1x@_lc}?c~HJ$g@v==Q- zoexOk|Jp7;#^={DKM?~R_*sGT>ir!dJ5w@>cvDp2eZqI_bweJ6P`zuN(y8lxzD9LjF7w@Xu%M-^pOZvVU zWd%{%7iFPmR~Ebf)As7>68C>+-`v*yUu|uf`#<$mTmSc|AD1RJXC{5$4D);6b#3g* z`s(OEm8FTVf7{Ofejmy#udR$`Y%K|0P+e{7mluc5ud0fg{kbGD^Q@%z%de=2I`k<` z{P67#?)^$?YonfHOB3(T?C9Qa{=5b5|J2uAd%gR=k!_RyZ|$xfKL1aB(Y^P$|J(6& zC-;Dl+<%w*KlS4e?REdB-uKWw?*G&WAG_cEpZf8~_PYPm&7L0p`_!Vuz<+nQ^PO*I7FA|N8F?j%cKuIC%=qQonI+ZZqfHkUhn`bY z7`^^@QRtj8gQM}U7bRAFaDsWEA7`F=W;geLZ`?7*y5K~dqDa($EJ4G`PU|N|GV0JK<59c zkGFY%BT65=KZn$ulkG=PjdgKmj6@Z^_c&sKI@cI-T$fC zj{l1{{x9D6KQ-5n|I_1*_r(9Hhqi9v{_pv3=exh$R9g`}`HT9*bz3I5pL=>*T~zc% zUFg5uzQz6DNwwMT0iW4kC z)bAYHA6@pU&0{@${U1D^aQ~<6ADZ{W|EZrjbkO~udd2!R?*H`j3ujJu|EKMf9lt-yu$q-GyL#>e|_R{_kZe7 z9(lz5pL+M|)$ae)*RGxK{!jhP?i=0zslVR6)%~CP%bTxt|EGRw-MQ}n)IZ#?I(q2K z^n`lf=If)⪙reOSf)w|EJskMO-bnyoFf7<{4OE6%-T&1TPIUiw^>Kc8%Dq2snDp~z?)NzVd~DI%q4906KmJzOpT_^` z=j-kK2L4Y!KgH(7;s4aLmuI{GQ_nhQywCqrvpy02PtE$Y_&+u0hw*=E{N7DpKi4p_ zIO+SCPxtyQheFre&*T5JeUhC|!2hW^e~bT9GhguR%b#u7^!}0V{b>B3n)~}{>!%ym zWG8(e{oWH#hUR<-{!iPPM}YqeZI3VhFW%-k8VPq!{sR9O+RoQ7|1aM7KV3dPkokXV&X3^#LfiRm{GXch9r!;r|Gu4O{x9D6 zKV2W^$MJt^&X42&)SOSj|EXF38vm!}d?5Z$U25|L@qcRk-~Xju6|SH8f(t*tA~aqD z|EJr>dSLiJ{r+?8^|&tM;)a|FN$)qoUf-YBZfsaR_dg9wetmx?^RJlyr)K>+{GXb6 zB5!}SrlIw@|8Cea{{GC-_V52s7q1FE$iBb7>xmViPbxXn{hxk*aNgh^tJ=-gEk zqN8$iQu^E5Cx&KT(Jy{KK6I9ye|cwgR_MZcecb=)_Ejz$;{H#K$HV`{8~>+fKIijm zhlb|-F7yBNephL}2mhz8HE)9dQy1F#c>JH7&BqF>RIkhl`tq z$Gc|PIQM`0eUG*G!-x9+i$nXsqze;|EDgf@8$kaJ;>&-;Q!QvZM`-8pSnkVU-y6NGpF?P`G4vW z_V*wEr^XlJ|Kg4RQ>WSd7yO@kTwR~2c+u^lv+eTne|o(#pKy%%KlP{?Y3~2jct`x7 zI?Lv7;Q!R=HjkM3fAPlushJ;w|I_;g{muoY2lak3%H}`f|I}kw=D7b;;}h_I>bd9T zy8lzxuFrMT27c^?$o=Y~kO(;OFsw@y7qDdA*uvI-uh>+I-i3b+OG?!~bdj zeDfLnr!FuLiT_g<**r1)pBlf6|5G!M4*wV0{1N^y-gf&#SDSaT^=d;`*nCg?pZ2dY z|BL@q*V=acpPKi-5$6BYx%Pb&{GS@Xi2u|5&9dVk{GS@%g8x$&+B`)3pPK#gf9i4e zeGB}b8h?oYQ}cd~|5M}p@PF~f|HT{srZ=kMMQZBiQlr=Mp&F8)uA=fwZT8~>-qcjEul%}{KQ*sc{9j`y{hu1YXY+f*_Wadj-2Z8NuFWgN|EaTW9^tGpgF;WVd5GtH zHzah)n#u0}w12tHC&mA%7p={6|EHdBe{b*lEF)~kCqI5$R_IbYKEVI!^;>J+llgz~ zX8xbL%={t#FW&e+HS;;~f9i?$`40c5#(OdUPmRZ7{-18|4D)jMKlK!wzlQ%)^Z5k- z7w@M#%+ApBHOGz@@PFz__I)AzpPKc9@qcPQPvHMTn-9eQsqujLKON8T{hyqZS7qpU zkMIBB|J2+*{GS@{h5w5;{!i`m1`1wk!uEB7Mk}P z`+Snp_W30=J{kX~%VRxw{GVF>PhD%jPyC-6e`lYsLbE0AOEMvd$#@i#1O;sqv{F9(XYH zB>Oy!|I_cg(B{!G|4%*HydCrZ)O zQijhKf9m?f^Z(S$1H}Ku8~+z?=KrZ#zXAWJp0!|%`#*J^`9}O-Xq$JA z|I_cg*5;uz|4+^R$N#CBhqyWSccIJd_fxU+_n}!282_i|8}kV3ZT_E{=O6R`)HChh zLzce#=g`xO&WP6b{=d+9wqEZ=8@~x%VCyB==gZKgWoJh}==)ttZ@c(!p_vEx!qH|ilCHi$oSPs9J|d?Ahhi#PsH&HOw3pBj&c|5M}j@PF}cbLsrh zV}=ZjCfv6mG=A{Hw-$!RW9<88QA+>caZ5sT{rxhRhUWV5f4V;A8{+@e_&ofdy3~9L z{!fj6#Q((`|EIdH~c`G4xNw80VnPd#bGaQA=l#{a3AZ-xI;b9?ZA zYJMO1KQ;T~|J1CniT?|~PxD30|5GzB3;!2y{9nBBe>%U+{`fyN9uWT*Z~R}pS^rnf zJTd0~sq1V#RQ#W=uhu*f{!fjsnz8@#aDV837hDkBT{0=# z{hvBFH`o22exI4<-|&BG`M-GM|Mc_nf9gu}ZumbnUT#y>&7pHAjd%a2?FAF;`yMv` zPhDiU5C5m0HgS^sKehayn){3YQ{yr5e`;<&^Z(+F|5Nk(!vCr9p!h#^rrjU>pL$YG zw);Ol9`b+cO4ds@|EK2h!T+i8i1^E2^(YCJ9ePtCkd{9nBBe`;R;%>PrD4j<(6 z|J1x6GXGDFAIAUb{_uXm{6B3kA2G!JpPI{O{-3(q)_-RHpStP%zoyOWDefZg0}8Hy{6b)r}=;J#{a3AxA*+jQ$sV4Z`M0gLNi}5(XKvmcKf6cT)J#-lv!05 zdd1SYQDSFpXguJTf36KbztTKk!@!!beU*7f{NKmtxAu91ctHH0`ut@J-T$ds9~u9r zUb$qh`#<%J1=HOB>GtK9=eqw>FD#khent0pN%`am|M&NtV|>0}RdrExzs(cO`S=+3 zee@egHgSaq8x&KpNb>(I5|27nK^!b06Zr;6yu_#?^r zf9fY6xzGKddfyWdx&KoieBwd(f4Y3;3HIHWmr(!c;1llu)NeIB>HbeY|MK3g?*G(R zE}H88@3LK;-2Y8qHpTs)`jQ(rMs2>yNgR{g+1Cqx?%FG&=+F6y>Xuy-ZI66CbMLBU z(fxx95?x;F>OOE*_2}rf?Bc{NyN*kY{_L&Hy5gbHXX}bW&#Rv7{;y)@@$Lib3(Tk6 zddKRjv)V>ACpPx*77>5H6KnTPbI-@LJ@fscTiN=*_V+(@=cAhQ{eZ*~!>79U>)xhS zbk_Ro6PG_$Z|7%^9m~AGD}Hlb=#$#FPI*1I?sRNQcj$gXN}tm8#FXybx1m(ZcRfY+fLZ|2wL~T=##h|BL@qcWQG?g#W8pIomxXjsJ@`{%_9*Gu{7nY1=OP z#{A!3M$d2`d0eN??*G)Mb#CYWPkqL*N&lxlwM#4af9exEv~d5Y%kR{st@}UqvE4ej z|5KlA^9Cn3yCU2^eBb89mxu0c>+$0Mbo=|9a=iP$(1+LmRWsiY|EC^w^6~Ef)B{gC z&i$X7>%;%4@qYL}HS7K2|Md9sc)xAy|Nh~HdG7t>|J3)Kzc%{%;<`jt^?3Jv4_v;^ z=l`i++slUBD>HpN9-*B1xKlS~#o;mCPs$aU!=J%QZQ-8VbUiW|M zPj9)?{hx0C%R6?t|5M*{;YIHM)VHr$?*31`<=iFi|J3_e*1G>wKYdQ6`#<$ntERaB zQ*XcG9QS|f2QRz8{a?IU|5tt6B^%xUskdEriTgkGW!G$W|EIp{hU=sL9s7p+f6EVU ziH`2lC-m)GZjV0g+B@{tTknXTKCV~jd+&bO*ZDIn(p-;`N8It_s7|j#-{YJ>1RguD?Vv>_wD9> zJ~?}td7vI2g`a1>&UYXDv|+?U&D`^q+4+WZ&VN62z4cd9-fcKzSkm{=cQ$(`H2?mL z|I>EPui*dGcsTr@E}zE#sq4)5;s3NhjsH{Q1DXF9Z|480@qS@NADa7P|32NY z;CF|EI?LO?c|@hWb+vdp_$8GagIn$Bub4rSX5-pY{Fl zfAPlusrmg}v+w@U_&)O=p;`YH|EJqiX6LK$f9lEB_&;@y?T`P{Zr|ZvMI@0}L=)?X` zjsG)G)6o99$miwZ|N7o{QA3|@|90=kd^!A|x_H6R=s!KqZ}?A-f4T3QVm|6uSF8`6 zzdG0bpSF*hJ;ME;`b?XjhyPP|EIu>3qWd|aN8~2`pRTX}*zWHC)IBr0`TW0^NB*aw z)dLS?_8oVE&;R@W*rfj(IkCI@Ki!{fTd#cXceBIub6n}^?*H`s%Qx?|Yx#`ucyT@l z{}&#gStH#4>G7?bJuF&0yC!Vs_mBV6{#iDEZ2NI#;rTtVqIY!llH$-~&1bE9t{^n8 zk9o)Dg=Rif`GUzQJ^tW?(98!K*l~R5%=v?&ljn>LJ$C*8d%wvDwXOy=ec5HbLsy=cZR?Aj9lG4sZ#?a& zGeeiH8E5lLP7lrb{bt)wN$HipIWaW;@Rvi54_#r;?}`h%h355-|I_W^{R;o5=J}5Q zi#PsHjsL~}sq5@~F7yBNc+9c$ulPUxzNgvwrG>Ucot{tQ?e&HKQ;(iI#QmRocwH}_ z|EC^WbGG|G^?-_=?*G(-s(QQsQ)ik7eD|b}!{yV=|I_>P=&GLX|I`__zBTLrst4Qo zOZ=aDP~AZHf1%9>GXGCKurBHU)M@p--T$daPVMXdPmQ0&|HT{sr)Itj{x9D6KfPX= z=ZF7ObAFWhe`>rQ{!g7fE6x3%I&JoF_kZ!m|EXDj8ULsEi_x}zF#b>PC+Rld5dWvn zw)cDH|Ecj?_&+u4Q8NEeU9m1Zs_%2sLA_t`{AT{2I@k7R{+~L}=9S_9)c73yU%c^u zx_s8V?6Klt=<;=w?E3eHu2`RA*LP$1`6`D<8TaomCy1iAaC%gYsSFW1m{!d+J$3yr(b*(+$@PBIj8U9aQY|lUZUugS0 zfd7j({!fh`!vCr3+;4UdJ=NxU;{W2?@qcRO`j(d*&N^qf`#<&MHDlcWsVmnNxc^gEpI7AmPrc~8QulxAnJaSK|EZa8i2qab zdbZbB=xO$O3IC_}i>_yYf@#t+)-G5mbKt*71WuO*=;+v~smBjus_{D%M2 z&+~f5|LOKjwdXJXPhD@Hhw*=EeC*zu8R7A+FkgrN)9-`N&-g!efz89h|EZbpjQ>-Q zUy$^FYW&q3FP)R2;}`iqHNFu4r{ftK|EFdiG5#;!_&;^Ay&my@YHly{|I~cH0{^FG zek%S?&G9DwPsdM1=1=i|>eAJd-2bVIS5DybOW4ly-#*`@^m*4^9UA}F{MVaPdUM9L zq4A;kKiwYweZf9|g~kip_p?Hm+q_2m{#NLGd%u0|Ec-+7W`kl z@qcQ*?}q=2H~vq}^B4c8=J|{NQy1IkUHqS#^@8z#`h6D87~uX-ojawE`#&|l4*#c~ zXx<9{7kbLjs70?QLr<{zd-y+XA8*IA_U|JZI$qAI>CeBPgwCrTVjEg-2bUrKNtU}E}NC^{!fiB!~ew_|EI39@6X`>)Ma)&j{j3L{~rIR&a-)W z_&;^_>~!~k>WSw2@PF#cxk>*QZ`S`+S0DC&YSzPj`q~dNbUa!+Z)EiR=O2cyvG4P| zG5F)qJfGg*^hrv8@&3<3Pqgo2e%14{(0TTJ{cio|p=U3$D1`#<%>;vVk*;*I}P=a-)8{!d+4es+ZaQ}cYs|LOHYGyhMo*Yc7+?*H`uQdZnM zx@lvSsV>av>HbfDZzhjF-Tj|h{!g8qmO3v;{!ixkTnkB9$@H~vq}JU;xN8ef6`Q{yl2e`@x}|EanBOExUZ)cH)dH|$&- zn(f~|za*vcfBJbm$;amZ;*I}P<8knRYCIwSFW&e+wdVh+HUBT(_&>G$U%c^uYOVhp zZ`S|S?}wk?aC2kh0gvl-QOb7wpZ3QG;{Vj_zw6~oGIf5FX8m6^`{V!AIip6n|5M`u z@qh8g|AiiD-@i5gr_LE+|Nirb%fj_n+PpygpKcH9d*c7p+<*LE{Ql$r)cidDPy1Jy zXTtxfS^pLPr~PUCpPKoB_&@DW-5F z^ndEYu}S}@F3L*!KlQ|{r2mUI{!d*qHp~5=n)P~F|5uHV#Q((`|EI?H;s4@||5NjL z;s4b5QT(5pd3pFhHNOwm|JCo8`F70zQ&-sf)A&Di$(Z5p|J22!hq?b#XOAA@{x9CY zK6OWUKf(W9`dDh8p1reiyFEV-z1P@yx+(K^h3&lm{NrzpjdvS<_wI1}@Phb1T|dqI zztDF5_&;?;#t8R+>ZbGlm=7BF7EL{1)AfA+mk;Fek6#|%INl}02BviJ(A2*_Wlg+a z`Os9~*YxjI(=HsAdU^RnQhiw#={o=VP_owN4z?*D-Ui|)EWb^sr-E_TR z=KWp2V@Bem>)W_*JIDH*UrtZylD>_-bm7cs(7DqZx7+#fj?YdFjSu`wl-fU;G$m}u z3qE#jedy(OfAD{WQPLl-TQt}G-#t~WeZC-_v93Cy#slL2PI#r2dqCC)X8vF36${<} zsaKve-~FF@!NM8t|8#kkRfX>V)Jw{W+^^{N(D*++K4le!?*A5?mh^w+l}Z1nt~~7j z+P!v+`@gE{3ip3%w&VXEU(wd*`&F9{#Q&-BfDJv%6TiN{oqIq0;KDiOiOuEheV$)! zRZWz4Pg&@?>e>kZr|r`#tKI({|I7C7|CY^}=l)N<%GOtA{a^KUS8a-xJYO7o=M9_P z|0S;J;2!XayYGm$r4=XCPv3vH`@h-4lOFKkqe=g#e$3|mJ!T$Gy?_4`?*G(pCZ3Jf z%qs}n-+lSH=%c&yL%(A_Xw0wjLci9q&;6f%{<(X1y8lyOxqP1czt*31bpLnx>c#H= z)KBcWE!x^9C!v1$j@{AEPs>Ym{B!3-e%h;1<3i3d-7Epzj{|Btf! zfR3t8|37|FP>?3lM6jUTlA);B%i6nZ zUtM)~EvT#Ve?Cw6Jh^v%=eXy;=lssk_qlgw?o4KeN$zW&Z;AT958pUj{a-_je4j`B zAA4qQoHJlwruB`}Yt;X3TH8lG;O2xV^?&SH{dzjFM{f2XJF`MPU-)^woZE-Dc7c4q zr~Q^SwtdW~5$gZA|ApekE?>Ob|F_Pi{sSpJqI+K4-5LA+_5R{j#s0N%-J{!_={Wby zTIK(#f06&SjI*MhPVJpPKD*Akea~*5*Z*1Poa^cCeb4iBJ6TWH{eIz`=3W2y)KmYu zJD=wDgYbLse;*{)ssC$#W_R^}?6#e{>ioady*29pdUolm{_pYb)$0FxpV>|QAN%ZX zXJNjy-?yexJteMRK7U%D-MzE=KkkotfAakmKf71Aj`)0Q-M3eZ|Ksfskoky1x~%ZC zgZlJS|HtDUe&I#x|JWn?U#$L*J@A4Hb^Tv9=KaC{u_I-DV66Yk4wLnSG5?RiPC= zyw&;ny&`|??>_Z#_ix?cWPVU+{h0W_-5(ZMzxK#J=fp?()}K87u=+n<-&Zo<@3C?D zcKt6LeZrYJF3i@X?sjWNJ|FOT{x>x-l`-Mfuy&6$G&sbGWCD#`)|EY{U7_)HP@*BV;{TbGUugsBkcY) zUp~j#-F~?Bz4CpA%Q_CT-a2`LQ`BXs^@j1a>i>9u_f4)-|Hs}{RjmGxy|1=P{U7`2 z+*#`X*n1aUuKthx_%*B4|FLhp_8Rqn>?QN&c-{}UEnV*ES08-X)7!UhbbR3-Hp?0g z>H%Zr_c{0bX=F)Xr`?V3Hp_QBTYTR%S&yLU?dB6JPSJUNnBTVethcOjeqhw2Z&<@` z!T)jpLYa>M|HsDsfuVsuAO4TqaeVN9Y|O8K|6{|;!2hw~W8nYTm=_2C$Hw_v_&;`voR5P4W9Qe8Qvb)} z&8rJh|Hp>cfd6B|bHM-c@hOz^UGRVGBAFit|Hm$n^C|Fu?#BE-{ycC#2lM~j4gbf+ z$Nlm8!2CaVWBwl-^E%-Fczf6%^Z(d5f7SKl zE1UoO)gS8T(DAF6x3{u%y{oiaB| z{U1A|I!yf^+mZ7V@PF1B7pebak4@;U^Z$7Jp>Zwq|JVb4E$jdC_y@=Ja+Y2q$Tr@!aA3LOKsQN$lh^Yzc|JcFP5*_$Ic7mL5 zg#TkF$@y^jKX#({m`;yHTBpc-vfny|Tc?X3+B!VUjz4i`w46T+wZ^<6_&+|MFwY47 zk6kHVWqZ%z)-`fIwp;xWYn)$)|Ks~_p{%zE|Hm#8&jbJGZumcTf%paZKQ`u-!T+&w z{ulm_ohR>4@PBNq-vYWyUpi3zAG@!3Pt5;g#}*D!|L1PZ|6>o6^EFuimrei2jwu|f{*N77 zG)(;;pWl(P{iVBJKFE$J7^41XZl zKQ`C@W#jVje{8HjhV_5>`b5M3vD0Lp3H%>BL*{3||FILq6T|i7%mB(iu z{PLYYn?KIl>qC#8Fwq+RFQ{F`LB4;`|FOr`1Ub+3NIJ;(o1um0JJU8sSO=H(a=KqI z(mHz50O!%$2U;h|{5kkPUOq!SEc_okRbC(Pf9{6=V`Cl{{GYqw|9E`x67YZQJeeo> z=-{% z{6Y9XHas-u|FLoX@PF*&DWlc@vD0USssCfcSHb_e8~%@-FY|rj|JXS)uL}N;4G#tX z$4-~`=U2Bq8p+=m@Okpv&dt^-@_7ROkK5t-;Q!cIFCG4m4c`R+=Wh5vc2ZM||6?ai z4sjgcr;&VrkC5%>-T9Su$N7t6es##2!DaAHV9GGV9bSG2&4x zt?~O9{2w3he0e^@|FJRu8~%@t^)2E5*wGCmoxSCaQG7nb14ee6YEA#g?Wr=q8}t9z z^nd(3NB`$;_&+x055oVkb7VbZ_&;{G{C)=i$Bvi#=MP#I#m~nH^7~WrvgOu^^7DZI zx|BsE=8~h&|z7zhBT`3+P{*Mj+cOYd|6h9xKpWJr6HJ&f>`<3lq zI6oG@e_3Px;3Wxbtm9-J8T=pbALfz5|FLsr-r?%E)>^~s6^~f&Y4|@r{_v6Te{A?j z_&+x0@5_98yL_R1-$s6awZ`x7^82kdet(Dm;JkN{?Fa; zf9{6=V;9Kt3;vG{9}54+hF^vMTSJ4V)<#r!{ZhRoZ8|8qC|9~HnD|FP32$Eg2fr%v=a@PF*GiR0A&v5VyUGVp)w_z4l} z|JaF>&yd1OLbS zgD%+og>_+Vu=+nfUyABR>ij=8w!{Cq8~%@t`GD|$?uP&4^Ru`-RQ(^jq+*QvKQ`90 z#{55aa_LB&|HsZM9-;n^ot8gD{U19r?-J*Zw|}+E`{es(>B+y_>nSsLuygpjKkfCK zo_(qMKfXU@rVn=>9oojnj*Ge2dGFoUPKp@l$Tr&^J^BJi?4b3ykuon(*8k=Cuh?i^hSzZL$E=MOR83G@Hh#bagtOYwi~{86Dg|BsFJ6yg8an3o6t$Hu%R_&;~U|FLm- z_&;~U|FP-+(pQ)1JQK{vga2d0>%srI8~%@%j~Fvn{U1AWto(i}{*N6I*5d!zn2!km z$A*`L|6^l2=KryAJXrsi4X+3P=WeY3>u&fzHoVZ4?_Xv=A2j?Qe?IhoZ2CVow!{Ci z;rZH*T<+ufOZX%BKX=3bvEfJI|JYb>81w(w$>AaD|J?oOQ&-vT!2@k9x!M}fANW5W z4}2v29~<)*;s4k;KCJ)iZmj>yE)*{W|Hm$spCA06wagQQ|KsC{`GW9&>^xadwd>&P ztn+2P)q4)Mc5dWYCnbB8ZAX9cNo&JD!T<60;LqUy*zi^Ge|&u4C*l9tA#(f454ZN1 zX!$;E${O2_^?{du*xK1~E&h+!5041{$1aTa;qTklMKaG0{*T+ynE%Iyzr*}LHvDY= zZ(19VKj!~&dr?G$&i`X$e%|rh*V%SFKJb6sj`?};e{4KH@PBOhKKMU(!~e12{ow!D z@M&AOZ?vBWI(*b7Ps9J&&sRJs{2v?h?co31jro7>-uuU9d%uAHOI^LiIx%Xr1OLbO z6Zk>+KQ`9mh5xgb#{>S4jmHcAk6k9`^Wgv3h2uii|M7SVPx?Q0sm%L>|6}9vh5uvY z@x}Z~v=X@d7OLm_>gjaPpyr#S1U)`M-8L-~3+`fA|j>p}2eYqR!nY%lCOt7Z| zJzwDbJv=|%m(L0D`nTKwUl`bd`v=bZ3+zDu7wG!}*Y^$Vp~Hhb$2(%A*XR8&{}(mf zyMN&A=LD?xn;zs{Pk3T=rRVmijQ9G#xpm&{^T$_v_Fpp5yZ>dAyz^=>-_QN?K*Rq% z@zxpY|KRuF|J)7#$HscW@PF=x|6@;UtW*ETo-RHR{?GcP|6|kteVcTK&L5m9+jaim zZ5`DAq2d1qp6rE96V(5ep4sC6E}Pz{{*Qh6^ak~R?90R#bdq^}?52s;PW+bze%@Y1 zNsjZ`u-0xY$W{Nx?UQ9a$!q5p_*YKosPq2vW&8b46!cU#AC&ohJqBgk_E*L8 z!T)jld(RwI|Hpp+*{9V1v0r|oW&L0FV|Q&=|Hr;!#zggh*Pq+s|CUZ~@qg^QHr%TI zkNx0|4Ng>_RDYi-XZZ&OKjYi8ezkK-VT$$c%bT3bb29v&f7;W(=Gzy1v(v-W|H&Fz z>H))KJxBOIcFo+WPSa-@)*EItssH=rxwF*+&XD=Gw`FJe+1UxH>i@3)rc6CxO<|e( zKlXLyRqFrP%km1HH!r)v-)~BhdcXL=r>XyA5A4$7|JJoDRR4E+hqmhf*gbl6^Ss{s z_5SO==sfTG!GZgq)!`J+^>xMaz^-|K9XodPbgy2$Jl(xpFZF*D`qZ|}13a^*`oABR zR;&NJsPh@>|CWATss8WcE*;hXvEc*Z|4wVH@c2JAyr6tOwe8(yePQ|hYJFDc4)}a) z-LH3dN522!=k;U$AN(JW2kZG>G5>07%=3HWldG&pUVMo&D5JIe_wVm4-hZWS@6$)- z1zytB2{_pMk>eT-^GLG?I5#|12 zqodXLl@03eB)n7N-}Fb6`o3q^-so(3SJqQM*@t#)QUAw&eDgZ>f9wY~-=hAH{kJC` zQvb*POkTgmvi`Zd@B1Xz`pqK;)c^5#-hbw>Gk9FC9p5Vl9#Q}ITz-uD#AV{uvHmZ+ zyl#^EKX!fN4E2BPrm1t(|MB|k#y6?|V_#lfq5hA(xS~}3ACGrUU6J}f_T7u8tN(++ z!@R#c7BxD5Zj1BRHbi@WX?}|n0|JX-wyiVr9_-y|-x|FPeA;-K^8zeDZvZ#Da!<{w8}|MS?>&bs5HtlzxNb7g@ z?sm>|TKmg;_d3T<3AXJAuUxMFkH`D)%H`_+*biKNh5A4C-E*g_|6@ON`2zKS?8D3E ztN&x)Qjn(pkG(GA0`-6FZSwb-8~P2h0*E zXY78z`};k2dwS2-8`b~GIW6^n>Eg%7eE5DdJE-Jr=fgMNZtk4c;`0*cjBFLI+4A>#_&;{3tOpGL$Hx3O_&+voAO6qX@PA`obJYLg@AL3~Y>Qad1^?&n9S`kq9XTJIWq47{*Mjc2mj}8_&+wzf588->HpaH{y*mb@%ZugTFn1rFSy{8+rzn*NWMN1y-uMmrw- z{CeH7!5WWO=j`>?@NaE@TWgK^2k?KqKLwLyo{acEHs(iub$pFA<~_>!B|9E8{2z}; z=Us~bW8-*aeuXuT2mX)GKeU|xvh6s34gY7Cm-Fr0lCH7ahwp^{6XT)&59i`T$ZFl)<_JI=b^afZe_-M{ z>i^gy6ML)wTRHDf^?%X%1JwWV`H6XHuVvJ>K7VDspI^lP@#mE)>#=_EY=w1}JYV7e z_;^;x`3(3!cA1<%f&b&>;fpZ;j~y!Kv*7>OSbsIVO@`h6XnA~g7o}Qb{#lQEldLiS zY+2g`>tLC0^nGcpb(owllz*?S^A_jHdR39uxiU`&{*SkxCI08j>ao_DGVkk+heliH z&5x0J8zFZ8a_2?M`MF^0a`AWYe|-L-;s4l$;vbehaH*&N?F_WW`lRrGe19%ol&tgr z*mdHC;Q!nW|Hm$p^+)0V*qB!Z|HsDrC;T59>jT68u~Vf#JkrIECkE?Db?aoEQ#nS? zH@CO@n_UsA{*OOzoNt8xBJ$tX=addn|HtipWquy~A3H?ON6Psg>ybr6bp9W= z50Ukv;s4l!3y10aKlbo~Ve0?b!9^qF`S*tHkITdV@%cVf&Ie)spS2t>=KryS<$Nmq zAKOM{TFy7Z|FL7myTbpmBPzuIi~nPX%6eIt|HmFD{u};}oi6kC;Q#pgOsg5C z{*R68hyP>8iT8v5V{`r=oAdwJ^nV|$_`~D>*!cGc{*Uh$^nYxhobQAG^mp87xb`BQ?`|FNT{j#2-|PM9Nq-xUAH_Q`xO_&;{E%m7&uSeN-fZNL! zr{ManbC)Ek|Lb>3i~q~NT;{3B|JcQglhpr-@zeRxn12ZW$Ig-0w|th2;OEJ_MeuvW ztl@v*|F}J0JQ4gKyHb3HthX2;GYa+lCspE`WImxa{GWI->q7C*;=`=r4Q1Y&r{%gL zd3{(f8T0>mdqr|Q@PF3gm*M~14gbe3l=+45e{9Tq!~8!sd>8y5J4<|r_#wOfWLb|` zJdmeleNSunz@TRrSi=Y2pS#Q&?|<-rcKz~x2mi-T7ypL&f9wqLZN{j z|JV_-Kl~p%M!X~Z9~;+?`G4+)|Ks~V9zXa$HXc9tKQ`tu!vC@1Y2g2OeQDx*;s4l} zcPsxL#fE=B)S;cHUp{oYHRjcQFz*a&c*}2wb+*Ri`|Iajt@GvmqWzY$tTDf=SAI|H zGMR5Df6KG3kk?Ddk#npuA24>oxz>0+!vFDjvA!_;9~I9`w#pd z8}C2xe{A?d_&;~U|5=N-T5^A=HRkQX|8YCK7W^N(P`niU9~;k4_&+xN9~<5h{*R6M z#qfV@_*D2mHh#YFe{9Uhg#Tk>J|_Gh8?P_;KQ=yp!2j{_E1A*a|JX&-;?@7L@%bM9 zkB#}5j;}6?&o_L2U;V>)>l~R6ecqiDt?B=`Kj#0z|FPl!1|66d#m{5#e~&iJv`&`w zZ886k+tHZ+$4--ZckqAihW}&Z`r-fB$>QVS|JeBb4gQaxmkQ<%7mFu^|6}9z1^>s-M>+C*hyP>a`TyciH&|o7?3-yfTGz}=aX#LD zlXc!CIe&e8jjLteV#Y1j_`Zq!{%4KP!}9$wJDxJRzw-St>r#3Cef9T^_IRQ9joWMu z?+5?K$CLh#4gV^?-`e%z{Z)SdZEbn~g8$?Gct3;xW8?2H@PF>c{6BZY|G69fkIngi zY|Q(I|6}LL^AY}!ohv?dd(VB=@LKSH{CTBR4_E)kPAwm${?Fa;f9%AQ^Z(fKWh2%9 z@#l-r=a~P;=KMc)e9>U_fBZZelRrrPA3IXMuLb|d&y!KI9x&$rvGM&H_&@eona}pc zfaWOsd@1wh|25BV9iDN%`afKk6qtySg@%>QvKQ_D{{2#mcr2k_V%Kn)D$Hw})+u6!Q}{*U)RQ|9|^ z{r*eqZ25f!>;Llk1Fs1G$Hx7I|6>=3H-!IVAH;{vV(JiG>5z|FM%~UOfCCUr*Wj!_@!r^_!VH zMExKCeM!q2rv8teAoBp_zkTdDUy%AgcC>gv_&;_?*f2-d7PbzJkoAJEsP^%EA^aBn z9~<5Y{*Mh$1OLa?`Bt+2FB={W{?Fa;e{A?T_&+xGhyP>4gTeo?v&0X=|FPl!u>LO_ z*N63g+0o(=vHmaH7c$xz^~F?Qx296{f??vvrgoTa4G*|y$PDY4(PNy?vSwOi9wPi7 zuMhM7;Q!nW|HsDtf&X(i{GYqw|Jd+)@PBNq_X+>U^O0!yKQ`utVg4T*UJ~>F+ztQd zZumc*pM7&)x8U?7XNj z^?z*oKQ`v6!T<60aeeTAY}|gs&8w|(d944-?NKt14*rjiU!2V6ga2cfOT+)M;l(ij zkC&(aW7Ge!i)Fqb{2#j{RzB~D|6^yxMyvm0r;4|O|6}9z4gbe3l6ixe|Hm$n>x2Je z=ZPAKO=@PB;#u^s-8T@dBd z`G3~pBjNwp@N4jYZ1_R=KQ`uB!vFF80q=M4f9{6=W5XxH|FPjc;s4l~F)j1|+ztQ7 zE|PhD@PF)lndgW3e>@({!^HeQcfX&Lfy|hPbPm$~2URrJ2r^>v*Bezv~8uR}) zpV#6Eu^s-8-6-n~WB#AJZ+@f98v8E~EA`*7x`TQ^ctrTWJHKjg^8lL<7g@vqMV`^x z@P7w$3vK&+S?@P;Q-O8$gevEerwZ-%a>f6x?bO;63v!&fc?Gr|4gbf-r|_izyD`6` z&i5;k`F`+!)usKk3{5Uf|DpyR&+~#?ne> z@oxqG$_ZU`e&5uJ8ufqdhKf4%f9y%s4eI~cRrPi1|JYM!&2-j;=K15hw0OP+3umbR z?wEsT!f9!{)G5?Q!(Eq6VKlaN< z4ypfRzw^R#>i^iUKiA^_*oPjuU+4d^_wHJ&{*OIf=Jhq~O0nBpFsa;m_S0nR74s%L zLoRCVnb%(J+#8(Y|M`?|x*qVdjcc8pY01`ityKf9#u=FIWFJ=tOVze>-o!S^Xb-^SbrU7gwhH*}Jyg z<_wkfkJ&e`U+2vJHr2XzLWBChk24C@|D^;ERR705Py8L`|Al{*ul}!pm($e$vBzB0 z*YkSs+V?C^x9is4)1zd*ocsMDqEB~EcM6;j*Z~0W(B=HUGtM}})15na_Vg*;yw}&R zht~)8@7BY!f8R5_m;XQO70dd?D}Gz)-&9zoey~%gPU`<&h$~kgh~t6(WA~PUdGLSi z^JP6@`TmRbIp>^%&&U4c!xiceF^^9^KU)tt?|gi|_OyKdw(fCWKYTv7KJ%Qj)&KGM zFmDk4k9|(huIm53|E5|!B)la2AN$NR&s6`%?$EWZGbXaa|J5j;dcWbLgVg`AcgcKR z_`e_jj8y-3V)I({f9ylMx2ykS@87y!{U3Ypwhik4*smOULj526BYFM8|FJ(ldf0*g zV}E$0S^Xc6r+LR#^?&ReSFdtD56iLRudS(cwuEI{m((?=|2s7=T76*MlN53z>^qk(bRLxDHrRJBTd4kzw|D|DQAN$Zv;!9=zANya2 zpH%i^gu_>ZaoW50giJ?j71SJzgm|6|`>D1Q%=^?%t9Rz|7+W8YGorv8t8 zQ$e!&KlaTPC7$=6*S2i%^sD#Y@9CHBzSq->HeBoJUZV!cJcIX|zuVPD&$p)K_Ei73 zXRD+0`6kb3@qcWr2L}JgrvGE(@5k_e>|&gM5&y@Aue<-m%gwU}ws<=9pgUjk^yaQF zdG>$(kr%Atr8-wWZ;kKA!~gO6G4BBWkDV%h3jU7`PYD0#ZumcUm)&y2jtBdnH~vub zvm;J42bJ&h;e1lhu6}ErZ-W2hcKE+PA2`rl7W-$5=acy%^8It`)Hw3I30b^?%_1tmS+I{2v>)5C6wbk^SNS*zvM{CHx;dsZqWUF8wv|Kt6~;}8GGPLrR{#CvYHhWD&2+-03B_rK8DX^r*S;Q#pi zK*RsB;s3_{xz+ZE{~LMd7Hgb;8)E%KAC*f9w$PO7MT|0pkDO9y!fAIR0#B`r;{e`y&%t{2z}m zB-9{q`tG zk>bPP|JWCl^;iGL4jMm1{U3X%tcMN%#}1YC3PUT$Sr1y2E$=5|tb>;1%KOJ?>-fd# z&e8TEcDyM|bDaCiM_AV^%yG8eH`KaxR;rWo;JkN{*R6Q;s4k^ zSuYI!&)x8U>~Qg|nE%HP6Wi^jAe^~#Q z4PT4-f6=m@IOcWY-w*gdc8>T0_&+x0gJJ$3J9ffoUH_LIKVIfx$o#**js9Kz9~$%j z*ikY+3I31ofAE4>|Cf#R!{Gn;ev>M`8~%?SIyp-HAA4+5wE90b{1N8=v9W$8{2zO) z_%QfCcZ;=qf*mj0;s4kP;u8j}e$^WDwWe)+!qb@l$Nk~kF#nJ5-)PMLvlgER|Hu8) z7q$35c82(1v4RJN3Fz=1ZE$D6;JOx zc@X}Ooh5z{{*Rp}9!;Jv6JNA!*v~|MDg+p{VMtN&wT{nslKu8iX6n?jlIdBdiw ztnu&Xx_@77oi6hj<@-z4Y2riW_Z#aBc|LqJ#gDA!>8Y1 z4Ikh3snyo-e=qg9$r}D|-PASKRpOuE|9JeB^7#b*k6kK$8~%^?w@lt&;Q!b)^7j#$ zFYjrYKW~lse=?um8vakdzvgN9KVBcU!~e12E9LiNYyEw8|4wWCek$Luvo4h1|Kb1m z^Tpq1;Q!nW|HsDn|1kg0-SB^G%&+`g-@SJI@T-{r$Ky+thW}$HHH4`DW5ZWH{=ohA zc&1m$ysP#PT4R0P7b+jJPM7B&=Kt~WPpTAuSoMhgyppRz@%IyJY{&dRK3}kYFy{ZU z;RoUW_<1t+^%8C82leQ zRT}gE*qA>L|HsDnUEu%R4gbgE;rhR9%n!^eectxR_L6&EuuiWU?ZE%>`tr(U{aNvU z?Cg?@o%uUnvBvj%;QzQitahaOKXy*-2=#yLy!w&q|JXV5{UZ23cK(D&^?&Tjlk5Mo z@qIh^KX$JCJqiAgjrpnYf9w>wKKMU=o=ABW5g#Tj~h!=$ab2t1S8|x3l|GB$y<8kZ!@)7F)_~W`QX_w|Bnryf%$)I_zCzwHs&+I|FK8P{3!T8cBFU__&>I9^hoEtS+lHT z#>n4W#sBem;8o!N*qr~zhHruYb2t1S8;?iY!%KWTpI9u9C;T6~K&~JDj}7kv|Hp=3 zf&XLU@qqtxH`f1UW4_gQpSCvkhyUaG%FvME&Y+H0+WuHi?y0Ssje{6WSu1%Zm^^Ey>@PB;0!_&e4xf}kEof;jf z{*R68ga2d0+hP76J2B3u^Z(fJqVRw0w5XQ(e>^^{R}BBh&L0=5^Z(fNf9{6=V~-YJ zNK1kLkNJ}B4)l6~o)51t_x^z$xc+b8<#BxO%j5mP-T3$9uNv>4?(Kmc=>2kJo~V2O zGI@V?cZs}zyBmJ`uNv?7?(O*Z;IBGjq<4Mb!1a0qy4uRpK@{okyB z`F@QP%RTpJ%4F|6z&Vq=J$G`IXaDJwygqR1glhGF&;8Ir{oe#>_&@e!nGXp6=Wh5v zHas8v9~)lplP@Z*;rUJ-+S(Ju8^ZrB9^XOd4Wi-y*tk6W->|pZd;H(P;1>TkV~WfN z6#vJbHEn|WKlY-gTJ?YIc@rzu|FOqc7ODT^?Nt_KJ1Jim+VPeZU_*US93gr5riS7&z7`FjnOHO`9BtzBDH<2*N~z_yRCt#>*ecuDSZ*x`# zwf5b+w&?snZh!p2mi2$xkL};5{*V3Sk;m2lvH$j@U;Q8Zy%(QR|HuB|#iw=tAN$3F zkEs7+Kfdb*^?&STO@-?J*mLWu)c>&;PN-A=$1a#M$vHnY*?;rKuDV|E^lPqkc3hKW zy?y1?&VXZy)~n~ucJ6G~+7%7O&h)3#{oi(L@qlwKo38W!9+=ZhJ>a(GmpKpi$?&ru z-?~Bl-}I0c54dCdR`q}EojbOv|6@PCc8&T!_U!C*XYYwr|D1Pvi&uKp7bD)w{eIT( zOc?;@@^^uLFHF3dd;96<%fLX_{!WimJ$-gtZwH^-&$E5_fD1g`?etST-L9SYcmh3O z;C#R?UA)J0Zf9@z>EQK*UE6o?+#dQrKVIvf-(01B4!ykb8h_XIc1AbX5Px9w77n;Q!dYd-qoV$IH|Iu}7TKTm2t?7+z&;NOupWXfZUe1fvt$nHtSj7B4-apJQg#X(<6~4RsYBK@7SpRkNxq{1M2_SUyJvH|8qC| zANxK30jI-fIo2C5Tj)spIN8=kA1^*IUbq+$J^Vm zXsY@@_D=DHuxRWpi)N_*WA9!(OZ^}FzN;3i|6?D#Zn^qD_Tkkl)c>)Y*RE9m$M&zg zR{bA)$J(3J|FMsVzsCGO_Q!{t)&H?SXg=Uz{vZ2|J8sqaf9xYSFH`@=es1G!>i^j9 z?AfROkNv^z2h{(uKfC9M`akyPd-pjXpBZG2_YJb%y?6=h9eFbUL;N52zpE@>{U3Wx zL4x`}_7!p7zo$$sPxidOynf_fPoFsYxTn9pdxxj5x@M-QBcp?yJBGd6EPn%P-u&c! zzKFbj>i^iq)8zZIGXKxIsm1@f8}t9H#mm9}u`z!wtmxI|^5cItKXt)=HSjiur$R_yqVrK7Zhq;Q!cI-%aLI z*#4L&A@eJ&aefE>kNczH|Jb;H@PE8LH2fbQZ=B!6{J%{<|Em5kS$_WTe}BC5i~7HW zsq%f%2d`+}apGt7era-k8vc)s^|$VfUerAMte@3?VEwHd_RP0Vm@Z!Hthv_1N=7(k zi)L9z$oI)(KAUbmJmGwqKRngCcjDPj^oAz8y>n9fIwc=ZZhqyT$JHYaOYNinkH#@TBvD0LISNK0ZUhxgV>i^i8^7DlM)EUdYySC_|EjMFZt^)_e;#T*YMS_3-zaOW$G5momFiI+x>;lga6~>g&x>&iFMw*Wc7c1f6bqtqW+IvJugYt zJ3G(bf6@EK^|OYTxnN}<>jIhQvihxFu8xuQ+Imu^?&SyiQ-Sh|G9hc*|%Eb{6G93pRZ{6KX=3b zvGIP4^?%v1^~2Tw9sBe*^?xyS!_@z=N6Wkq_&>h?jgfgY@PBOjKfa&P|FNTFJ}%b( zW&33Q57z%>C(1ls_&+wDPw;>2T=5C;f9!0TX9@qu&X?ym{2v?his1j)@ILT=>;jn& z_+q@0(=JNml>Ih7T&Zd|kvXS2*f};muyYXm4waZ%TRQh;{BfpZY&u9{=9L z|FPi%;s4lJe-!@D-QugP^JM*W_`d~LwbA+5==Dd3wr-bshVXy9Jmwq1|FQEI#K0R_ z7cA8IVXZB`5dM$*!yCf?vGM%C{69A4SHb_e8~%?CzXkuthM$7}W9QA5`PLoRTf?`- zF4*Gf$}e|V!^O;XH);PYSUyZiL{_=XU#_fGn81CtBJ4adL_4)gg(biahSzce(1@ir=J|T(L z`2B9+*U8rS{RsY#_Yc2s!2hxF^ULj;V=brR)&JRc`TPt2$Hx0R{2v>ix8eWTxIOqk zHlAPbe{A|cz8*OLj}1>X|BeY!{CtFNUp(0wz6$=2+mod+|IgjB z5dM#yApbt5Cohh&&qMNk7WhAQa%GGEV`o;3Q2)oqdajGUUlzsBFCpT!;Q!bW4dc}R zvGM(yWwWl1;^%`*`Tbpff3b$I>v`@CpBJkxy)KHM2dd^LJ9jN!WsUXZ ze|Y(NYxr#VKVH6A){BS#W8?PW|Ja!KUUT$jPs`_*)|THF;Qx64@%uXb9~;LH|L1P_ zKX=3bxf}kEjq8K|b2t1SyF~mm{2v?h31xo1HT@sA!~cozx9#wM`ws55#{C`JbB{Hi zKZly`vc|l)lqc`@H2fd0AN#}qvEjGi|Jd2`{KERbZ1^Gl!~e1Ks>iASb2t1S8$J;JkIx_YK+OMR!v|viAKNG2&w~Hs z=gWwKAv*t$?JFMcJl_3K6hB|4$?tDh)*rUc5RaAh@DXdQ?|RN@Pg-YI%leOnPg&>6 z_l4m9c>P&5VNTd1&sf8M#kYUXIRh=Y^=Y4^?%t};`y-tFB|LgUU&Rsdpz@H{$yeDC)Q)igVg_V{|NEQ@PF*glm5@$ zqbGc2+wuI4e(WFCdGhzK)Q;a+7s=}Z{*TWec)&An{LZ>gzAsbu>G#$(GQSZ1kI&B{ z`M%fpEB|BL(P1C_;Odt7f7~DU7ygf3R5jEY{rxYV{xj~k))wyy|Hs!?k+i%v?e&={ z^XuXN`0qnf&L!&q*jXuq9a;O^wkOA4?7Xq_6zhoaV9(!|!^RHN`G03`FH!#oUx)dB z?#BE-Hs}J`VnmjmHE2kB!@d|6{|e z!2h`${?Fa;e{6V{Rr8ixj~yMX{*T+kLPx6qW5Y8(n0BQdKN|jz_Xl1G^Z(op|Hp<8 zg8yT~2R%7xg*E2=Vg8@pp3Gx||6}LL`mXSQynJC~r20R0fy|?W|8qC|9~-_8{?Fa; ze{A?btpCf-kp1ER*zkJre>@({--G{SS4T#x|8qC|AG<{6>B0Z8i{<#?|9HN)IBJ~w zKQ=re{2%v+|7$#BjU5kKexJ0?m%e@Y&DKTnGLKgLACDjF3&a1pd-0d8U7ir_^jUbT zZ7+>$ng7Szhv&omKQ_GIzk=7<{`7x#{U`k&8^;6x$A%|_|6>=%#;X5g7stn||6^Cg zwD>=EX;ie%|6>=6FMK_Dlf7PxWIo``cUv3lAH)Cg^^Au9V`F_{_&;`bj8E79Wy6M}}V`Dxf{GYoq|BuICCF|+J|FJ7&-X7-vvEc=$`*zypQzAw= zonLKjUxe5HMMru)UZCF#Y^+!9_8ozqFL3|B4)lJ3^Zu~Dvitf28@}4T9rIS*9q9i8 z8}k$0`(wRvcL(ktI1liD%^!>km@gRU|Nd78dcwf{1Lq3{cA)nQ^n-!x|2EZoyzq$2iu^swJL!DC>PeH- z|Ly!oC-r~zQ>HklJY3{|?uO3l{Te4XssCe7p46!Rk3D0;Wc7dSnG+jz{vWTeY4T*9 z|Hoc1Z=U);?!WBvMe6_9+qZ61|Hr;Z)~kg7`&USd|GV#w?dt#7ciyp8{U7_@dv@vk zKlXzU+^hbN{nV3()c>(x5kG|Wf7$Q8_`Lc*_S-KUQ~$?)MZDl`1JZ2&PxowA|7Y99 zvta%o`+@ll>i^iAYO>V-u@mbvoYl2SwtrYrwDX_siPmKWvc8Y_zuxb3Q6E^67q9-0 zJv}eS>G4jAe|pea{?4a7@7uU!k@~-1?&_)jZ|k+!s{dmj+_T5|H8b7MUcary|Lvd9 zOXmaLx_OiOKlY+qSE*-W2g$!j2QEzYvqui}&gbjjTVCES&*wX%t*7zs>)x)s&$a*g z=XvJ?o)RzXExERL&cgYL*7<(JMtJ9&o(k^g+TNy38&98diq{8rJk`7X%=X^-fq}jc ze$RdVf!*cw_Uiwfn<~}+q2I4x>Hp?Lx%#@!r=9M6@#YHun^Vio1E$8dcK^Qpbp2m$ z@7n)-^?&TM2K3kYf9%oy2dMvJ59)cg`agE}?%mb@vAcHds{W6CR*%lk#4XG0c>12( z%Xz+iYoF7vr}{r0e}|53)&KGS_3qSG*Z=L=zgpM-oj$%o{a@**NcDgZHBEBviYW85 zzu9@4QyWogec#SaPTz-~4_aNYQcMExK8*XTryMrAA7fK$NWF`-uaW&|FL&YtycfX-X@+A>;JMJ zka>mhf9!`>T%rDt{m3;-)&H@NUU!B1KlZB|ZczWnesRre^?&T=Z@gapAN$4i+tmND zU)y@S`akw+nNJD-$Hz0FAWQupduw5ov%1e9+kQu7qWV8xerrLr`akxvu!}wKFLO$~ z^OQe+@@dcZ6VJTj{5kf+=EK+hsh;ok^|yJpUpq0^nYQ9R+desYr20SZpI$Op{U5tr zd_vj7Z#KWS?GN>P@O7_Myy5B8(_XhO6Yq88-oIH_$o}wuyga-g{2v=05cB`o72@aM z|Lpcp`ad?#zrg>o)x(MZW9K!s_&;|3lotQTE}s(PG{rq-w^!B_?ZE%>_TdQ!9yr`A zelX-UV ze{9@8_&+x8AN(I1=a(@5j}5;D|HsY|e+U1^&XV<-;Q!e0A@F}}tS<%s$Hw|j@PF=x z|6^xQ3e)+2?uP$k_&+}0*#BtqmCg5G zdtAL=sysh-E?(ArbnDOR>u^34{_l+kep3HeEay89zqO?KtEYcd?}z6v{2v?ZtHS@W zW2VHa|6>o9^CR$o?Bw(T>i^ijxPI#Y*d5}!tN-KecTMS|{*T8uBIN@0e?0z>^o!L0 zvBzdzqU-i^iWWg+VS z*a_nO!mo&F=KYJ6`?LFK+ndoh<8JJ@LWV=H{DzRSy+ZJD*grjkM|er^DZnNWKI9a=O?^O zul*O<^A+8${e{*zfBR$cdDa!Op75u8`dSx>cX{=i^j3a{Tar>@+!k_&;{4 zcm?=Bc8aXu2>-{9lKtWT*gm;F_&;`xygy+6A0Pi{@#FA+>?Ha33I31m6R!>b$Hx2> z_&;~U|FQA>hyP=zo%Da~)XAgN|FJWs$oX0Ef9%on{)Y8`*<;0*Vf|lrqWCcQKX&Yl zIGz8;=QI2c{2x0}&R@g-v7_bv9R80Tank>>alDxS$LD)$?QpCQe(>ene^Ku|v@Tfv zA3Ip)2g*FWgM9zM~uN*jro7<@TRd&=G@?ed_O{qpRvpVhjcVW|2)+ke6^_&eL4FaQ3F&pTk3mw7*!|Hm$o_0lo_kMGyvv6#p2IM3ew zLo@teY@fF3|JWh&>o5Et_a7W`y81s}-<%~m>i^h@_&+v$ALjqDu|6{VpS$7z+`Zt_`H{STSikwb zcb8h@`hJUBVVx)Q(faIN)!O3C;Qx4i@TBm6Y^*N{|HqDRke|2sKX#bRJBI&bN6iXX z|Hn?1&qMHk>`b}+&Oh(B+pn6Js{W71Up+rf{U1A1JUQ0?<>d?H`2qjOE}5UB{*RqE zGfn*;FP|))5&n;zD8~c;$NlO5*z|wwY*|ke>;Lldneu&z1)u(6jqgXSPyf>z>j}gE z@$z{8g8yS<9^r3sr$_Pn#?B0PR{qk#I#T={{2%wn{5<$Sc82_W2LH!~Ux)u=`4%A8XgCdA1!r>d^vEA8jhO#`k}6FD&!) zCvQ|(sawT@PFKn`MvOe>{Ri9nE%Jlstk5!Zde+{ z&nxL=!_@z=@%!vC?0<^2r)k6kUVXZgHgjrWfgb8oc9=fPK>y~!Fs|9n@S$oyh! z{C@Of(^@-Te7{eAf3*8sEbmA1`=vG3x0c^Ot+5`k{C;YU^@HL6`1ryP!vDD&{*R6M z_wax2hW}&Z?<<)9$Hw0e;Q!e8eH;Fd4Ic>q$1WCs4gcqE_&+x0XT$%w8~%@7BJ$;s4n1fSCWs#`?IJ|HsDqxS0RP#^Z5RsYA%llk`Wf9{6=V~-QhiTQu*NSOzS^?%uzR|x;-ZumcT z=J*!>$IhM*rT&jySbB;2KXyjWx$6JexjE;n|KsDCnbBAMA3G$wuXEvsPwnxIt{CKe z^N-K0!^BHIGVTlOsPWT&9fdAw3FGuFN!~e1KYr~x7BYv{R`o-{ne17Bg1OLa)uMBbE|E%Tt zCjV`nSJvYH`1(yQ4RK^vr;qK+2~z*Ze@{}`G0I&ALjqDas2RqY;1@B z5|Jd+;SpSy|UjqNfjt>b{|L1P3|I3Cix!|HD*6=8$$(LEfXTtxL{#2s#NO1e` ze{B4G;Q!co{NVrC@P6=rY+OJ5A3IX!jm^Jgx!oSttL^z%Ys34%|M7S+{|o+)jrn%) zf9{6=V`KeP_&+w*V}<`?!w)|2($)5OV}0N3>J`>l&lUcU`{VX7|Igj z{GYqw|JaxZ2mi;0_k#apXNf;sKIeMt+<5suTKgNU8{!h3gBx2L9uWSIk8i2?M)*H= ziOfTT|Ks^x%tw3Y?>E_YJihRM+#l-`!~gMk;K|_s*qQM$>i^hT39;(`*z|wyhW~Rn z{2x10{M#d)*0#3z$h>W>4G#$a$Nh2rnE&T)tpCf#{66?UcfH+-h5zI0wb&P?{*SFcfAN3rhW}&31H%8g8}t9z^nYy5|6{|K zV*a1IvHmX`^AF+w*u^oiy8bWk@8mdH-$(o(yFt7u{2v>~2mi;*h=zS z{tvG=_x3>F7wG>2J>UPD-xs)lp#Mt_m%qokyhqYF@4UTnW4zn(e&pUiaJ}Hb&I<5; zfsOUt-PZ@t?(RT;7}$Zw2QTfue4q~u^nU-V@qX>TzQFZ^1HE5h&nox&zIo!w+}GDo zSLEscGY_!A>-(C-<3MkNJP@hW}$@fB3)1A5K^Qhlc-S&ukp;%#vAM?#`<#wZ?kI@PAVqPS^Q> zX!t+&{H7Z9e{9S@g#TktuPSiv-Cb*U!Fe-hB0c-2bYj zm#hC{@7%UU{U7_m9k;3f%bV3%=l|`$W0(3r_MN+Ts{do(yLXTJKkI#a)&H@Ni1+I; zDAUh=?nul0KlbxS52^oSzx>n@^?&RaWjp*I`-LYSQUAw&aOW2Ff9wMrZdCur-n3x4 zv#Dc>e`D_!&$o1ZiuylpuTLJL{*Qguh||^oasMd!{u<{0u`wTVNPL3z)mL1m{x9m| z9xeXwx)tjG*bm;eS^XdT?%P_{|NUcAPxXJd-Fm(HKlZ8xwd()a6{+(5xraY2Lm_-YwkkAK2>dxR_{9S7j!6Ixp7i&qoe9*R#D7_@3+EgHtd* z@Gtt*wqF0&K4AUe4jsJn{Q}ny4xA6zw__*uf7jMknEwl{yw=a|)b2EA#LL(CZ+^W@ zJz)D&+dA-nTN6sv172{_|FH-5?}z!={tI3z*3ajcUVI+DKV$7X{}Oz^#(GGn?)dy| z-C4Y$d_MQIe15ma`o!}2-nvJR9_s&i`+fTMaE8xbYRA{^bVvOk@6YhgE$jbw9~GhA zZ_kR$)c>)YuV1SEkNvmpx2peR-!Jnh;s4mj9@?k=kNy6`532wBv+)uf2Aa`akxR8u|A_=KryCswb)cW0y{vss4{WwPBw6Klb#A3)KIy z>nAU8PJ1lXk2P=M`6f(R?0j?}#kyKN^drs5*3rpn>i@WZxP1P{`oHWjU(5VIc7iWX z{okRN$EyEJPfS(+$4<=1Q2)nH$<9{)$4<|d_2b`&w(Cb{z3sEEmU(rU|Hs=ypZFlM zwZ#X*|8e{HniBPY>=l!1)&H?Ee-Qu8zIA53`akyCS>x6Jv3JONi^jHEMKJlkNuF$BYdgd2)n(5*I%aokJ}$x zxlsKd`{1f8)c>&`U%5p6AA8^YN$UUjc;8f-rv8t;tx|lq_&@f#!UX5ba|c>qoi$4R zAFpr5xbr>lS8K+Xdiuoc&wBgA57httHu4Yke>-H}Wa!85H?vd964n2)$EJ=}|HmFF zzU9L=-nRXtPWr#} zY+N7wpSw>>ebz1y&$Z+~$E@MKe%ko7b%}VtunA8#i{Vh;haS=Gs5Nd6{*T*nd+>kq zH#GHs@PY7uZ1_O&N^*cft{2x0*=0U>$v9W&b>rd?T^cfR(SmW`I>Au|>KM(OG)|jWUchXi* zf7WA*HGbakfBgC3`2hdN#`72ckDc2n&nNMJ>^$+1@PF)bnSTTS$F7+bul|o+Hz!f& z|FLmC6aLTL@PBNa|H1mde7={+`AV$+%f|Uj_&+wzC&K@^8~%^ihwVe}ySn*7-!JOF z(C~i^;XkYY!}(G8zx~-issF?LOZdMt8h%v&S0z3N{;zD&59l?xUv6HF?tN&xilnzk;$Lk+dda3$9c2N0X=lHA?JDwr({rb8W6Rk(e z-{)VsB;I;hxvV$#Y_$D6hm?+%^G{LMVd4c}SsLzX_&@&qhsgPYy6Z>V;}s<5*IxW) zr1fZ-*S7fIBW(Xf@iY@NhFN1?P~M)w*6=k)>x1m^s+IGlBMuC-t``3>@ty(p_+Wlt zp>vU^;s5yj#di2VHoPDFpS$7z*zkUb(t26LL)^Q$yQks*xPQ$;nO7+Oj}2c4|Hn?5 zA1~|8wYTF-6JLY*fBbotE=pGa$1Yizr2dZ$k0bwm(B1HVY^*m2|L1P_KX%H3SoMGG zRC#>i|JYbR5&nr}Ux5E(pUm%e{8Iu3jfE3|AGHwW4_c42R9t#>l2Ojf7v-R!_@z=vuBKTV)IuX z3y$oB`VF9-j}=K8UE2a&-OQ zS%X@9UHP00__hc!SL*$;j!9v}EWHa>5_|FNT{ zj#2-|j+gbAG5?R9DC-Nu|FM(g=K=r6+pn3Gp#G0tA@g)G|BqcR^K#(-c=;xo#|8gq zEglf_|JdWj3u66WHhd1&|7B;&d{_8CcF9aRzajJg*oD)4cs|(epg zI;PiI*6{JNzP+d6|9Ja&e!~B`d-hlTtl{_I|F|9f%9ac5c(Ud8YO*f2#`>!FJwDL( zFOlPoo)+Y3_&;7B-tXc6-2L6Ek=A&>hyUYtH2fbs>!kli@+>+SK!<>CMM{GtD2)Bmxt{v`Y#8}rvsUo|6&@0XZ2b$0k{>%xXH z>i@Vstp@&kfo+HHga6}pH2j~t;s4m_;`!kJ_<1FzY^eG__E_;G-#xoLik}D2@PF)a z@_ii4|8qC|9~<-6o?muN6h9xJ<@*8F$z{Rn|F}K1B1HWk8}sGh|JYc66#mazzTXA^ z$Hw=&;Q!c|&kp~`#_wzJf9xW8{@i!;R%>{_-+HaH#{MgMZLs@;`R?+42N}zpu&PH#`mh$L9yU8vLKT;s4l0m7{e2AG=VVAMk(djH;IPfBEywtRAWU zkB!e)@PBOhLd^f;=Tm(D1pbeW_3h#R_<0le5A*-nIW@uR|Jd|@>`b{m_&;`bMX35e zc21?NFZ;_e+nz3;ACpp^wZ{CwZX2Jo#^=BHzkc32OXh{|4u8=a>+{ZB^^&LI|9F3J z{P2Hl{CqI~kB#q#!2hv}WxZhdKQ`_k{2x0@eqQi@Z1^8{`~{%1>BqXck4@YFLZvp^%Lu% zg#(<#&p)+}DjMe8H0pEfI61!t|Htdc=YRM=c9uMz@PBNbe<}Wtjro9kU;3wYvD`oS zKi=OG`TN|gynk6&)s0sF$LC+AtUmz%$A)Kx|8w_?%YU{mm-U`|zjfTYRG$Cx+_&dH z<^#h2@%2zxDStnC_YZr$W|hl)%n>K7Q;THY+-r`Hum9A{q0aA@wXu$hy-@uh|2>Kh z8>;?~9X@K1{Pxf~pCe^Nkovz}g+(p?Z{!g5f9%N7L)8DVePf2H|6^y49`5wtQ}4Uv zqXPANX>$3B7sgv-{lj(NH(0};!T<5{n2!hl$IHXJ!T-7Yhdxtme{6^Ub8mOV-Y|P8>Z}{U47Xmxupj=gK@P_&+v$4Cep2 z8~%@t%ftV<8~%@t0Qh97DBerv<4Y@fQ+w&U_qZI)TX&%AeYYhyiU z_&>Wn@o4aWZ1^DfKQ=tkZ9gx!$0L7SloNT)mDYt3(aw8)uCm7d^Y3nL_#^l~ULWTB z!T<5`rvGE-Mue;X>An{K$HscG zFU`BjE|2>Q|Htb`!~d}}qhr@bkJkhIA3Ja!-~Vs_FAw;?{9m9S4D8%+ zOq6Q<_XhJ$-HrF3zv@8GmnrL^yZ6WY=U+AE)4I3g{oLJ{_v-FIABgu`_jdT}ziN1M z_x6}kLp&WTUfsPtWtjZE()IWx1O<6|%+SB?>dHFL{&h7Co`%nJUw>f3^SQSN_C%TY z=ic5R^Xr!GsrUc4Q;T1#sxNmw{kG1!TINf^|J^dFz0L73?*EZ?-_cdoS=h&qNH5ZnqV(QELP$vOz4zV|LhrqI zLF}TUf{IG9fP#tzNkr69$KJ*=>dffq=-BJ1GxF|dU!I+F@~$$T71_zx0l@V zx%=nyf3h^|!LVUj5&qaG(FXWXTfs zfA4(QS^eL<70cBBu@|mh=^XfLK{I>V>Q&C#UkjT5F{g{p2VA~pwfeuz?miE=bmc1b zf9z$eR;&Nx{ySyfAN(JC*Q!;{*yxtNWb=9_byJRQKe*rL|9E^SZr`u|@5J%0>i?SV zzDxZd`{=y~)c>&`ICi)CKlai4?p6QCe&o>;&ZY~qnlCQwrt|bpi6?4Tm}%W~x>@}n z_dg>(FyfQ6X7(Rs-WdEJ``I(6)c>(xdhU$+KlYnXH>v+)KlR`do&U!^x$i3Vf9zfJ zs&)Nep1;85mFoZ4{!7Z#|FP>Ti`DbMwxApb;Kg`E1xhS(a{*^xJ`!LV< zw(Jb+8FBJ`Igsef80MWdb0XIc6my$`ad3jUGO;df9#B5y*-cTsBYeQdGWov zd$vyq^gcgj%e+hX^FeufqNj)T^v)aX*w*U{l^eRA?^^r6*52>@^8o}~{(j*54tIC# z*wNFNpXc5_s!Mn0$gW+@y@F(h=#>Mbhqmvm{*T?KLp%9A;!@k*L*@;_|ApOEs{RkB zzcr+#ar#G(Y;SJ3s6;(re;H^9|M%&^BK3a*+O}8!#~yor8})ze(ZU(w|JdE-_~8HC z4gbf+>BIlAF&`20|9JXC<@n(L*u&)N4tuk_xv*`hdc4T~U7g);m06#-YOC|bpGvJ? z+;_9C|I7Vf*n5+%|I2=OuW$Wd_G=G6tn2@>-)wGD|Hpp&$i^i)^^4X21${AH{a;PP z67_%V$_AhRW5=dsssCf=2KuT0V<(Lpsq_EXg%c;M|GV&wVD*0$@_M4+&e&#lXk?=E z%*(OO+&?x^*7JKU#yT)FSN$Ki2W980|6|9=dhzgo?3BuK^?&Rb`TGq2$Bvc1=UA(j zjlaj3UB|AOQK|lqy}Y4J{U3W}V}<%Z_6;*D)c>(>UD%-hkA2hfx$6Je2RE-&|Hpo8 z%Ubn+?E6iz2CR*zNh|=yk4!zUVB%i6N-z$^jm(Pc-u|Bc`L)~@PBMv|L}ioT>tQY?uP$!H~gQqd>;Y- z$J@6+{F{9LV%u^5l<#M(;s2UW-(U^@CG#DuYvlW8S^vqpVQG^3KOTSG;so`7>};9$ z1^>s!_to%!Y|Oia|Kt4;^BUm)*m!)v|G69fkB#dC{*T9perL+|rjWKjsh2~;{|)@& z2lanAzL(B!YKj=}y?Vd8g|X`Y*fV8b7yRE#e&4D8OO@|;;s4li^7zC2KX%BhX!U>W zQR43~|BoG)I#B%|J38q?^?&T~@dMQV-P7g=^@wQrKc3%!#0%B`@$v+T2ZaA)hh~gW z|HsEeWX>4%f9#~faq9ordGdY8p2L;)_{nVa`9I!YO6B`F%>U!{87sHPC5MXa_MSc? zQ2bTCH9jw|&d;^ZE*`D^kH?oP^G|jSOt;g^kM}jvBT#l zssB6t5l9g!`IpJlt>fk=sQ=^j6)`hP{U1ADo*#lz zr`Y~wvcBg2!;`GB{$`gB6RgYECp(et#x?Q$%vhb~EdG78o!{!Em!ZQ{@$pb2x8GZ7J#2fW z%+Gu3)^65SGOzRa_noaH#n-|A@%+V#zk~l{&zAXtSpV1ESpSz@yw*4W&)x8U?EJMU z>i^ie;s@dX*qGmi`G4+)|Ff3s>y3-wv&Q<5@PE92!Qa9EvGc?$!vC=|WIa6iKQ`tQ z!vC=`zYz2P*qN(R)c>*5#HYaju`}iTWB#AJKPbBM6z{KizBtkOR_jukCkg+@?P&Nv zcCmP(xqGiT#rspC%*%rRV`F|P{2v?Zm;3Kody4m8_-yz;cfR{zKCfwI0D z{2v?s0rUUZAu^8x{*R|Wvf5w$AGeQ^^_b=R`^Wiw9bN15f9%+LpZ{Y=)(5NqV`IH& z%>QEt$okCif9@8)caqP~PF0HfKkLyw?%(PM z@%I=0kDawNR{Y#~5p4J;@mQXQ|7(8lKk5PDd*T1w4gbf+{65V8W9P5+&HrOBlJ%A0 z|Jd`zx559h>HpYV|Cik$`@{e7{ML&ng#Tm1GsFM68~%@t^@4-@UE^t)r)Zro^E%=G zczStqdhma2TtArq$Hwy){2x1Yd5-hdWykIKCKLrYdE+0B;QNR4pia(`%OAInlaHTw ze{O(z9QjbXWLCLS{GFWi^qE1dft)@o&U$nmm{Z-`G4%(6}jsFc>XYd z5dM!{DzDGr|F}Q=75pC?{_35Vf41|NAyyugC{Sru8{eb@P9nMT=A4L-`2M0$@Axxf9hvlD);B1I|o>o%e>k9LNBte zmgo2AF9usz%6hrt?<4tm!F)cM&ub0e{jD>`_Q&aOK0eOVJ?kf0r-_f+-`CF?9x&h! z{?-N3Pp%B~bl&)2>ooC;AH5f19WC!4ms}ohoib~xbAD8mHQvwc{wBs6?|(+#9&e5J zKM&?5Sz~^8Lc3H?zi}en8vYahkJmR|pTqyLarxo@+}&?oksZEByw<_VrPjsr`XlHs z<<>a-Ggnu6x+t#JI!E@0|Kt4w4gbf^7B7qWf9xcgpN92+*;r2%{*Rp|^Sa>wc>Ctc z{9E`xc7DTD^?z*oKQ{dzJ4*iE!2hxF_hxq7#z?+CfuDl^W5WYt{a-fbW5fUP^#U6H zj~y!W!{Gni4gbeZknQk)e7%5%|6`|@`uv}}G5?R9Eglj6kDXpL4zD*N`S>=5eq1 z>PqX(it)~-=&P*@tH(OKuDQm#qR|h3kF4?fV}H^?R1B{!!#~SOQ%j+TQ zh9z;%pL*PEUAr*a8D78F8pkK^Z|(X(%lltzykC^}$DW4&f*!Jc>lQd=v~%0{AF$LvBq}zKb{^M{*Mh02>-{%=Na;P(#|h_UkLxl+dErc zzrg>o;Wy#`*jOJJ{*R6OEBqfjMdstd|FPkhWPJte%rgDGi*;&wpw9o}?FCPV`G0Jz zCk+3`POp*mdBy+n{)5L4{2v?M4*rj?Kj8=A|JZ5b;jsQM8{7Xe`b;EW@4+($E`Q3p zKu&MN(@%RE{*Q-;4}|}7H~b$P^9|wu*eP;(;Q!e8y$JjtJG)NS9~b|}%R~RiF2;Hg z;{VtUGCvglk6kUt2mi;;lk*S%$Ih1ditvBz;_`9o|J;rFf9xFb!tj4Qe;G309{!J= zE%WnVEPmgvpPbSFr~ly(tl@>>|9Ji4`2+rs9aS<>{U19xXQcW+c0$2u^?&Yuf6FI! z__(qu&e+#KwN9xClJyEcv&Q|QY0>A_@R#s^JpUzfe_uJ|D^JHQ{Mve!c*yk!zP0P4 zp(;@3oquOtAs!O`kM~bB{2#kqys7-((_#g!;Q?iqpmj-kfFo-M+v5ZCCE@?<@hkTa z_&@$V2(E}w|HmGcHbMO#{~qN=`TQR{C1|A1|6`|5o#dQ%SKBCdR?rk@MnOAk_zcYd zo9$nyJ`j!he{8J32>ZxB|FPly;Q!e0De!;p!(;tlHV%*Vf7zJF1pnvm zNm28y;oBPP7g*E(@$}#e;s4n1Z}5NYBJm;cf9yh;*9ZT{&h!sb|L1PZ|Ks_|o9gp_ z?EJuK>i^hSe-i%B-SB^GtXB#D$Ih1df$)E9Tpsv8Hhc;E9~<+f;Q!dTzTyAe4gcqE z_&+w*+l2pPmz=;&;RlI$PNls|HsY?iBSK?rvGEp|MB=a|Bu`0 z|Ja2x4-oVJxIa7<=KrzFWj$EwukEe%*|6}9unE%K9 z;lnWhkB#$#`G4%vs3`S+>>^p882*o4DD(Sv=U!!vjA_6@%k4{46@w(wNuj_71J*|6!h_dwc6{?f+Ug9-r>Rx9-;a zx9);)ukXum5YkhkEtCJ>sJ$~%C5uVeVGY&Id%p|FLJ!nduzdRciask@YU0 zd9}oPg?PVDFKp@MGi#lWmBqGwaaF0V|I72UKztwO|MBvamldo3V^@@yIK?ZAnt6Rx zRF*mLf9#stD(9v53Y+i!bI0b-N1u*roI6|n-_#AAbpGFhrHj@7ogC)#e{)wZSO3SJ zw`zs@KlY+k%bXn}3YytV)~s-D2`gyse5A8_z@@8JI;Yp>d-~&3dDh#-7sCH>|DECs z;s4m%H*Zw`$3C$CR-ONMO;#73H%R|C;JYp!|Hr=X$U*ggZ2CX;G4X)MWj#;!qmLd} z|F?g4SM`5Qk3OLOkNw2Shn!1xXEd``Ht8BwLQ=4`8tS?bMN1}Tl>Fu?XZAwiwDH~Ja=Qg-){$B-kfu7xvqEX z*Rg~8zneSCn&IOACUU*(z zvz=dfO8CE{?LyT5m5m>z{*V3qjl0$Vv7fu+R`q}EGy85-|Hp2Y`IA4rS7gWc-s2Cd z|Ks+zPCu^xkNv{K$JPI_AGl+$`akw^nKyg?-*WBv(#osV|8aZC?D^{d*flekssCfw z&RVYik3DO)Z~b3)WBp%tapOYue^}EN^Z(G8|HqzN->CEd*f}Zb>i^jIeHG^au}2Lb ztp1N3IBcZ)zXfjxssD?cGFAN_dz4>@`akYJ#y?E`AG>d0xcWc#$hb81f9&|IEcJiv ztkP2Tf9%|fV)cLShW}%iR#mG1V^`GHsQ+UxsH#%`$DUtVss4|R*8`aU$Hwc0rXQwR zubEk?{*T+QUcXfRAN$U2>(u|TuUkG}{U3YB+*}zG7Am;zEZ&|-e{U3YZI-mbz z?^#@`{*S%BI9mN5`?@lp|Kshkw>CxnAN%TxMD>5{RSA>T|FIWD4pINd<2!TB63_F^ zpYFKP(`Vm*UH#vzO~0!D`{eD{)&H^adja@AcAM~a>i^gS@-9;U#~zV;vHCyxj#&L) zVBKW(e{6jI3IE3~m?QJd#s9JKc`*E+yLZidrD^Zxf2sGw=gIJY?uP$!H~b$D4=)A( z$1aiiW$=IO0+~+;|Hn>|?~~yF*s0>l;!Ztn$Dbzt?2-GiyEs`9C(!Kl~pX zpQpqB$!Bcp|8Rcb|Jc|L|Hm$u`F`+!>=N;h@PF)N@n!ITY@9#%KQ??C{2v=W4gQa< z-*1Wk-{%db99Y|Jx&|6}9&k@*VNxPIXO zxIJCg--7>RXUO-t@PBOF{_uZntd9%-$F7oj3pHo1_4Ez%ud&AWJueNo+8W;n!T<68 zjqjVW{x2KfM`Qh8HttU+Q!exL@$WCS#`V|t;+=N|is z`Z}C{_`gLje5?Ks>krQh-q;lL@i*%I(C~k3%!7gdV<(;Sf9&X)G3x)=qcg{-|6@lb z4O0Kdjz}2bydAK>PJguY!nO14{EZh60{{2&-tW~bPD~xD{*RYuQra-}f9$Z#k?Q~W zc!LhA3I0Z zTZR8)XVm(u|6_;9=kf4=JiQose8K;*Q|0*q^Z(r4eSTciEjRzD-VeS-=HJ-u3Eu+$ z$IFlJui^jP4gbf6pThhlu_XPqPSN#OsufAQi_^?&T@)v?a9hOxH2 zUi`>k&Wy6gysHn2M%v}UyuQvehuif7&jlc0v{?Fa;e{A?0_&;`<_z3tvHZK1^ ze(q(B`A_hF+>XZ|{2v?hvf%&Nod3s8Uz4Q%kKM37OZ^|ac1^l7>V~tYc>9*FPr*C| zPrv=m57s5?lAYuGzP5%Jye#!|YxtiTKYwgpB)%s4&JV4z9rOQqdhkK;f9{6=W8?7f zf9zcGhwy*yhW}&dtcu3pqf@;9<*kwVF;Nd%XRnHr^`MVhW1eCA19w@&1Hu3C@M!oy zHqJl%9~<+{;Q!dU%Y6Qi_xHTzkJ|Hn?KpRWFo9U|*(WBwmIB5$<%KR$n=G5?PpUNlzypS$7z*po`esQ+V6 zDfjt5Hs<@m|FMJQ`(gM$p8kXyKlOjyj`h6Z|M>hJCO+fZZdX6f=htxY8RE08;Wd5= z&azIB@7rZwpLOZX1o*s@JbZ4od>$_Tj~$vd75iIvABo?)Ir5zD`+G6E--Xy7=IsO4 z1N(MY|HtipdvsR+$Mf%uZKwW^JtSj1Zr^a;e&MrHoIey_YaKEpQJ#MeTSv<45BNX6 zzKa%5CG(`id3<<&SpLGt*6@I`uQleOoek&^!Tk$Y#>za!p4N5Z;hs7>$QsXYa{EW{ z_Q3Po&KIWGcC0`CML?MK9Cl=D(HrZ}&9(ACHgz&)x8UY|Il}`j5TVm2&>z|9Ji|4-x*4 zjpKv=V`nWdQUAx|>k&Lq{U6^y43PJyr}l~6)c>(FE8^AvvGMvJ{*PTD^NKP5kLRy(MW*^ccHNRx^?%$S&oA(QY}`NK z|9Jk>S4OM2hW~Rn{2%wH|8qC| z9~<+n;s4wX|Hp>!hyP<^{vZ6GwcOv~|Jd;|Ukv__4ZjWl$4;FcqW+JK*Z1&$?uP$k zmS|{{*R681OAVPN5lWQ8~%@t!^8ivu|NEuyW#)X z`O9O}|FQA<1^$nnF25gx|6^y0|NH6B^IL8|Y4|_ho|sPs|Hsah^)|8oFFT{bxBf31 zeg*UY*r8RE)&H?0>jKpO@%2zlU7-3ucBFXqQOh<*^7RGQQ-%L?H~b$vS-c?pA3I5W z;3mIIBKi6N+u{G%*be{4hUcjox69MT|JoJF*AtizSd)6Wr{Vv&9sUdckDV-j2>y?a z^@!pB*ojqB)c>*Jd*J`rIgK*kXUFx{nD774yEj;8$-MX{Cf;aWz1ZjfczMd_N2&i~ z7s~Hj=03d7E+4$9yuPx=?+cyE+dM7rpY8g@c6onojrYs){=22+?nZ$J1#_&+w* zw}$_7H~b$P?=Rv1+ztQ7E|$lee7<0(S19kF;Qx4g!vn(qvGZgeGyESL@2}wh*zm6K ze{9bGW2egRDd7LuX);e4{?FZ*|HsDt6YKx-`sVt-?C5j;j~#Q)|MB)t6<-Jc=Wh5v zzJ7s+h5ut?z99S`JEJOC{U2ZN!5_l^u`&M;{?Fa;e>^-cAN(IXNjx0<9~<*F;s4wX z|Hp=x#QMKH|CkRA|Hsa%pQ`i!*qCPr|HsC9&hUTiqWU29e{B3d82*o)Q#(cdA3I-u z?}GV%>>Qbo4gbf+cKAP@-vYUP;s4nA;veDvc>Uyw_k{mrj9tpd;{zE7WVkk z)BCHwvc|l>3r>Gymlyp`&+n`;|8IB74|aW_<-Th7=Zc!C>i>BEEtmTr{2v?h7vcZd z1>y_g|M>X8`p;#tzgri}{Q>@ue-E;1WxdSx=UInkPH~#Yx3SKT_t*J<{CkxY?DKzY ztY--S$8Np;BGzlXx3)Iw*q%J~edtfO)mdXc6Z{{yV?Go7A3H8!n)*L>tbd^MTCbV5 zJu<*I|Bu@-j|ubt+ztOXrE7uuL+lU#$HqJ+_&+v0;QpNpJ^kL%Mb_|tecxE@>8xLt zSmW?J2QRb6@nij8_wmF3v9aDS=Kr}H^Z(op|Hp0y0W_&;`m_&xYP?vM3%;s4n1eei#5_%qD^V;6~k zga2a}iuZ#5V`IHt_&;~U|FLm-;s4n1cQyO2w(|#n_WR^(ta1MKKH=?<+-q$+F3+Dn za+g>Iu%)x*@}6F}$F{@g z!T;IyE&dSxk6kR=G5?QU5*?%dkB#|-@PF+5=xFtSZ2CWTUbt`m9~<5j{*R4$l<Buk!)x>#EiNv1c^Ys{dopuCH|( z&X(E!SU-1rLQBt@*`WT9`!8HDSN$J*&b%4w|JXBT)~NquFFoh~*o)5jKc4@FiZbV? zsl|5r<~7u*|KsJKHEWjoKlbX?tDPU;Eo%PZbVv1m^VY9X|Hodiah>|VeRZ95{@=(&3US8d&({*S#{=JUb-xf}j((pR0-|83l`R{fv5;s4lI%6hc$f9&hFZ&m-tzUi^iy2YmDY*82PW-_!RT()oYv(dvlG<+v5OMJ)&H>z;zOO2!&2?=$q6w| zo5B?9@DTZZpZLF3@Ag*z7c778-H+$AT(2j_>mm2{0o}WLy7j!i*7N+j$UHsw;ahiG znP=zT-ntzCH<$Nw^aNV`UoYv$Ph8&ocwL!#KQ#Ow`$CzYhxvaa-YZf6H?Vzs=aOG{ zHt)(U_O0*Rxt;Up`j&>bga7094jnq^{6BZY|NZb>q541g!=3|L8lG?2)@`=EOXqIR zJ6~_L?tVc}C%mks`*gd&x$T)Pw!QBK-JP}pEq&1iot&BbHrw_-?ay;o{vEMs*qxwJgV+U?i|Hpplwwu-ev0o7%i1mM?riSSH z!CyY{xUT=pepuG`J@i3AGxuM;b(8u(_PV(<)&H><*HozgV>i^zR{zJI)#&qo?7SI^ z)c>&yW-d|x$F6Q%s`LNY@Pd9P(wbq`;QjJu`1~I`CcjesAA5FwiTXcwV@{#^KlY5k z5cPlTs!0Lr|JV`!Q=NX#$J^U#5!$(h6|Hp1KX0rM}_W5J|)c>*j zkD8?Z&)sKb{a<#;@UiOu*h?egbp9VZJ~vzaA3LcaPyHXeJU>_cAG<6sNBti=KR-kL zAG^3XNBtkWvNTuyAA3e^srobGFk6g*8gR1 z2%Dh(kG(Qwyw3Y$|MmE_p68>_pFHL1vwwL{{onqvzo`Fv_2p;P|FOeEW&IQJf9!rC z?bZLWL*)0k2PeO4+wu7&=Kmd!`Iq{?eEGbu?4h@;@%b$LAGgC_!T+%_uMhsu-SB_c zPW)N@ANGg;b2t1S8=h(5oENO&of`Z8(YjdH*R5=R&N^>axRXEYS!;Y>l-BzX)>w}g z{*T8WE8ic%|J|POlls2|Ilq|y$HwV@JMoDo`Hii5KYZQ||HsDqV(@?L;zcp)|JYa` z7XFWo&-)*L|B)v7%uanzy7aMK4_hb8=l_R7PFQ2TU-&;Bp6mazarwG^aoo1!`?528 zj#*=#;L3#iJq`cI%ZJ0m|G69fkB!rV|8qC|9~=Gx{*R6C zMfg8<{?d4z|HsDnC-8snhW}$@-Xi=T8}k_9|Jazf2>-{%`bF@6Y^)y)|L1P_KQ?ZE zS>MU7KivM}S3C{>$Nk|!;s4m!AO6qXZJ)l<8om+!kM~D-EcicmsoWpn|J?oIqD$@Y zIR4-^JM8{~^Lw)Ywx-=PzE$sszBzqM)14c>QSXQI_v_|OO%Lw*TD>2>Uxfc-XUX*m z|Hn?2hW}$n$mhS9|HmFxAEN$`-8F5f`akycgbUUGu|t!5{*ULUhs+0r|Ks`XmpxSd z-`0%p)c^Tqj8y-3XYKdu8K-29Qvb(}&l;xwkB^76LZAO*XN%9l`oHW7`Mo{-9~Eo(KFNPcKQHFW~>! z@O|)q?uP&4^8@`KFE1MYk4^u_#`o7T6~Rrs{;>U?ra(`_|8YCMPlW$tV}8xw|2EOO zMCSWs#gDhf{66t7c6-6Uygh5Ab*cEaCte(84gZyTY?xiXJURS|rXhCyWQs5QxX;Db z*=rKy@j1}dKL5x2f1Y?d_&;{e+I01Q?uP$km&=(`GNmq7jMi^ z|Hm#^pP}>r*tz0~;Q!c#a(lr4v5V#UlfPf5cz?s?h5ut`hzElIW9KiAR{zI_mxBLe zV?G%CADjMm6;7oQ;W|Jd*knE&T)_&+wj-Z5k;s4w{_Ybdl`ip>*kMsEw`wxG0`{S|iKB=Ax^ZkDNa*j3T z`#lhnY8@!+eb3%D);d7GZyx??d+XwiDeC|D{2Ubs&v)P?+i&t<^?&T4L%PfBO~+wh z)VH5=yhq2d;fJ4U8nSIy)WzZfkN4PNP5;OJdvx9{f@Q>D0XNQZoJ8A7dGgSQ_4<8}xv%>$eW99xV-qB7!Ry^^ORQ_wZS{*SM(F|RYT=VcLmJ)bA* zqc2!`wWqKA)AiOf#Bam@@$?#3%e+VNf5%4tram!mO_meZ{jP}DLjK)!&$q{;66VFI z|Ks*HbqUV8UArRAzxGVi)+a8FazZb10wb@C;QcdX{8;sW?68UB)&H@_j2rH}{MVap z|9<^@s{iBp8Q;H?`agEy@ZReG*fEnks{dn`Cdud5Q6Jgm!Ti9%hyP)X`GJ`K$NjTb zWjc?{{m!nB%#|79qkgjMGiFtic&LAS8vc*hFP@*^|JdnE<@aCW|Ja!42LH#-mcO^~ zf9$wLA?p9wiA%%P|MC36i^2bKJLmtgu|6;SAG=iM*?x4_ph(^yFn{ld;=!JV|Ks*F z@n-OU>CFX8{J<@Yo2f9yOtKk$ES{JsSK&)t~+$A(XZ|6^l*>E9>Kwc88t zAL0La`z6Wm%i#amn12ud$4->@Kk$ESy#K@czihmJJUV$zB%g0mW=@m!AlG>s^Z&RV ze{V4VkBz@i@PB;0fxn0Fe{B4{{BpTZ}T+#AGdS+2*S+ZU#{2v>>74!etsj}WF{2v?hDdGRz z4gbf6?}Pv2^@qm%KX$0h8^ruSc1U#)UO!vo{w1FeS>yir+jCFY?T78~f4u*o;s4n1 zegoS-}>IX z5%0fj+o#uss{iBtHKaaF{T~}X5dM#i&jT_4k6kGH!~d}hjU#0;s1F3WRy--|7Tqmp#G1YDeL#b|FP-+*cq}v z*8gQ^7Ee3=fMB5Gjk`X|8qC|9~<)l;s4mFwZZED*m(Z||L1P_KX#E^Utb>m z+SAj2|HitkR_1w$|Ks(E7CUKOTNCccEJf>@>M-?xyg$Pq!vC>z<^B)<$HzyZY={42 zS^k`Cqm4#B4wLdvKm@Pml9+w!YOSihp0irw(zFH=l1kaq>8)+vK*^ zLDQ#tKF@AFZwd407XMTe_0#z|>RaIBj$T;j>CdLuTVwta=Kn2UmaBd+(r=RbKlY?a zlXU%Gwx4(n_&;`-pTExk`{|QB^?&$&1^$ms|Hp=xga2b=JNzFT+c&LQ8nv{zK<9P% zPo3;McKb5xsp3iC|F}Q=BK#jaUgiVB|5=L{g#U9l{2v?h6yg8aSRWbwj}0FJ|L1P_ zKQ_*<-~H?C`iPn`*@6G#^%LknN&O!io)i9$jro4?e{8Jh3IE6A$Gktx|6{`o!vC>x zeZc?m@Y6%5ssCfc|9!b|o9&PJU+{n2j(K75e{6Uw_&**$y5?j{!(aWLvBS2*1H%7t zf2`jN|HsDsGtB>E$H@AxnE%IycY^<8!ym%`vEyXE9Q+^8Us8Ou`agDNoX`Jpe>D6b zoBq$;@PBN~zk~l{7lntb|6}9)!2hw~<3_K(%FYk`+L!e{6U& z_&+ud5C7+G_&+v$A^e}a;s4wX|L1P_KQ??N{2v>~2mi;8mGuqb|JZQ}(dz%$nep=d zk@!D$MqIS|KQ`76hW}%iBqXT+V`IHx_&;_|e60FEcVqq^J44p<#r!`uyc_%<8}}FZ zKQ`7AhW}%i%Kc^Q#9Qq7Ej=;98FtFsLj!M#T5(NQ^YwAPqs!yso#rzwT^bYX{5txcD|ZJkC#WoBf`K|Ksy-ip+a*`-tRd?>s;}p4{92SL5;M-oN!c zzt-J)z2VmW?|*s1Z1KhJ(`((BFYDgkx(kE+J=+UfdBE250dwT}-hF(NTKPLX-?_Kr z`S-td>-m0oes=HQdcGj$wYs+#$n&?m^ZX`wy7lq3UXR$(1vOhd%#bl7Jcsv-O7L`I zq1W>@w3-Jvv$oo^e|>{@|C(B_|0}32b6$I^zWJ-V4m!`SNah7C8Q9Wg;ywCQ*4g&* z+DfPW$(rWD@3y!3f$)EYAwCa?`FIV}Te`Nc+BvkY(ze%&|NF<26)i36=feM8v8SES z3rfTPv1iJ>K+OMR&!0D2{h#&xM)iN}ndkf;yHVyRj=QtS4qsnc?p*hEv7P_2>MHer zygZF_=Qz9ai|z7OE?VGB+EZjbd)*rKe<#}d{NKV&>z%WMikmka=&0Ur(dG^6|Jdud zZE(WwC}`&X=zsq`-+IILjq3m0`_FF3x8vKmVU3e^D9?I}c)`h^o)6eGx zui3Fh{U7_X%YFW@-z%Mb{_pTD&Y631n?GFGS?B$oI(&z&|I2>z$YJ$=>_?9J{2%+o zy@z!DU-q$k59|CtclQ~aX~%!h-S;{x8Z)f#J9@va|I7VPo_Ivp|7AaUs#*Qtp`JcJ z*!09n2mX)!)H6Q+$A0nIr_}$k-+bi-^?&S-PCuglkNxmVcCO3|#QMMN{OAz%e{A@7%>QG< zzr+8rF@GBVkB#-`;s5^H&FBAel4CrN_ar$z_w!L?koWm%Ku_;_yG}a+Xl|d^YQ0~~ z!*g$M-L2>OVSQWo{{PGW!3&Oj^s?q7M~c<=wG;0*b9hT%AoB&`|G2$-+w;}`O&udM zJXa2g?$)ub`agD8nfC|($3CxpTlIhJ^E>fS)s{eC0{2zN*?+eubvHNytqyCTQr|Wr+Gbdw<8AA5FPz4||PVTE|; zzvkKTRn3^I{*T*d%v_-UkKH(Hq0awfmo)m;|7DlX^sWEPu9~q#{U00i0pb5JqfY1j z&6=n4|JZT)#p?gqIT=3x$1cpRRR71$DyUNb$Bs|USO3S3O3qUM#}126Q~$@F8kwN} zk3BIsQvDx$(B$dr|JXf7Oj7^Hc6yFc|7YEMoX-EV?m1BXAA3?URIL&KXz$hrusj2QE`F#KX$3i!=3-@RJ;Cji}Th0aXbG0 z4|W1i^iAbHmmDv44N*5$F2Rqng=gUw_`Y^7Fqm$;=A% zerMl%P5mGHkI$Y`|Ht;5I86N?+nMH@|HmFzH`SS2|4x&92d3T+zpsY>W9K)9ssCf= z%=Y;|c9HyE9R81u&wsBw^J^s7^Io*Z=i~5y+@JoB zjqM+_dCvCFlFyU-9Q}iJvizPrwd5J=H2FSBJcKpo18#f$$)=F^zgORvCdU`H@w7FL zAO4Tq;iusL*!8Qjo%ddUyh+yNP|sH?>v6ua>7;d~d_VP!-(#MJ|FiwYcftR$i)CIB z{2v?h_x67Jpmn~izl-^QJpHU05$gZgnGLeutN1@QzQ2M0W2cGNlX*_o_QF!J{tTVJ7qz%uK&x%{R#e$jrj($ev%zOZa-OH$i^iq(lLn} znl1_XvMD|It|;{A<7=&PeRmtY+B&#mvh(fE71mRWrl|kp@r_9G`9Jp5#EaDbxf}EU zc>V^ZUZnnSNB?isD_)#F*eUtT>?Zc~v?20)`dN1Q!ZL@e|C8Uqs|QTX9_b7{(_q&} zrp)hp;>S9>ebUQ@ssH2cRlUIH|Je9`9sZAv@7Lk~?DmoG?=k<64Ic>q$Hw}54>so5 z;W1xv=;=&r%=5`AO|$cd4mpu*oh3eHWUoX|XFU|##LI{MACvii?iQb9*9X?$d;7N# zYs_ne|Kt4u9uWSIjqj5)m;2lGi_0JM?qq9R{vnYQt@CBQ+$YYCwc88xgv7tt{Ry4m zH^Lh8t0wLlYF!}n@_L;&*g9X<3l>jfoh|dSK76ger=Je%XN~o9kKEbYx^R7(%-`&5 z*FSvR4fA_hWB;~KcejSWTRfsJF1K+pFuY;$*+|kw=` zUn=DM$UFt>aydWp+UP zNxt9>YaD*)>6bkH^OEOUdVPYdC;gOl$tGDJSo|N)f9d8dcyv2|@O;-?_keYl+#hCU z9JS6_5sUR#t+8HkpHp{u`tzl?Sm%i+l6g0thX3RB13!9m-z!e>{#_u)5C6w5k^3k7 z9~(Xu{*R6CpW*-5S@L=W{*R6Iec}Ij|4)$hzTyAaF^yBz|FIKgJ`MaI8@>?!kB!$8 zj~p0d9VPRS;s5x26WO!>YT{*Rqk7Owt}ot{5U{U19!VwCLv{7H7?gx=0i*_WKG z+4`h{hD!NY~KI}YpvUvBLL^}>8Z>(P~=a`*$*d9z~0+dXET)etGi_p){B>_F$qZ$7fd zd{_8Co*w)={2x1BzR!mLV`F_m_&+x0<-q^3r-}!8YWNiEV3|(@|HthKvc59>A3Jdt z&R>=_{0;mcx1*o@rp`J>&fnOK`JRUV*j_wVnFy#F>k{(;^5I)BZ)Gs3oa>n-=^!`2t{@2CEc z=l|j{qtySg{Sqe1Jhe~l@}^cN$^5i0tt*$Oh?n}-uD`M+iR%A&eZnup|FN^hYs>tb zNH*p%!vFF5#C*LH|Ms>W{%-bPI(i!ZkNaaD9_IhKd%@D4)>-1iWPN)(JobMgt)DfH z|J7gnTVs8A_&=V%BAM3+|L1P_KQ`vM!vC>z#ox>N;MSObIlb>VYs|k)d1`_+{@#}^ znQV>g1OAVfr$~Mu0sqI&mHCW$;{Vw2Oql=2&XDeh{uHgb2t1S8-HKn z|Jd+|@PBN)-h6%iEW3Wu@PBrD$@?YvKX!&(U+{ly_(}LbHs-Ct|FQ9VxV@WKM)LUt z&p+^gY`i~&|8qC|9~-C+AC%Dn&YZr)=Jzq&f&M%y3nFQ2~brk0l1J0A|;XXgj^ zXL)^PT_Lake|+Xv>vB0f{2#9`%-@6mbGN+zwub+c_vhB|fAap_)AIX1yZy@K_eb*k zKkFj-eG~j2Z(lV0AG=20pTqyLtK|L(|Hm$u&kNxH*roD&L-;>-k=(!F|Ja3c|APNx zXUjZG_&;{~IseDbka^1Rf9y<|w+#Qs#@~1NKVCm*_&+x1|FI+F{ssTX#(YWmKX=3b z@&1GD@PE9&pyB`A4gcqE_&?sCaDRsXW8?k~|Hu8YJ~#Xy8}m2e|Jaz{3IE52XNCV` z|f7zH%2>-{%{kh}hS3Uju`q!+nzWBbEU$-u7oaW3N`lfYmeYi7q(OcH}Ga{X{ zr~hP)`GN3%JiXG!5cPlTirKP0;bZUG<F1J(brQwpc3|6`}-`TU=|;s4lv1!L9!u|wqf2J`>eSRc85@)wbO zy^mhF_Dky`cxmx}+#l-&%m1z6@x(^j^@oQ4I&8$R%XsDIgZtS=4!$NMk( zr&oTnE|+_Q;G$>i_unASJ=)|M>SNG-#;$KX%|$ zpZ{ZrO!xW)%(uh*zp&gK^?T|5vfjM-zmtE}-U0rPhlhv2 z{69AQTDPEC)|g)h|Hth({Fb$IJl%BbTxA+9sTf=W){a+p*8uR}iKb@ADjM<4NnID z$A$-l|6{`=!vC=&Wqum`A3G~n)_)cM$Hu%p_&;`HT$K7hoU#5I6V9x zyCNn+=l`*>UM>6|yFff1{2x0zLgt0a{69A4x559h;lbelc=~w>N$UUH4gbfkjEz_S z=Wh5vc5!^X`ad>29sC~~J`nzojrD)w|Jc|L|L1P_KX#UQI`}^}{384x8;)$c}6Uw^2ja}(m!|MB?f|J)7#$Hwgk|HsDp zhyP>a{KNmTG0*XnoA=r2!&k!p@%c^fA9u>(mt?BFHKRo}sw`T-+=MUoV zk9&J-uQz?7_xR!0-TUM3>3{3iz7X?i-TSwfc~{!qKA*q?3&aCpz z1FRCy;XeMds%lT?iT}IylZNJ%NgZ^aU4Biu`oF6VwO0=a9|!;E?uYl+T31(BJ2TH# zH*Xw#&I3w68|P}74>*2Dm2Iz+`GLD$sBCGOUpTH~Me_~o+vz;Pdhvg=Gs>+SW&PlL zt|_ygJ!^*Z&p(w~FOci^Jxt0-z_Z{6wL|?Md++W`b^c#z z51;>g_`U<`|6=d&r2g*-neR9HpE=F!C-1vQ{U7_peLnxke&F7N>i^g$4joYc$A0j@ z9S-~-`-n9BAN&5p2i5ykl(oWvK>te462CHx-` zKSJjD!T+)SDl0sX-{QnXPfr{;(9?tZ_3(5b`M$vYe9*gVxBuGxWWJtz|JL2Lt9PDY z=gys-=hj@-yk$kc`a1N)Pj^}O?%mtDDz~LO_Ui8ZaOzUq-u8knPVu;w?$xc66L{67 z&42!_K)oM)ALjqDJ4<8!AG>3_^VI*b9r1!&Lw4Bq^V+v_-oE1!Yk0R(u`3!DsQ+UZ%~+uG|JYa`_{!5scKGVq z3)KH{J38tQ3AVj_#vJv3+>XZlKX#?eAH@7WHqOtjufBQ~$?~y#6Njf9yk-U#i^ictzW19kG*&GD)oQt>*vl@ z|Hr;o=Gns1u~#)Vs{doJoH0ZF9~<*=ll~K6`=jCixP3uEj`~0L{QPY7f9x5>dFubz z)wvn!|JZrCS?d4TMTL3l|JX|^O4a|dH^|?A`97t2+25zC|Erl%tp1N(RG#TvanV>i ze}9zUM>Gx@V}168=hXx9_@@B6pjQ2)n1{rLUr|JY-O_f!AJ9(>OK zv6HL()c@_j=128^Sg!;Ak6kY7(_;P~J5@g4#r!{Z`l4uO-+A*``JAp9SmdYQBBsx3**%P zasPsO(dz%$W#Z%D|J?n{~^>Q))j}7kz|L1P_KOR56AB6vN zH~b&FP&^|1AG<{68^Hguu|6;SA3I0x-|&BIeBW}>#n)P69>c58U2ToSU$XovPe+Wn zvZclMegE?1p1ynSW!6}~Ro1t%hUYsNw4+Hr6ISnsd2oTBY-{TJ$(QQ=(7gw4ZMylq zFV*|u`=zkp%}uMn{-^prc*03vZnVbwaqxfKj(L{wf9x2UR{{UW_LJYU!~e0v3;mrx z{kYV6Z0yC(shY*s(_;Fm|Ks_Y9`Bp~$MZX08uS0wKL3^azln*1)c>&~WnLisA1`m5 z_(1VJ_V`GX`G4?#e0&tk_ZeM=)LCcC_Y;`^$J?t+9?zKn$HqJr_&+x0Qknij2e$TK@mHm6(l-hEBm&&}oeHl8vc*hFFfG40h8_igUerh z;{tgX2@PBrC;x8H&_OaU|e_fJ1-gobocpZJS~5}tP3`# zssH2U$rUdN|HsDlyZ`VJJO5}|f7Lp3U5b-B{0{33xxNN}xX&8vH_P|k*6>B}e>{Gy zHwyp9>kIcE_&;{-vT*f(?3$(WdA0aIcF98d{#X1TyLf?b{vR99zwm#2JivRw|FJPo z5cB`oc>aX{W8?7v|L1P_KX%fbAoYKIJjFCjQUAw=KZO5tH~gPGq8jDKlX^|N$UUDMfrZ}|JdavvL2@R zKXyv_DD{8r)QZvS|JYeo0 zeG`vux6WRl?sVLDO~mc<{-vHTcVnhAvdbRpg!S1@?5cg%p-U2+p*PC zyNLhe?cHbkh3fy^ai>9rcU>m_b2bQ9^R+BbK9c7M)3VeNZ+>3lP`Z_oieJA6Epgs z5qv+A5#G~jSpSXn%%X`hZ}CU#j5)F5p?c>kH=rXHV5BlN3tuHrK|*=Zu1r<`$M;{=;^pA~*zoo6e>^-I{?A(G^}+wS8~)E){Aa-7iz9h? zF^@Mcf2cK{j|-g<)&=r>4*$o)&l0~6|Hp1zm8$-a4c`y{$Ie}u;>;N?^Z(Ahf6Nvi zxc1el*7&^-{2wnL=9|I)xf}kEjrB+2|J)7#$A({m|6{{1!T+)0{ow!D@aFJ;Y^-k& z|L1P_KQ`9ChW~Rn{2#ka<{85Ov2lCD|FN@V{bTq)Hs(db|FJW~2g3icGgm~b|8qC| zAFoerhySydznAcT>_mA#4FAW*yfyegcgs9cyS)?T^(y=y?;j~L4-)>5ohkDL;s4l) z^8OV5j}6}j|L1PZ|Ks~HtWOO8$4(V5jrD)od6naJ{vTg|=ai3C|HsDjFV_EMac1pkuF)eY8(;$7kYxPRKxNcDegc)z?W_S)&A<@J>{=5NCP@%&fF z?{&`h-*1iIb9I_?yLF+wzmVT+SeMEBLHIvjzi9YBHr}7e`+I9_m-qkHSpQo-AF$4s zd9w2RLF@YENsj!!(7IxQ&XaCwxxdQi6V~{>B>W%mA7wI+68?`}B7Yy@|JVf$)71a5 zGb<-MnE%J7|6^x~=Y;=b!+*m6@$$x(PE!BJjw+d`^Z(e9#S_&3u~X#tX7GRPEh5ut`$UJQLKX#UUz6bxuPAnOt{*N74Izjy(ds^8<@yM^){zYYD)c-{&Lv+z-^?z)v&kO&@&M5a&|Hsae z^}ON#*m<(vH|GDbb7lQt_&;`zctH3+cBc3@tpCf-690zze{3B8*w;U`PRSkb#Kiw2 zlCR$<$Ice7D*w06k^3+FA5TBOGQ^Qt zfu5GNk?r~{teEPAwEfAtNbWyv3x2lFs}5EF$NO)7O_=&Wc2#YZ6Fu@jc7HA^4Oaih z$4|Wc9t8f69g*+vln*`6IxgMcSrOkRihm!bh7VK!$G=Ch(jYm@D=cX zZ1_F+KX>mOHrGxM`#&8!&su#&{d`Z~HBsJFo;&~8|6}|p*VTiU$WZcg4ewEMy*%lk z>l|6{c=x07BZG4dUjqNPd2fz-LiiQT|FaI8s{W6S^^-CGkB#|&nE%JloaU$gkH?Sg z@PF)V@q_SxYLO_ z>y2XlUpD5K!T+%_zYPA*-SB_Bym^r!y8bV>WBppJ|I3EY`tsYB&J$m?Ys(JXo{}iP z&+5C=IxRWgdFEhC=Oo2Db<<@o`nlUHJ2B2V@A;O_iiuPI$L(nNKQ`v;yuJQ1Yxp_% zKc0X1JFNf9E{~2?|HsC>H~2qxS!|s1&%!J1_|lV-ogM#Z>5SwQ^?yA5%#;N6f9{6= zW7j3cssCeF$4Be@KQ=rX=Kry?<6_kRv9Z1`{2#mMod09Pr@{ZRvHmdp9~;}@|JX$_ z(dz%$@Nt{oxZWOrI6p%gZfNPmNcDewzM%hOm>j|6{|`!T+)8|9E=ze{7sS{GYqw z|J;4|>b-V+@PWx)_F0$5%J)s;|9E<3;yq=3qp08WGSvI!ix1o){?FZmChm(W_)l8% z>lwYG;U}Me%-isP+&?`wO8p-jk0tvzFCxYtXzo_`B(?LNKM z-P+@|_JFOs_542keRLmxWT5x&Z|lS3_IK}pUb_yScG|RU)sn9HT<6O?D|dGv>0OUF zASu_gJ*3#XesDy2m1lctRi*mB&`aB^|0@w+R4}fg+1>r-)?1g?R6Fp0{{L*JKCrT~ z(kcFXjdhjykzdEQbWKf-bMxG4+g>N0CH(#>Yk0pedQ>+5rM8`Tp(mmm#Uo@CR9MfH z@B8n&vD~^*)&uVTL78>Uj0R`o#ih+}pJ}Up5cB)y)s|SVoWD^0AGdE@zS2o~vBXY) z!}^Wt|9E*W*}g;lAA7^jjq3l{n|5th|HtcRhpeyr@Wn-T{cPW{$yrrhXuWC2MxFo1 z{n42J$KJYSgVQv&rPr-pss1m1oX-<(SnczF?44V;ssCeNvEAqYb|34Y{_l>PuU7xZ zzI*>}^?!S_JL>$u$Bx~p>;JM(9XY7}@4(j`eID@syVU==8|(kFA3k)O`akwv;`@$^ z=V2ed^LF)r>_d0#SO3Sx{_h@4xBc%wxL^Grw>Lj@zjNEDG~0gSkq6ZO9l4^Ddca2> zdr18syXm2$>i^g`U$aa7AA8l}67_%VkbnW||JZ)A-uS3LBsR07CbW_G>2KIj?H(nE)IQ~$^9UAs8y|JXs@+Nu9z&rgu= z3XkLc3T8RE1w{omGC@_p+8pYwlgeE-rsWoL6!ZlQ0!U?-pd<94hU z4FAV&C-eC>uH0@7|M%wKwpn)+j}8CF{ow)O|Jd-3uMBJHKHa-GBQM)x+vVt;56+f0 z|NU$K<}Y%b=mBzVUe~UrZ`!m;{U2tqVgB8jD>gaXW&SDq{lhmql~|L5Kg|HsBWK=?mi-dXia)c>((H!M~E$F7~ZSp6Tn zMtmOpAG?0WJoSI>hW}$%i|@nwzib>I{2#kUE8=W71kFd*s=(dCE|G52$yY5&2$9`o0VfBCP2X4JZ{U7_tjeFGp zu@CINM*Saq@2;Kd|JYY-*{uGLeaYH2>i^iQ#LL6~v6n2Er~Z$GpS!XCFS{teQ2igfrm|Z7-;19GsQ-(pDN+B&j;}A* z`G4$3uDD*kANxPAzo+y6*k?a@PyJuY;2+ih{rKuj>i^ge9lKrqAA9`h3)TOz+eZ1; z|7DMp_06#UFFUiwPyJv2upiU|7R&F~;s4n1R|glo(X?{>_v-!d`*rv~Ynkt`=ji^g|vi>mU|FKJCejogwyW#)h z7JjY%5A*%t|JZqr)7Ag6v7QS29}kZfpJAOTzkkR2zdZk0;{7oHkDWO~KVP@bk@++5 zf837GXEFcJ-I)K!h7W}QW9QBaQUAxzmWKah=g*5!|HsDl3;)N)?Fs+Kjuw9h|L1O* zUtpaox35!qn{|fFdy@5!ta1O7^^rUc|HtFQcKAPc!~e12>)`*`nezPx{2!bC&)x8U zY|J}=|6>;}h*JN@hPQ+Nb2t1S8$J*IkB#}1^8J*!ZXs{*MjM2>-{<6rTzI$4-)uLgD|| zK_$NVf9&vrsp|jOBO?Z>|6`Ae=%N0P=Wl#$UkCI5qHp{{z2exULF)f_dC;9t&uNl1 zaMU+WO1en>A3Gp@nEF3HK4Nl)Isg2u-X1^2a({*YGssUdcM$dq1xG|0M0E+70KuV3`e7pBQC(AN(I1^Zoqy{QDFe+vWQdPs9IlJA5DfpSw5h z`qUc!t}yv;o*v)seQWqX`M%84^8K4Nj$gjd^R&zdvBvSsyb({2TztwJhnK%c*6@Tc z{_}WCi-&~&}|Ks*TnO_F~$A*`| z{69A4ZNmStu|7Ba9~z108B`}zs>fBpLPQ~$>v*}I?mzor$Z)&C8b`Sb99>>d~NR{zKD+PS;) z{M+f_8zw#36wpz=_Yj|m`G0)==|6Ii`akx>DWPRUdheB+B%=`QB=QvNNBxhRV z_Ye>4DYnM?oELvqYdv{xkn<<`Q3{_=gXOEggqxOIXRpa{N)~SPwEOdo%=JmmU40uP zUViAwrVX<%i^|)QF1Owj8~AVTrV8hWZ7U*peWz5)-;WL(t;5q~y|Y)gMDX?*A2JNL zZv=1O#0e9evafboCr_H>!2j|7LI210n>beeAA8i8p*sJM_rF0G_j8K--xk3hH>jWb zKlX^exIZ7Z?E`!FQUAy7_&jIrclXNy zSZS#GKX%Z9EcJgpz9kz9)&H?)E=^Pa$Hw17%>QF&uZ&m!$F5qL>|7Rkfo-o`A@c;k z>|qV>_m7`@Me_8~zunQdrNyUp%kJ;#A^#p|jro7@e>{AN%-elizE=|FJPY5&n;zE7w2#AG=VlKlnd)!~d}hWPUCDA3IOx8^Zsw>HpaD zf9xFbfbf58tcMK$$HsQ}KX+sPAG=!qKEnU;`YVywoA7@v9j*S44c`U-$A+g`Iev-V zzE}?y{*SjeUJt|nx%>CH)scMvjCtzUe7V-TK>QB;ANNm|&jaB9+ztQ7!(+Za{2x1E zrp(V3|Hp=p$NIl~y&Wfh9`pa$X*GfB|Jd+;ec#$?+u{2%#Q*X2HX8nqjrnNse{4LT z!~d~EYJKzn*pV{--e3G5Uq8U}!T+%n8|3|{_&@&rr~hMPd+O=kk^Fm}D8HX8=zhI* zlFYNKskp&9PJS;p@18x@N%H!9;JkN^Z(ds#lHD}?36-3^?&TxqRHz2czs6~ zOjQ5Jjwzg^>;Llh#QyMq>?rYo@PF*+k}2x{*zkXS>z}pzM}&O-Q}e)c*7*Ga{2%v6 z!~e1Ic@z8}J5jtJ=Krw+#KU9$A3I21AHn~zQ^W&e{vSK9AxQln8=r5%|FLm<<-hQj zoj>%ggWk5zmEX6*|MBsJ^>N|<*pY=3)c>(#ihTZ$oh0jtWBwl-um9lx*vXZ$zPb26 zcABhr3;*YC_&+x0OTz!Lv&2`z|FJQz5B`sxDz_K>A0Pjrg`?E}vBShK!vC>TOML#1 zonGdr{*RqqK3)AEJEtPVky(Lu_-yfu@P9mg%rAU-@Aua5i37j*!5aQ?M%Yi*IdXb0 zANZHuKDp(xzWGPL+T*{zVw&^Xw0~Qd<;(9QR{U=F|E%m$>i_uo%E=w0{*RrO5$HVe z{CQFAu!xb)ny=eL@$W@zZx9_c)${r^G1%)L;2q%qp6-&R{?9LHn$G`=zb!-kUqHxo z^?&TJpkVcX+&?5xE|2&>HarCU9~+(x{*Rp}-VXkc4UY)_$Hw`C|KsVQ;s4k;yd(b4 z-SB@rJp3N~pS$7z*zk7nf9{6=vzGJo@}HM`8vZYNMYeiCoPPX>Rkj_yK5?}**57?} z)*5T9*NgdoJbs)%_&;~U|FLm+_&+x0`N99W8}t9z@GWyx0Wwe{6U<_&;{0_&E4KUO(_r$6wlR+tKiU+#fy-{_p=#b{@ z<~q#Pbz*#;gCw z^{2)9{6BKKv?KqIoEaah{vSCbZiLqVB_kgX^?%8^l23>HKQgu#{vR3pgZw{oq15Mv z|3^mN-P8(q+x{Y-ujZZpysg7M zZbtr}u}qKrKXReeM}+@JhTl10-~)dA?(5~8J2J+(A%By#=fp}qov+I|UHn7%e_USj z(822ek#nR!VwXJ_{Yr3>`hH;ee`NZ9;CU;ZCCBRoX?KXPJlANBvpfxp+t_vEt${QrOR;W7pX_Eow>qeK9s{i-Ti7M&?A}&ZxKB zW_GEyqh28Vztequ{vi0=&!db{KM?-k(5;o#2P~a3N%Q}j*YNp$#gg}j{6FJ~W7Yp7 z&s;QD{Xg=`l`GZ%Bd=b)TKzw+fAy;6>i>~fuDDJ8Kk}O8KL3xre$}n&|FJ)AU$ad8 zKR3hwBQKVA)c++fT78@Pf8^DR7pVV7UVQUS>i_Y0ED;|N`G4d)*R4|jk9?2R_eK5R zmwu|M{@=Do?^XYgynpj1Ct*ptwV&MetoncFZm;I^0e3y4{$KUJKL2l@@PlD#Ubesb z+!p7;>{R3ZTOL&ZkJE2|>;d)v+>HD`@-x@`Kl1M9wyXa~ereB(>i>~ndDW}_ANh#K zm;V=Zvby?z4{y9n{Xg=iIaAdCBNqihe6sDJBjM?RjLn+EuM&1?DlfPwja@Y&q+ z*Q;K``FZ#{?}q(p>hCqFThGbavDUa--GNVD0r(sR?|2Tgmd7mQr z&)&Kjsd{}~uX$7CLmM}0-O~9_ayj>G-OMT7zrxz_z50!fSNbjg)+sB!4LVB=>@m%T zRITN!|J!p*ruu-5f4yo{RR52>^Y&Hh|G~LZ|8Mgn>i?0C zZrQB6PzbE4fl5XK1ltsu_aTS z|2#6xc--izPWBT+jYp53rv4w72ZsMg&KfgK{XcTfxasQuk>}02Mg2eWtDaY!P5+Lv z{`u_Ko9h2@|G#?clza~zY3&!@ddqpDLWJ>WZ@;bnAD4Gd+C#q`Xxjs>`$L!?U;bC9 z@uw$Gs{hCN-+%oL_5aAHUVTmdKV$D<_5a9k?LVmgANl0&J?j6FU*GYf`hVn8&pfUE zANh^VkE#Dhe(vFi)&C%qzFhr3@|t<`)c@o0yL0JM_5a8Rwr^MekNoos zJJkOpUp@1_`hVnK&wk)MG@_%Oj~9<0RsV0vYd@)lfQKXTac8qN(X z&U(m2llo}>-|b)gq`n`X7b5?UjQo=4UpwQO_TInL_e+%b3Gn~Oc%Lvj>y&5yPd}>f zhx{D)e`MrO!T%$p9@P8SpY#-d@q_w#sndoyYg(KzhTjMOkJE#tzM-|JTtCQpw%zN- zNmIg{u_uojBZ6A34zg{rL^GoFav468C`usmK@(JMok&)*B z|Bp=nkDMv>d654{P8Qz}{vSDIn&t->qdqSDKenSjF8n_-{4Dr?ZifFy#(0AN=VthS zWcYLN|H$zD;QzT9{-2xS|B;dR1pkkWJSg~oWQ^a(LhrHu1WSIEG5j(3f1DocNB$of z+b{VNHa*T4dH-aL@hk7Aj1$BUi8!;`jz8*a|F~?Gai;iylJDbLI{9n${UWaqb+X^Q z%~Mi%MSZ^*c^?Y@kBt3+|3^-mIRw6dXWA`adEjTEzVdac3yq_szRdiC^Nfd%8RT5( zd5dvyR!`0U8sj__`&#v|HtEl@q4CE4;wEyKlVS+ z)fnUF!?I2`9unkzU*wtg#)*>^eNyTfqrPrKZ*61vfyZ{&wCzED;DV>B+xF*6 ze&E&q)vP}-|NdrGtiQms|Ey^Ji}hb9aQyi0Ie#By|HGe?_bGlX`3!z6^`86~{vVHT z)}jRU|HwH@k{tMd#*35H|8q0^KXRV5!~Y}aFG<1sLF0@i$?E^H9Sr}EjQQdJk#iR% zssBetf587E!^edGM@C*E^8eh7{6AyyDdGRQ8UCM};s23w{NewRalGLFk>Lx%|0Ac$ zc!2*$#{PYJYnk=;sD&x&|M7U`+#IX^9~nLd{68{$4ETTK%sDaY|B*8!f9Z!RT@Uj7 zLcL`8e`MsZ!T%!%N&Y4LKXO-j9}oYJ94hr{k^e{Tn9)=HzkQE;)c-4#yfyfLQU8w&Uu)a0 z9ucEj9ai5D`GD~M$Svi5|M@3wi1_~T!|Ja!mc09MKdv-(x>iyDkH23%bA0)KWYi~v z|3^+K_SOF-N0bDs|Hr>qVFi8F|0546Y^(ksIc{uM_5V2k;IX~c|073D2vYx#( z_luG7=;r*Xsm|^Jb0XQl-NM_b|HuB1@77ZNKOV32ejRaqBgrBCg4F-x@$cWekMmj2 z+at-n`gGU)KaQ7fJvyuZNAB6h=l^m1b!^j2{XcU1RzClajC#}X|H#c6)lvV?&D&5BR9XGmrU%3Sncxf%W+_XqWSk^e_VyOF!T%!{iSM*-aj0>kXSX;jhF0<9J2BKKws7cfN0tF}}|# zYPZCX;s0^^k>U@+|05&+@w=6`+4vngIZFLMj_(M`(}Vv&Kg8F_E;|HxtELbd)cd63j2h5yIviMTTP-mLVFDE|E)F89~)|HxQ>hiv`${%qUa zhyD2HHy$y@^Oi;LK4$xqCV7=|y=IL3_a-+zVGLgo{vZ1Te&B$eTaDodMpb#r81=j3 zbDuUw{p-x9o-r#_$ zJV50C8H*2y{6F^R$gJM#|B>MXBL9!$En4ocQUBM*m$ak)ubYoIK4u&QA6EQ7wufPS ziT_8AC>!i-ulS}P|B-&e7~hi)f9#|mZ}{;oMqM|3^-m7OVMxg#Sm*mFrFUw;zk^XPi|ad5@C+XVVvlssBfY|95xUzpNeg zj33?glW~^#e9u(;#W+)ZKlp##UgQt%SpB>4h_nvQrr-Xw@mP@7$tfH8w{b>XE9BqX zcut9L@0>n<)y8{TVn_A=c>eW|>#P1BxyO*M>i_ZYO`vb^|KlgX|6B7_vig6h4~zQ0 z)fXkH{}(>cSO1p`pQ3ZYcxy-A(dc<)#_;_%JvhM_zQ_j$CmQEQL^uu4PclaSUWzlt znEoHvhxe)Q|H#?mx557-XGy(C_sS+Wx_BnV+-BkKzAu zdbGp;BO_l6{vSC#e6R!mkBt6+|L11-e`NSLsQ=6NvG8?}|HpRZo5BAhqaJLN$mPb! z_k;h(cFYg|k6b!i@YJ`G4dj$p?i0M;>`C|BsCRhW|%~F9-jRJX-Px;s250OTz!-{-#J? zBK$u$!~Y|v%JSgL}<|8q0^KQi+F z;QzT9{vSCnZm9ZyWcq((>>vC;a)OLkqsw_ziO>J@)bsg-W5$klF66jAr{~rIQlKOw6CYGuH zSCCRk^ZiCoo~ZsG`KD)C%+V+Ey|Hu6S!~Y}ScFq4IFBN|f`G3Ys=c)fkUbM)U|HuAcvB2m5 zk?&cvT>U@ted7Ps@0nr!|Lo%%ou8(r8}EJcLG}N5d|!X*8TJ3<8MgX=yI*=*{l6*G zs%ie;OS_&@|Bvklo_$>XKk}|Eo7Df~^xGbNNc}(Zv*IVg|0BQn)Ki-OM?Sb~m->I? zV;+zCf8^J_KL3yW+Wy^||F^4_&;MJw@D}y|$YaN3sQ*Xq(pl=|{1Wf|_qOWl@1Z`* zb3x@iK&}tcZ-}#Y-)ZUx;`bHxf8V<$L;b)Ck|zlNkBs_B$p0g^t65F+|Hy5` z-)s`S-22Y&nd%3k|MIsjGp;H5gAX+*=jxL8*Y&SLZ^qw!)%Qd1!~Y`>YuQ@;Kk|`H z52^o$8msXCjy}0n{Xg=dM;}xFkGyB&diDRvTUN|h|Brmfq$2hI$je8itN%wX8Z}=1 zKk``d=aBzL9yflv`hSP(3{d|Md3W&t+>HD`a@ho*|3{|(N2dQrMm`|&|H$AR0|B*j?=PmXB+>BbdZbsIg@teoh|07>G{)YO0 z56qW&NGlcPt}|0AE5cI5w&KR$F&{Xg=%yPsG8k9_o*C)EEV?|yuX`hVmXA9+mu zKOUbgQV)AW^KM@9OFMU}|3^Oi%Ii+Q!JX}V`~J*X=W=u>EZv?zx{jl|L{B){vR3nDDeL{ zJsAEU+v)$2lcl~d{6BK8d~Xl`ujKjf)c-4$=h^W8$YbRBGW;~y*I?OerG9(iW0ejFJ7->+@1sQ))a`V;yo-tTqUyTtQYzsu_TArA%qA36TU1oi*O;bW!#lK6k*k)uM?|074q`v}P&vi6Yl zuFlidXBu~mZleAl*Iz%TiTZ!s-s>da5BYyvuU=9AuX{pU_5Zkk{nGJ${AAnT@a%r- z|FJ)!rM{#1J=Q;{PY(Z&=L71K=fsUMhQD^`$r9s4DXr3@O0hBCzuq&pz!>>>@c(#x zkmm>gj|^Y$^umnt>96^JTtD(^;Qx{7|B> zMeE;DlAi_tkK+#v|Bqa_I9~lfH^cukmhG2+`?0(~GG_iCk9Y3UWW3+9cKCpjm*L0o z|7?2k{owz(8UCM}AN=63&7UjN-|)Zzi=i>b^|B;)?{WAQ&x_2H@|F3?vI_m$Ckq>xd-3P3_ zQ~&Oo|Ht3AUIk(5|B-`ABDDT5xr^k*ApeiQcWtt}s{cpsoYh?YKXT84w#YxV>3f&7 za%$!FHSRa2t@?kQK5k40_5aAp6S_L^|Hw(xf}DSj=0@`ODQ!lG`hVo?n(xr_RL<=j^D|2Y0Sw`-yP zAGux2CYt|8Zr-@A`hR5P`=S0XxlR3A4*b8^dI#123vO6l{XcT{fbPzLvoBkFnmm7( zHsk27ZJhdR4n;02Jm6`NCw08KHFO@__o{K7h%SzYRK z`V*Wsr9~9i2Y>Hkks&UWL#gt|0AbN3se7(oOzS@aN_@wi)O{D|3@yk zN$R1B|3^k%BK$u$!~Y`}&6fIY;{UmMP;R<0jt~4lwr9)q@c+s=M!uKJH-`VTpiz-A zzTa5?$|z&xw>^4eX*rAEx1-%S<5bC4d*$siV_dJn|Ks{_JqQ1foG*S==BexL_<+YR zoNhcyd@1;U9FIlvy&L>LGW|a?{XdQ$`hVmkxnF_*M^2FA3;&Od`*Zkz13wV?e`MqZ!v7<~_k;gOh7Sn;j|^Y0 ztZajwUsyi;Kc0W^!QlV#dH}vyQ0F_N`1d|s@&)1lkt448f8`va{vVnCA9?7+VDOkDMj_5C6~2@c+oD zKa2c7GU{2w|05$`5dI%Ip*RTNkJ|pAelPq#?*E9qKI;FGBjtOxueuzu;}L$%|KstC z%#b!2feI z{68|D|G@uqGyFetzIe2&tXM99PgEnjE9UL;2aM- zYmDRb{<2Su^W^vB^V6RiV|;wq{=6}MpZ~hyf-%N(RnKR}@LLzSv`mubk zV~l*tkl!vDV|w_1JYUCMAEo{uxk&O6<=@txTjI$Pr-!)&Fxd{68{$5cq#?hW|%~zXJb{`v->qM@F6? z{69{Q<-z|W!~cQ*M@}C&Q2jqLricIMX83<(7 z|3}V^>SB$B&!uBUy#@D&K$~i1p@>n~qw08J!EnX^T_-rqaSY_?V6U=_U zoUuLd{}O(SSN{(_Bm6%y^6zfDqntD2hN%C?{v9R$9Q;3SFMK!ne`NS}@c+oEBZjK~ zM~2@9|Bsv<7pwjsxi~pl{XcSET%6|rkug8~KXQ`n5Ay%WsK*Tdj|?9W{vR3h!~b(L z{6Fp=+Ts7X8UCNK_>J)Y$Qi?9)&C=BM@u~j$^Ro~M#iZBM@HTw{6BKG)E|cbM;;~& z|BpOE@)du+@BZ@RGjxb^XV;C!@B#bnDd#-N7kn%B0c+2dyu+#Qm$U9)*(Pg8ULyQI zt`B}H{6CHd_@BuCBj-g%s{iL^_|>`<_17Ki}@Z`G3PB{O1qk%m{yfEi2OB2Mo;f zgMaJZ{{Q9!2IdV0=KBTuf5Srk{hL4^FVNQu^!oza@q6#y-arnVK5%_8A^!a_G*rHC za``xc`GbLfkC7kcp1wh45k_3|SE=If=LE7-*+1{gspLO@;|l)mjU4}Wr%hX@$`2F0 z;~MyUu#WQk7uUC(Q}T+Pm8E6gzh_p_e7USqW1VLX|Hw-u z4{-AMEbFgz3+HS8AN%kARV&p0BR{xdx%z+Policb{vUbYQ;(|u$K!YOrS0nf@p$hN zAF$x}G&}x#UVcvfKeq3eyg=mtkq=0{-3~9Ol=Ge)&bU94jbAyq$JsWpoR93??R-5a z$=Z(|*z5G#n^?}W{K!j*-nX8us{Y}YyVh#{A9?+pN$UTFB~;V=znGq_)c+%Q?%B+l zusgx~*rjUf`}Ga!p#C2j=YLf51aGZdtE+Z~r&0+1P)2)Z=weU%9@&e_WxC|L;+S znw6c02d(!$dMZ`@xr()_I2E?6Ge*5z)c<8Wd_mOzB_qES^?zGkpQ8R?Makbo{a-Tt zJmmjvtd^`kU_;3(K>i;Y?^lrjM{ZoblKOvS{C>j!BO~7r{vVf*?Rg--oZ(YH_v~`p zKBrn`r$O^_t}OM2;s4D~NmoCxN5gvR|B+FT82(@W@eK9cc+&@Ary9>i_NE`lR}QC|B-LV&QSl)&G7%oX}QJf|Fx*sU;V%AqA}|Kk@LlWga1b^ zES;kHf8i=1^A`76mMe5*=7<1gQRNBuvxUpe!h`hVoh@1Iit&&{a+OUCpU>i4kY zdHM7y_5XOhF1~wO{XgkNnxY?>f~YJ9#hv(%bu3i>uL>-hbbT8s5?P%Gvjw znd1Ag{q4gC|But-`8xbRGW|bt#)MF(W8!`Z>-k!JK73F8;op1x z82Nvk9_`5gA^blw-WS0Cb2I!uV;O(&|H#OLg#Sl|pZda) zd;A#nf7y=pt-13~>o1HK__@;n;;A9;xMr}!>*yiz9)Q2&p|FH8CZ{vVG&{6P4B z@(sEAe_;536Hi}O{}1om;Qx&{c1is|oKL@0xYcv|@|WuSCEqwy{XcS&ypMtZM;edg1?(@%|3}ANwCHzKV?( z`hPrLc>i8+b$2`d$d82o$K#9qzxu~IdPZ0O@|y2AT>U>c*R3o5U$={%V~Ja%v!q_| zjZ0b@7cLm-y!T5pW90vZP89#|+VtR!XB!z8E=YF%NfH0=T6@9#Bxlqsb&cVJ9S#xy z?^-+Z|9(uE8&okaoF_iRl1kPeMdH)I|6_j_%JQ2YzIu>cBtDwt zw;31Dk8|XGiZSvD;s0@bj*>h*dADT@pAr5a+p)irN8!it|Ja@_?ePD|S(2wG@868! z=gIp#<9x}#llOzh@crQbasC|1`-A^SE?%61zej%DsNIXk$ZP!a^Xxjo8pD5- z_sPaZOA?SzV~qXp`~7{!*ni2-@#E7st@C5}f80L!g0ufz>c{Z^*pB=`_-MSO>}fBh&vQ)BhV7eo*~Ce4mHcQ_@ z8J<7VqyAsh`ab`UjC{Z4w^xs7^_NF|KTMDOKR3hwGp^H6{lDIey*~d>>IEbJkBsl< z;Qx_Z*Q=@iAAj#!x2vrFA2};m@|mUnFWI>%OZ`9o{yEdr)&C=p8=I*9ANj`VdFua> z^JZnM|3@yEovZ#IdD7f$_5a)q|BqZYCtdwN{=SZ$k?8CWDvjjt=?!CooUYTR7*CV@ z8~5`M{C#k9isX&CdF+%VKkm`Lk@|n^ulhY2ssBfA5!_n+KlVTJ{NVqQgZuVV|BuI$ z{vR3je&PRdJoJ*hy@`|VHtyQBtNMQ&Pdz&O{6CJrF6~>Y|3{|(M{e7qvHE{x_@wav z$atOv|8H!?1M2@JT<6RGBTtw2g@5*ZIdXIAe)aqCd`(bOtoV--k&49yCcEfWIG6}cr6#eX%4;`IZjKh&#v6t6eI9mcha;`J(ccg?oO@D1Vr@%{=7|Bv^7 zX}1hh|Bsv`{>0kKJ*_=|B*A~`w94eZifHoX83<@hX3bg_7SS`Q>_2M z@c(#xvgG>=_k&wf-+TeRQz;e;n`dUEu$bhm?k@ z|3{9JyjS>t~Y{vXeu5bvD9aV|L11-e`NZ9WPDEv|Bnp+6#gGMZj{geaYGEd1OI9_5a8tBrg#DAII15TwnelIU={4`hVo`oUXXOx9P*Ox~Tuh_K=KD>i?1Z zNxmHN|Hz@ELvX)foGkf<@c-DJJ1JcKKQf-5!T%%YNj~4yWAE7b!SlD-O->nSPL0s~ zKTeN!_Oh!v7;@c+ogGJfIzk>RVt|8q0^KQjKl!T%%U?;HF-a+%aOk$)SH zmHH;)^4a;GKPA$UY<}Y`$sZlE@mu4@rwV) z@!WHG2j|ZwPBeK$L_25azzWekKSoA%aPmJd=fFIqKo0Z`P>&G)-<=T&>i>b^|B*30 z{68}NKk|^EzUu#x;X@$*&&}}v$hba4{-2wX|3}9BsQ*ibUkLw?96CVqoy7km4-Olk z`F~9|C;It+ZifFyhJOM7kBs_{$p3RQ^8efn|BsCMk^e`={P6$CA<~ZezvMxZ4+#H{ z964~1`hRYQ|3^mu!2jd^p}*n(k&({`|BusS|Kb0UF+co2GJK<#zFT7R!>`F)xYStd z3)j8X7oZ&w`K4ZDH=ZG%^|Bw4q z5EHKc9~nN@eDVLtS>k`S5dV*id^h-i^ho-X`9 za*_CC$p7Q~qs4cd{8Tw3ZxH?;`vdil;s23Q{}}myWcX$9|HzrLJ*fXn#`2ETy2H32 zYKZ!OY{&k?|05%x4gMb)#}ED=8OIC$A30onOZb1}D5*~i|Bw5ZI&_Hoe`NFz{68|* z5C4yh{Xza88TDh~|B+E|8To%?_;c|8$T>0|;Qx^$#GixzM~;c{`F}hfIDYW|+zkKE z&G7%o*dO?Ri?3FHwyocjCS~cZifFyM&7FXc|&0SU7+9h-x&3V-OCHi z`}@E8d4YakAj7|PuP?BD*bx7E!9ybb^9KVtFpn_s?-%@a_xb|ckuU3R$M2(?k-zHZ z%rO7urHA-G9}2AB8_4*3kQ;d)%^XUid7NtSML7=)(3`P<8DViOE;?y z=$aqCApE~4)2nD6T>CDa)&C>68z#@EZi?bnu!8!3>!jXguhs=#H^cuUFIl@>{XfpXRPq4f|B=^-5BS>ve_oT7=jHnEUcJKU zeSfYW!~f&m%y_k#}zM`F}hf2X;KA{vVI;^SidI|3`jqr?37m`S6Zs)c+&D zv3IBXf8=-e?o$7c{O-P&)c+&Db>JoS|Hwzh_k;gO-nH!^XZoKB#`C9-SN|{QyDI7f z=H#ZR|F?f-RrUY6b#JHsAGvGy4(k66@8t9ULI(z^|3{7*G+6z=x4qTW{{tickL`WL z2SolKIYjb@-RBFgx7=I>r=$D)3FImPzHNZt+rDu_zxnI7@b~j-H>>B@-oC!S|JR{G zW54z$O`7;I^7Y)?*QCCGz2Js*{Cz*vC%SdkI&aD6iN1Qgk`H+4^R>qC=kAW&;O*Ek zO?^1j2ZsMQ;i(k$0Wm-PKQi(I;s22<%KH-de_xD9R{yV(yibAuN3JjRiATP@${7CN z)8XaZtY$6s|G0hENj+lZ|BLc&{zSw)HY9Gz_tLFIpKXShcHP!zk-(EUd{Xg=f zx6D!hkBs`L?IQ}jJ^t>aKHGuEA98LPl5f24u}#jq!}E*}Ji1x^KR8#&3*2@81M2^g zciy{6{Xg=(w=7iukGyF1JoW#`H%yqK`G4fG`9)6b<_s@+TtTtZc1yZ(Nx>NBx2MfqW&-W{E1^uo6mx6f6u-CnltOm z0e%es&!&Ilbl`JF8vH*p{3rN-ZifHo=1GmE{_mA<)bGRe?GC?XjC=w3e{4tn7WjW;_=iJ}9XCcE z9sEDGXHOdJ^c{E1lThm$_5JduMymg3EIuLpzh=F^R{sxq2=M>NCE`b=uRP?L+2M-% zdj&Fol|f!(_+|U995hau7z%&FIClIX_5V0O82%p_^>^X_aeb*$KM4LG+fm;a{-2xS z|B>ncaembIh5tuJeIfXNWaJCL|Kt8=jPv<_ zNPoirBjfoe^8d)W;)l)<|BsA%%<%un$Y+HAM~1%!|If|v|Hv30@c-Nl|Bp=nj|~3~ z{vSE*h8Xq#+zkJZjQ0~SeSDwoKY07fdyV0L!T;m*VEBLJQhA>N|BwAON}hki|0Co5 z7W_YQq#SSfe>`5p#`jbIkDPeT|Kste|0mCs)&GP43jgnu6_@<{zkv(BRR1qY-lxF- ztMbT2_5ZNF$p3RQ{68}5|B@pmZv*}xIkq@h^Z&>(d41LYBM-{%r2ZedPlC_?RxULf_Au1+$>^KJNl-2cSV0qXy;e^SQw zQvZ*fFL^P~#g^LngZxGKe{6?u2mg4M&G7$tJmAN{|0Ac|6r=th8TlIU|Hyd1 z1^f39?Aye%Ird1HPYeDiQWhX2Ryf!}f4iAd`YF#JFE7xDz_e-&o^iF#pwq=gux zo)`Q-_CFZ@ACC{-uOa`>&G7$tJh8rBIbA%b4t?SC{bc*$|B;ig<^PeBX2v-1{~rDP zbM^o5ej5HCxj_6p_&2Izj3LwFMMvd@fc}Oxp{{%@&Mugad}|)e`NTB@c-Nl|Bqa{Bu)K4a*1rOyg#?) z7mJTr@w>Ig=%3TOR`~Jb^OySZrImAy;XkfyHr;5kC|DpRxFZ@c($c z;1kOEWycf8d)0}4#zoTqQXkWJ^rCd<&q*y0^8Ct>_kDNOX<(c%IYs?Hj-Qs{ZJmox zy>Vd4ulv+b>fE&*^2m&vwP>XN-|4yg)er2|xS8hvk-OGwr2Zedn|u$4`oH8(lK&3> zk4*oMO#hGEO!DrL|L11Z|Gl@@0rmfCN;~{NGX1~HI}WJ-SGz$Ct^Z4|)3B!ce*?n~ zs{hxdZavNaBO~7r{@>qU9aR6Xetlp4UpK@5Bf}3w{$J8GkI(;;>EZv8TS^`r{6BIX z38;@f@k~VBc3#h&->r>y8dOmKkH;q>Jx2XM@@+RxQ2&p=e>)z&Tm3)s^AE36|Bt+L z^BwB{kq>UYU;RHf&)PaDlI(fvUiJUTdp2*-{6F$D53W)FkH5E@?^>$ zM*UwN&p~~C`G0Qq+;O|L_vzVH{XdS6Zk^jZ-#>YOq;bdA&V#cajO6&D|Htvzx@|Mf z|07>JKO)Ipnl)1YkKD6$Gxh&?euZ@Jsri3oeBTcL@6fP)>i?@9Zt{_6jc2Te^-|BswMKVAJl{vPGdO;!J|oJTq> zR@JlRA-`7YiHs~D1`?nPF|N8CkY8)@$7aSSa!#HMosQQ1rUyPjEq82NgC)ebk#oGpI8_;%RQ~5u5BS>sKCZVP50U!6*EmUhLHK`U z`hVnj@zdb{k#YSE|BnnGu*v(YjPd;&^8Yw~k;e!B&lq`VlK)3WeRueOx{XcTnq-gd3j3*9K|BswG zVW8IkC8vw;hWtNrYFVgrsk6tnCr!RT`*F6{I9c-BkpIW=g?g;W|0Ac!_igh0$@Vv{ zFi8DBjxR9k|B~ScqW&*AR>lwfKQihEBma*)D5bOdf8-#k-wOYa9Fo;d{Xg>H;{NLY zkw;97RR52R{J)Z0-nQeHC(n!E|8e{zOqA~%#s4EGO&;RhI`*`2s@xB6*zuk*z88i6 z$LWzD2>;K`$p0hb`%vWnk>MvdD*M>Z7mT;_FP=5V-cEa$Rui9CN0H_wmZ|M7e;lJf)p zAGtu52mg;eWOJWe#nf9R0* zPUVRej05W*#ticJ7XtkUSqz_5aAI z4~+ajH&<=Ez_uUxeDMF+AJ{+me`LIW{v>>{AH)CS^056)iMX z{V4vQo7X>5&hUfa|FNC^ADR9i8OzK4^)@>`;9qZBW(*(fuExua3!d?W? z+XGfuduD8uGwnz@CngM0|Bvg78!6vwi~mQ4zXt!0;|C1?kBode_89{G(|_LpQU8~Wy(e>`64G9KXnk&)jB|BqZ4 z8>9XoIbZStxBa@w+Tn}B|6@CRQsn=U3x*7Lrakmv^lg)4ef56BqaEb`k>R%@|If|v z|2RMLq~QONasI&nBjb3%|8q0^KXPFG+dy9~(B}*E{{nqBod53o>p=f6(AUHH>^Hp} zFE?X6yBX(~n*-Ye{l7rpFfflWFz+ug|M0)%?~Mrd-`|m;{(fQL@&fY~Q$zj#UM2_o z=L;qV)a(5p{$EIMzy269pr;?l1o!gep#jqe`gwsISpPRL|1Z%0t5jVc;JN%HYRMO%-VAj)7Afr{=Jg=faCH@)c+%o z&dFE*@3|S3H2-f*UZMJbl|HPf{@<9UvI1+LwQ`yIf1G}{_s)7g+j3sNe1X$oY__#eTed*+|G2;7=g(CCk34VoEY1HT-@3?` z|HuA%e8D2k|0BPA=iTc6k+@tJ12P_cu5sRQ*3P{65tGB?pT? zkNm&8{;8_|-+=Ie>i@C5SBzY*i2p|plD{|Z^P_2iPyIjg{%|_E&o}YU+}t>zzIVgQ z{^z4pr-tA3RT}!|`QiD!dwHl2+Qkt@}#q4|GYUS-L5fd5BE{a^ThWapayM}|*0 zr^~IjeDK-3mKs+Qe>Th#v}fB4LE&KqHc-lbQ2 ztMB*b!#@9yyzilV)&C>Ew(T+X|Hv=zdeP|`pKJ3U@g7wF4>ece1HO02tNtJP{Z|gF z|3`k$b5Q+1@;m$Xs{coRa_=7X|H!K!+NAy;`R;Y=)&Ce`MtM!T;m_mr6b#^8d(Xljo@aN1ifej{1M(>#v{d zL?0Vr+fzDyu5;b-;l{;MzxRg|!;Fi{CaM3&^)FeoUj4r}8}w8EZ}%gQYW^SFFT8PF z^Z&@7OFduY|8e?ruf3-JANh>bn|=R6gst!W^aeew4e*6L$??$k;3|JaWGL;fEb%ZLBR?E}OAb2IAyl0Sd$Ap@ z*-f0|$38O7nbt@BKhB>uIZXY(>_@&)|8JDMKY;&7j+gIk;s23G$n&;c6W;X*`^KMMXIIZ>Vm=5IgY8M60^`g?Kmy>M#5o5pzl3jdGOr^)lMLAzhKcGTD1 zvGu4Y>65S2@5>h-@KVle##vH-L%y%}bd$Wa>n}eOohQDZ5wkOK>&hY=p z@E_s-krT)CSO1S3GPb|^f8>GJ^8d(q{>zZCwTo8kYF@q7>Yf80Mj z--G{0h7Sn;j|^WhG~or~>u!v7;99|HcLo8kYF;b+1Bb2I!uGUkW>N5=c5uV+4N+mH7F=Q}*) z$M3zf$&Zo$$N4cm{68}C3*i58f017R|BswAEk^7AlJlky)B3;U@zaN@|3@Az-*dzN zBg5B|_e*v>!lj-R{68Kq)R$V(X{{Y^JP-dmZM8?fDOcYQ^?mpLv%-@a@um8HQIhvC zw#jl&j{z5bd4JM>uO!^&3CsCHeZPFkqk{iOj-QjL{vSD7_NV&gMV{fee6Bv%aCzSR zZSDf&L6SH0?(1`nN67nuU4!Nr50d)4sQ=65A%6h%f64ul+iLzFx9_^77S3ZQZ?Nrc zlhr}}Kkg6m3gG|AGj#R;21@-!_;?hs_)!?|X(D z50!kvPuj%T{=(;j|7ZOn++)#T8xQaa;s3Ee!SMgc*uT!-1X=&%{Vx1J9v@8qbjx0L z{NVe+|Kstb|HttHj_cadlm6gm>i1#(XC7#0jC?@&e{4s+CHQ}2)T^vk(#$i;d%^SL z)+eJ=#mBnxUK8Uq@wHAQG%|+&_w1qi#>mUt5L(xGg4B1taeFO4hW}^l6F(3BpPRql zP}z?kTUyb^H+;U{-#OMl@F%*w_|HN17a0B@j|Uk3AGvT*0^ZLU=PXJ^-h&^@`y*rc zeDXfZICViH-ftNvOaH+CY%Ur*k@8N+Xj*zl$w*Umj^4F3@RALoZ}2mg;eQF#B= zmu!9DRVQ9BE|&Vkc^jYcV|o8;^P^qfCmWBF`o)q@V+^0LwD>;bakr*QKHeR+yirS1 zouIO{#_$Q@|8e_JpBVlh8UEqmjknnJV5ukW$KAJ$x9O30cs#7okEb3>GtOI>>ZEKO zVe^CK{5r_9^V1W96oWD{+N2ku5j}JWj)n4`e zoZvd@|B)lwHdX(R9Ne^?`hWed->3dx=cWzS|8q0)|H$1N)K&kFjC^ zer@&tnsz;){vY!AYBfI*?q>LZAAfMb>ir`B&&}}vj2qN)zWryKG3vj<|C>^DP<_CL zjq9lYN3JZ74;S`&#@ZcuoKgSjgAtO*>3L%My6A+oB=!Gze0I%RsQw?%@2ekwq5dEF z`_C?^|407m%dge{BY*eh=j#8FzrFaG=Kqnu`Qn25e{M$pANjX)XVw4X@9ovg7q$K` z`JYeDY5iaF)i1vEdw%l#yKg#q-kiujbv)`jHkao;ML8wLwHsD&O1_(5+@)7bzxfCC z=%)T3=a1^!+Zk25IFkJt9^}ja2M#-Rw{g2} zoz?&2cb+=UQOfVxtZca z*EUWU-w*yDrw7CTBWDUH9Byn3-@UZBX*o-M^f`Yv_hYG7ZVcafTTokL)K5Q`+bN3I z$Ck&&00Q@6J<)_-MBU*oK~iO&4e{>EuHk5vDU_m{=9hpYcbE)-u4 z{vSC<+Ts6QzwA5xo((=5{68}Mxqc0X+4RW28+LGnak|{EW=)DSP7%LoLX$+}IH?bL z%i&~W_;qWpPctr)`&;;b+@7)W{RI3!a-QTtAHFfqkKb!uXq+NG-=#N-jg#?xhWLM+ zKW$c|`hRYQ|3{9x+2{X}V{RF${vR3ni17d14FAtq^4#G6@pvKc4gMcFMHv1cIZ1p? z_-FS)i;QtS3IC7n$OnY~$MHk|&&}}v$hdw){-2xS|B(~rdKvzoo8kYF zQ9l^|AMdx|6T<%^511UG{vWwReoyuP$ju76sQ<_7`Ig1q)&Jx5Ir7-x|G63dAJ4z2 zyq@a+xf%W+IjG3z|G63Yf4p9dk@~Oj|HzRUKL3x?N9Xr){(SKPYaby#;Hy_R84nyg z*tsL=A>#<~|B5$0Y#cW!)ah~Q5#vO;Kl-izW5x-RC;!T#&BnN2T7TkkW87~SHs4~5 z{PV75Pa3D)G}8I`#jVDvGbDfX>NaEeS!Hcpk})i!Fo^$+gXdaixekKzCE_~3g& z_?(^e!mh3mi_l0Lq zA23G!2l#*7o*eN3r9MOy$4}i>~r^82X&M~=?w;WXQF%=#}fqnp$5=huygr?z+c#T+*tmeLOQ3&z2cKN2vex(A z^0^uM(U%A|L11-e`I{04F8Xe?~^xQ{mnRftc-v0|9HH@ z3I`zn-Z&_yzjOZBKQ>;PMK)LekK?;jcr*3?c)s);+E)EPazsR5r_sF?qB(tJq`%Jq zf9=r7lIVNxk5#`8c~t+DjW$O6pyj20JZsAsW7Nlm|JU-bk?ISA;s3cA{-2xS|B*8! zA8&Ka#Pa3I`p%7>WSk@Q7vcYL`*P)dF8n_-d=~hBZifHI;>YXXo$JTPf12mV@c+2|^#928 z|Hv_6!Rr6H8UCN&_K5$-cKATZ|084j;s3cA{-2xS|B>Mf!v7<~*FpXt8GaA)|Hv5; z;p+eK_+&;#sQ*WX4+j6w&G7%oSRVX8GWr+(9~nMnt<06i!($?yr#~;}B+1u<|HtXU z@c+oU!-lE<=VthS+4z1rxAxSbL)8D{@c=KHzrot` zrQU6;I=36c2i*5iIm4gJ>vM;-qrZOjlr#G0uGBlN9sU;lKdx`6_-^q3$RkD$bsAK= z#~6OxbN82XzDy7QkJBT65B?uHP4bW6|B;bj2>;K`ho|3foGp2NqbhDRM*kuIkNt=J zf&WLw{=)ww!!LyYN6wKvLHK_>UhvD{|B;ao3IC5=9E<0Nn~V#jUNrnawqyV5FWwa0 zEqR3ceL3+X9dF$SjZ;UARR53d@sbA!|Bnnm68@i?;s0^@i7`>?|G63dpPS+Txf%W+ z8ROaQa|HT-$wU0>$;L+n`%NF{#|8R;IG^3i5A^Q>{k%X9^!WlgaQeXI2Xdf~80aeo zGJX%-+yCD7GB(2MkLcmwMhSC)E~ z?&+%pw^pfACH4P$ovP%0a?`8P zj^vvm|Bqa?Mm6>S$jy3&sQ*_w(C7d4jEZx-(PO>0@2aT2Uwmes(`I(5_q7&2-!Hpl zoD=aviTCft6*TW}w$!IQ_wy*@hc>KslCz7w-Tv*U?|1ixRqFqd*DPPG{vUb8vW4pZ zk(Vr*qy8VcWd3aR|H!2aZ&Ck`JY)V`&Hp3cv|yh4f84&g^QUY6A9>d7DeC``=glco z|Bt+A{$%z4$O~k9Q2&?vKWFYu>i?0;W=vQAk34V1GR^;E|J}Z7wfcYL#~#?E{vUbk zL-(uyM}B^b&;KJoB|c!nl5{VR&$G`wq5dCv+t$a`|0BQfyf6Qc$M?vNr`7)>pWMGo z{Xg;--ref|kuM(d)&C`*-0_I|f8^U|j#2-QoSPr3^?y13`UbU8|Bu|OPj~hI4p;H{ ze*+|+6aL@YN2;j*7akg>{vR26%kclm0|)!+|K<+z`G12W!nFP`xkt3WKioCo_jRD; z4Z6>lrqu;q=Qn&=HzQxp&8P?D=0*W|p78P9?X_y5Vr+T7XQ00amhTU|;|Ip+^={)j zb@6?IA4`6*G4k;mZC+;#pAY`uH}}P>|A+d!@c-Nl|BsCA`+4{}@ATgj)aOIJBKUv5 z)2u{68|bANhY|`hR4+f2q4|rL}`^Y+TL_ z#h--#$L(eQ9~s93^?$j%+O?&=u=syu_<`{M$WGNNn*T?}?=Ad4E)NXWOZ`7MR`CBm^z2jr&&}SA*Xx(zH#i0&W6JyZF`Xahx)&qAATVGKXRJ*e(?Xu2~w{Z{vUbT z#4`2&$h)4~uJwP(Z|&Qu{vY}Lo3E<>NB&Ie?{+yGWy|~Gjib)hPa};#62A}rAEyT+ z|Brn3xX=G1!{-}yWstRhBEBE|KemJ6|FJ(Vh#v_5kNmm#b)H{BZ2B)GAMd{3gN?rw z9}oT?m-m(A^}+umUzT?Gf8_IT9asO4j66R0e`NS~aPhc)F#c^U%ge3X+onJN?g{n( zY<}?v;s4q6!tnpdU%Ycd^Z&>fW&OziBY$@49Veht0GT3lVJ|9g$` zeC^-+q~7l}#`87!e`GvgotE~tCuG7`>i6YL5r64FCyi0R2L2!0H9anck?H?&`|$i0{vR2BAN)Tu zricH>`SJb&{vR3jUEu$5`h4+4;s23S#9w_Z^d94MdER{Q#k-90Jvj3JIDNL{Q^Nlv zkDL;!{vVGASn6Hc@dLyEzWhIVhORziXnJ?`|G2*q zxqZc#nq>Qr_iyn3cs?db-iG)+#_(qw)E;YGD8DE0|Ja{+-}CwDVr$3y1@VE5)8&2a z&P{p7$Y04ikz?~Czvf`?EI*d~Fh7R>$Mxa&5B?uHRqFG?|0Ac%`)2rmi?1P zJ{0~R_cvbhW#Ip@f57nn*nfDx3jdFc_uKIQ$k<=_f9!vp53$eovEzgHeenNy{J`;F zcC+J)`gX|w|ErX9LH$3h{~7WB$avol|BqZC`7)iawD6?PJ+HpsD9IOs|3^ms zRQP{n)K7)~M~0sO|If{bp04BB^zb=P^U6;~mq>g2j89$&$dkL+sHz_iUt7r- z`GHSXu3(J(!0MN;9_0S!Ef^u^!(V>-~}Tl5xqcDdM}mP|jH1FHal8AC&jM2RR<$|H=DgV=PbJPa98?{gwCK z#*-xv@UA*{*z!tb`J>OTF~;(*_FrMsWBGqAU1IIXS6u(p9Ao%`k|%16e7>7cjI;T( zm&B|8$MY#?X@b1JOgl(MePZ~3+@I0n6T<&v|HDs&|3}91;s5dY7cCg&?CA9O0db1d zC+aY)lXGj?*TxkFbaQgHePrx(XsZ67Wd5lS7}BVr`hVo$h7Fv%>uftf?%Alm`hV+7 z_Fl^aYydy+Kt{cN>hlGQANSnJseUZ=2#oRl8T>y^kMGam|B>MX!v7=F|0Bcy6TfeN zhr9Nv?}z(U{O4x)e`NT8sQ>%hb^F!-!~HS*KQi;? zef5J^8q@z->i=>7 zQhNre|3`MJR#g9w+(G=fvA0c+BoFM>NBuu?c;6uP|JZ+#1Nv$HAN!yFA2~Rvw^QrP z+DLN0-rd#ztDE|NcvTendE&-l9L>i>1!wnzOx)Te;|M@HV?zaKpk zncZoR`hFPC@c+no-UI)S+_qVB=dG(1qWF8_bZzKN*jU-P#jrle12rBb^_k)S@%Jcp zPQLiiwXMByUV`(+)w;&{x5S~oxN+v(c<1l_jg7PCCpxc%Ul+yk2p{kKsb}Xc82tFbPWcW3|y)(~_AMXEG&0c7X`>lE#78~P!4E`U-1Fkob z|3}94DEvP%{K1Z+mf3g$_kLlyAH)CS^tgY4|3}91;s4qA6o&sthJS?oKk`8FuaN&o zZX|vl^8a{$cAeBiMg3oLf63#6|HtcdF#JEBuk`=O5jowp{x3OL^30L{=VthS{C$YZ z?W6u5IXtVU)2nQwwfD{Lqy8V;gXQ}I_k^diQ?*U~+m9_7e2!ev-ph(V{rn{jDotw@%=O$+al$=CF1r$MajG!VaK@=n- z(Dy2+7|Bt|m@tiw=^MxJ+wX4P-F5HxU*r1L-?e59&pH)ORh_zh@2RKWjo+K_|Hygb z=RLajg>e2oLmuGsH@sww-$xrW*7)#@(slNEg88AU>(?8@|C9GgZ2Oo$X!rRmK0Igs zCOhAlKYI7@Yd$RRKic&vk@rdE{Yc|dd7pIHL)(opAJOCd4j=w^k6p%iUs38a7$c8u z>EYeRSii9KUgIqJecA5La$~$73;&PfB~$7N!~Y}0zk>fq&M51R`6oM`w9)|e|2V$V zrG7B-|BPk4A^(q@daeF1d7z9J_kc!K{&9wN(sdEsLlUqj{dcxuB7FW==2bOGSYlqJld*E|pY#;s~|30Js?>%F` zGA_P7!l}LEYvVD}4*!qKkCOV#@c+nIAO0U1^@F26{oZ)+aPd!i{>z7pXa8uNH++Ee zOZ!2ct|4}t&3?ZYR5 z|HtQ{@KNCZk@Lg*I`IFyXK$Zw`$K)tCgT5b|L{$|`DMEG z4?an!#xsr4KBD(5W3;czneD^pCeJZO-r_Bf&NYUAg8V<*U;jX7)`yjh{4C`Eu^kNm zj|^W3{vR3s3j9BEbpKus{6BKcfI#*C$XFl#A2~&ym&5-f!v{kCAFmJmH01x03&rn( z|3}7nga1d)3J+2LkDNXrSp7dT>Vd-lBPYejsQ*VU9vG|sAGstpPW?Y}VNAUGf8_kA zSk3=q|LOmc;j_X2Bd1FJU-*CIH1Xl!|BygZ|JMJL`^)`&(%+x+XMcYVpI7enQJ>q*{_XyZdeiRZ z{qq8mZ}{KZ;RCzdk#Ff{|Mih~>2Ci!_CH>He!AC>=pE?8{{El;`u^uLDa_YD^ylnQ z-+IFSd5!+dCx`nk@1N)ApZE87?4SSV&;GvP|Ke-@U(tr^)&GMJi2T0^^(*|pnVfFvW(fS7_0stxpevz z_5a92=T!KAsal<9QPV)cA6GjbI|Bt+I z+$i<`c>Iq}ukioK6K2g&|BrnCBM+*E778v#eev zBmcP7fD~`fb5+&%!}|a~4o&ekomNfr{E+{*^SNXno_#jSIG|sUbGdc0_guRhyeT2? zMFh$H`ci3;yg{Cwn{ShPwr*}J^=#dYdbj?3 zaQbrZ<~tMA&%^e6efF?1mWTh>rBS^4f7m|!KQgut|Bu{6^7r8Xk>Ml4|Ks-I1H%6! z!=GDr`XO(h!-?wq!B2+&N3JFQUEby;#{I+xg#X9(J~!Q@{vR37Kj8n78`ry8{Xb)= z4+H$!pAPkZx&EHjE7boZAKboC{Xg=dy}Q)^BOlze zQ~f_URq+2#NPX_lAJ6lWkL}!|`G4e(q+a*qD|4*i>~H z@$7Xz9hYwXz5MomXTYR1gNF++8B%X`xhk75B?w9KNbHD{vY|2_<8XE+zkJZeD1?{ zHUE!H|Bnp65B?t+J|F7;x*7F<-36lSkG6BY%4M zkote*&yE~c|Bw9T(Ie{r@%mgnc2xa8@@3f{mgVxFo;;%dANk7BgX;fr`Ag#a!T%$F zE_s4)_ULH$7y3IRxP$TKV@I5T{_TywIDOLjBBGtKzyG&;!+Q1qLJnV5|L>_qcc}kI z&W!A={vSEIu$hzb`)SXA5UoeJmbmO?y#>i)b|Htvf`oC^Q{vZ2;`DFNi zWXw0i|0BbX`{1spefW)TPx&zXKQ52`!T%#C$^0$+KXS78UGV?N$X9^>M~)oQ1J94_ z{HG7o=S#-9V}jNHVEBJ4-@0i2U(fd! zcshM`LC)FQ2s~ed|3^k%2mC)Wo}Uf+_Abx1Iv3R63X}KC_Ya<9+*6(>wLd=7IG`+8 z{XeeXF}JJwf8?%`H-P*<_NU!7|BoD!++6)X_J4rn5upBW@0TvC|JOgGjrxB)-hoBk z)c+%==66&7kN01O)bE1-N6s1CQ~f{kV3}Y4ZQ@{S$MZq>e{84!M@Ic#_W_*4M=lsA^O55Jk&(ag^X?eiKkkR-BO~ql z$IJ7CfsMoLd?ic@RsWCY56?^C|B-RM;s25G{1*Nn&wsAmkMRF^eNx0Hh5zSf_G{$;~~Hz0a%fhkP9Pf8;{RbAkUyPM;O)tc+^p z`LO7m`h1y^r}yXU^^M^hlm*r`Mn2#VEpGM{+_cddcuz^ ztLDRxudd>G{KzMsfO9WKAU|(vOUH*d^!-mc+sp2Xcg6<(Vq7vu9%g*-V>$buBlQ-m z?EKC+Z(f2kebHCtJRhj%8#eJX9~L*#7{0{2p`ZBh@9&%{=k2mg-@UodjsHe0?}mamz=$+$#(z7suO z_TjR3Ub6M!`*nMAmGO}KGQ=-gVLV|$mQ!WvW48Wy@&7&?@vt%dKlTSK_04U4>|g4Y z+wp=Wf7BTLKb1Y+7(V2_?}yp?8RD}b|Bv@~wyY2Tk33eEhyTaVn{n6tKlW$HJ^AYY zku&aybIRUnZ`*Gi;!vwX-5`tWiz%|IQrT zss11QK5>=ylDjpm@c+o|8rM_*@9WH6>i@NFP+R@KP0s7;{~`bH&Z)QWeRIL<>gS;z zaQNb6W8?wWc&4*4{6F#ajN$)i@mm zcTa^6DD#2hvW1eb6CbeNmj^=w9^b1zpL1O;r+$Zv#?4xGaT*T)!FWOcRQ3P3{DHfc ztN%xS{-KAQ(CYQWCVa6+{lb-t7C8~mHZ^`~@jXsV@3zJ(9=uoT6L&R!`k@D%d-nu| zv41Z-{txMIsPXG}&3Bfc8EE`iQK|Fz=v3oDDe=zAUvrIbllhJp?k_X0+pK}JzR@V- z&b_;#p0aVDUV+Yzpc%#?fkEp3u|Ls4z108X`Hu<=(ELAgU~o_M|H$2Yc2WP2*PH$y z8UEjU^`8nOGyjj{8To(hURxDL?$M^X`hOh%;Ia3u3nPcOXsP*skjq*zz1(S5Y}VdcF(Z7iy~UrZQzs! zd|=$JL1X8e+(X8FZ>^{PA3tB>JGD~(kBsk6Pkwk~I5}@_w)%hM@$<5snbT^A^Ydrq z%v9uy8s|&>-dA62V2pa@RhBji=idYP^v&Ab;=|)wH4W$AmqC(GTYXD2_lrHhX2R!yZHN-y}qk4e0BJL{Jvfy+k^i{E}We#^*e)&3uY%etG9)O^Yr##3za4xz-MC1;&kWAVGKT;3;~zQ3@c$OB&G+G^nMKC<{`1OjB|aSa;vi$xCq9-s z)Hp|czmdNVH%5J5_;2 zAN)UlUk{QzKKOt9{*aQ_Ui1IRNjYuR|08#jJahPewEi#e?t~ zkvj?_|If|v|HuP#+N=LZj+c7E@c+okg`J(}Ql7KVhty*63!hwN+^MLYGqcn4_W97U zu&s0dovV$L2T6a$|KsOL%HXcf>5(tm=RwZ!p3a(0FBzA~?}I&0ueIeyZZ|>i?1R#8-s>N5=Sr|3{9`ZLj_x$7ibe zwmUXU9^kd>pD%t}%pWI>)8+j>_j#ebA6XKT-v`XBKB*bYAu{-2xW zeK6x9yx&`V)p(e^uYCJUUl~u5JjGf6{MvYeM*d~vH9Dbi>~*diU4*zvQHTq3Zu}dtmr~#^T?>|8q0^ zKQjCe_m|3@y6JTdrxWcX+B|H$xN;Qx_xLqj$HkBs%<|8alt zBjNv%W2K%P{6F>&{vG^3GWM!iw^e`NSB@c+p0E#d#Mzwn>n|B(kv zebK1v7uxb=;uD>Jw34&K<@`(jAD0Is|BsA%wDAAPr3n@OA9-+mg8F~tQt<(i|3@x} zj#K}SO#hGlhYyDQKR3hwBO}ib{-2xS|B-S3T>83_;lsiIV|$6zF&tJZb7x;f<)R#v7--P-x>i=cL3{d}%4F9p{@f8to zz8~eSS5Pl9U#{OR?N%CN`|nHsAD0KuNPN~9`|EhRlJg`l@WjaHtR45my+2nn&Trto ztE~O+>i=SWw;$rq$R~8SXG*@6oBe&X|HXcOApC3h`u=%${&|G4GM?SbV#@9X`Y|M$P@|MvCu1O3mBzn_SD*6#k}{&KUw@96LU!Jl?7@9+Ql zGkiSv^8WmHe&GM#Xz&Q$-8JZ1K5_5aAz=FW8zKPt5T+;i6)=c~GvJoSzW|BwA0 zGhw_F{A7V0Psxx$>i@BQ+>l}F|B)w+9PP{;oM+45F{Z-*09Abt`gs`$JHz^dG)gu{vUbm3l;t!dBY2<)c+%Id3mk+ zf8<>+zoh=(+TGWw|L2u@zwrOad&M_`|3~)hd`OI!9!taC6H|}bx_xzTs>i0$U4snhIrg>KnuBQH8 zL{M+%u?eZh!F_r;g)gTV_YMhkntz^b+^27a|Ht)_2MGU<+&0L!KDTqTuiw|AhHri! z^6uRCBi>(jGv3elVVSRgspq5K>8bJR^I`se$TQ2m|NJ3V{XNX@@2^?O4eQ+KbeQ$9 zwc~whdB4Di;s0^{=F$%Tj|?9W{vR260`ULHc>VzYkNrVDVE6G$y??ArP~Q*!9Q;2r z^Z&@m|AYTW#{S{|k+FZ||B=yu_`w2de*v^9BEp z41aRcPbJ=!&AX`YSJbVm`hVo|WlPonBfs?c67~Pcn^!-n{@h5tvsw9l*lANhi;5C4yRWZNt1 z|B?4R`?&glU5j|0C1? zb2IY)$QM35p#C43{vY{M$T`yzg1J3zZ zfbnI?<2(LKPhzvGWi_ke^`-iM^Y0z4{vUZ@d{?Jw=Et6YulhoLzl0&})&C>sPYPE5kDMa!SHu6~_Th8E z|8w(#pN@E1?f*=DKloi?=MH(kzWS;9eDIa-TyoGjWn75(F&}#3KD(m69{jRbs(fIK zJisAa-!skdca3vo`!fG&Trj@E|Ks*BANKR^{hoTYuBg9<{J*Q?_Zer7mG>cA zylI?0M)J-Mdwm%GpRF(cA^bl#!~f&{GG)FG`G0PP|7SeBzvlnB8To%?_;~RD$fyqt z|BoCa^?l&~xf%W+8U7&rKb~(e{68{$!}0¿Kw{vWRw<~QO0xf%W+89o#IKXR(f zcfNi!T%%2iysO9j~qNY(D}XkBX)iRhFAE1Jpa)nx@rC& zIdOcD`hUEB(YJ>8xca^*f_i@AnLCLK&|BsC43#k9g;|aLt|4EG<_5VWCTd4ncF7UGYj!C5z{vUZ@ zNiX&Pc>l#o9wGcca=bi`LjE5ac>?hN$n^inS>m4||BqZWIY#|IH^cwq^+}if6!?GS zjHxl||B;KOJ{ z#ex6F^$W#UfdA)a_%NYLL+{0UaIPTSrK3wO4^*${5FXbFhSbzNa=X^M1$J55h`wRZ# zAGSX70RK3%%osl3lVK0q^2L((C!cTD4&L?STswYn#0Qg&hsgF1tR7=rCf754)*#~? z$p?i0$NLKm|BqaJcOvdbf?oj`)OZ__P|G8QGroBl6cbe}Px8Vun zHVx~*&)Yj_$}aW&IyR`O{vWx0J@|ad){gu?_ z_H6lOm-&721=Mjf{6Ak_WK92$?ezbqzxcZPe|SF*{vR2BBm6%%!~b(L{68}NKR2)2 z_Oi9Z*Mk4|UWeW417dy>{$IvDdn)`t$-9UDXDsCq;QtwSl=@AQ|3~g#JVyOL^1}Nc zSO0Ix@!jhG-MipX_5a9EFJ7YlANi?8532u1MmzjJ_V3As52*h~estbE_5a9i>(o*I zkKC@tE$aV~gPL?y|Bu{R>h;3^BX4o|=Rfjo`;2ZJ&c7GPw>|#T zEyly=ra5=azs-lm-w)^CAFU_+M@t``x3GjtCaZglk3Wi zk(b;peTZ?E)HiXg_8)JR=e;glR_;K`@c+oD?+pKsJV=fQ{vR26U-19P`2G+7kBslf@c+noe+Kz~{C$S^qsG>MIGo?# z@%s_}A31thfck&@{tzU2;$2NA6P= zsQw?h-;mzw|MBxhf^*dWBgc)8Q2&q1qkb#=KQew#$@?V6BjtTP_zk@*$lyz!EcR=U%;ROXlD{Y>LB zneUSM8)Nu=GQZ=)GXG;-B=2MGzFKZvBKhs`|2SUY8^ix27fBvG^8d*215y8%jQJ$w z|B>;2C-VQusU-pOef1qX-t3az>i=i?3H<@+l9KXQCVXU+d32c)-E|If|v z|Hug`?bZJy$0fDZ{6BK9jCSh(xf%W+IW()A)9CYKcKyJ}|Ks)SC;fx}$Lk+f&`bS4 za-8ttgwxgzhX2R*jKW^(|G63Yf8-pwA3vFP*2Y_&oIlB1H%^oD3;&PfGegF={M#7y zo#FqnJ!_~upOgGQa(~Gah5ttmmApjwf8_Kb{nh^?rw#6hJa}u*lKsK|V|&4<0qXye zM~)U>O8h@J!~Y`}%l!cVk6a+*2mT*<+|VHP|H$LTH-!I3E*=@-ytm;;lHv*OmQh=QBR#Hue8_{ZeFnRR8=pyPk=OZPfqc^^Zwx>)bT?Pa6*dliE2=-u%lr zI<}{?e4!J;<-y%vzAl2}-QTB372gQ?f0z2l`1pV1ys&W1|0BaU+5FZpTOR!FmEp!I z1Hzro*N-$#4UKR{v>9cb5E`!jAGa4jAWZ!~GV=A{|G63dA33?dygx7gA2}hUzvln( zdE3Cg{hjG+CPk3r`iDAO58Pp#88X26?#nxkGy3#b|Buf@!SMgc+5N;PlKek%R$r+{ zE&d<34~G9ohTn(!zvN`eLxlgw{zmr-R{xJ28yuqfe`NTF@c+ojM}+@JM*T|oe`M4P ze&onJWB7(6XWZ?>@c+0x{7CqJZjS1Bj}KqiQOWRYQ2&?5gS^DsPA;(JbH)FAeZ;-S ztpCgHYyDdB|Hy?A12q4SjJ!AG|B>M@!T%%YN#5Eg7w?a#|8tc3T4~~oJuq>hac)AK z)A!Fx9vl~~{vX#b8yKnn9~pk$y~`i4?IWKK^?&X7q#gdBo8kYF)1xc=KQij$!v7-| zi?0U%j|@Ky{vWv@x}P(p_A=W)82NwfU&+7$>i?08WBRNAN5=Vp|3`)&3IC6rC*!B{ z_(yyg{vY>`yf^rNZeG{sF=LF6xUH3pd^-4l9RKj!;QzT9{vR2~3;&PXFOdGi|0Bb% zg#Sm*lKQ>y|H%3AQO+YBpQ`MCT%^|jR@t!qopGr^ZIB|2J?`r22ng_<^9>e zUbDXs=`hEey0qXye12ePL|0DO!FI4}JJgI1q`hVod@4ip{Kk~{&52^o0 zUbSSo`hVp6mMl^Kk9^PK#p?fgp7_)ARfjht9ufZz{vUbn__59%xrJW#e{x~2=KryM zQeKw&f8<$(dFua>m)>4c|ChYrjyp8}kK0@Mzys?4kykzRu=;=Gt*c&8|Bt+O)hZ`y zW0v)2{p!`~|AowQG+*%r$@i<{D*VvQo-Ne>BM0@q z&8e1`=1qRHist+E?cd5-_>WX$)Z1SBiuis1yk31jy#G+^*EH{ll~vXE8_+k{x!642 z`$$kV@2kz;kLcGY(0QvM%^1Glx<^xu@jmrK2UCpuckS%labqR-?cCAH8<=eE^`*WF z$FBZ=UEe&uHuAo|yS=0MXKu#)xj#qmd(<1&DNcRA+r(#s|L11-f7=fZtjO<^cKCm8 zhW|%y*s!7cf8<7u8fpF?xkKY7>i>~jNge?FKQjD8_8MeQpySA(U$Ne9Z z{lotwACY`P)c+-)^zPRDKk|_`_NxC!KDN)J{vY|w{x{VBBcGG{P{{uypFXf({Xg=V zci(b;eI(A>FYMdrq&*?7?X~lHeCJN}|9Ctbwrp1akNooH*VO+bpV+)n{Xg=ewzMC*x1W7o6Oqy|=p5 z{2jCWj|k)ib`EK0jO8yxv^DWcb*sE;!6`HwumJ$6}rzii1%ga1c{FC+7lo*O)uD(daZe5}l08l(OU z{68*VCeKS`{?pnsBp<-J@onQI*&h5qZV!2Z@c-Nl|BsA(LHK{ zr_1~r{6F?5L*5sL|L11-f8@+-{vR3jfZ_j<^TqFj|L11-e`MtM!T%$djE!>O|Bv~Zhn5g>i_Y0ddYk;^8cFEzNr3Rbb2%O|LT5zQT@L>dA^4Fzhv~U_Q+Aj1EgLt z{6C&A_-*k2$Z2;<{W$Ue$m!E!HUH1e@c+no{)_xSH^cwq^+}fe8TfzXbjiCx{vUbJ zj70VS$i-7)<@rjoZLdJ`9pV3R`*x*{e|8YEk;s23y zCGTT{_eIphBPUE7sQzE~V;`&kmm&53GB!5!^!?8n_5Ctu z4Ri{(*YiwGJ5%BJ&4_jS2G%i#?*RXg?Z^v)|L11-e`M4<9PxZr&)w5bdkXu#7y;hj zs)}*h+(c(!fM!i{2*w4nOM+^Ut+aE3YabL9m#(0GI6{AjlQO@Im zzt{1j%f|5czT9`t82N3aoS+U5tNX~bY+V@)j;roqn=Gggw zFZkKlcNh=7CsWS%C}SM&m-|YM3#ET!HfHi>~jrFK*QkK8Pzo%(-d=ay>f|B-|1)K>p5v&MGy|N7LctNvfZ?c3G=ga0PAOZTqp zvqOD9F#JC^HyrTf-tkv|$D{V{x}`hQ^L|B;a|5C4yh?ZN*eBkvFXAGvkS z8mP~^XZhzl)$eO{Q+3quHKzZ^cD%2K|J)4!kK9P+A5j0dk}LB6+>HFcyhnHW_aO9_s&*k>>~hkK8vXSp7e8KY9Lw z{6BJRY^-xv^}EA({?fyv)c+&nd7zwsYY*-z&$~01gz@@z?a)#EKXO2a)>{9U+_QZv z_5V2jSpS#fyK9G5>i?0k{-v}R!+1Y{;s3cA{vYorw6B};nsNJ%tdW`N8sYr=oHRVbIk4j<36;3^eQ!pJGc@65eMI){vR3ne(?X?4F8Xeyg&GV zWGoN=kDNU{TKzva!~Y|v$@1|3$k;#pzeVo zOM3Gk#=R!SIS1xF7S8*#R4;UNf)NJvBeg1%v|Hsd# zSn=(U|3{9O_cy2f&l=-U@%^Hs))`00?*aIK-2UWAG0v448;mE4Ke*w+SFL}j=iB$x zM&oR$f3Wz&*X(#pNA-4cZ{1>CHoA{9vi>$Z|MQI%Ma&O=@#zZpsnk_L3Kv_|#G3aLEUR|HtteliR`RJo30* z&!~(p>i=;(f|376j?e6%{vR3ji{bx~kxz*FzivL*?GqbMshMrn|KoT|miG_g|B+)e zZd3n{9G}%({Xa7D3neSp#&1$VCui)^tK;$p?+> z@x5`8wNev!iqB=bvoU$If?7QVaF}cztt| zTdM!Z@sg0(Uj08e!~Y}4$Mn$rKaOuO{6FLWkNS=9|6aN+TKzxx3dsK>!-qirA303& zzu^CoBO)Ty|0Bot8=(H5o8kYFqe8=+8lI66+fPNR&lNc!)EV)~C}ZR$?fak6KHQ@5 zSYzbf%?=u8jC#Px|KsyEJTHd-=VthSWcVKN|HxP#`G0(#hvS9+M}~g~|BsCNk?{Yx zK72g*f8?|v8IR)sk&^=g)c@o0yn2=$UsBJW&R1X0HXb1F zAHo0Q^5_rzKQij!!T%$N4+wGK|B;a|2LF#7Ej}LnKQhiQ{68}M7WjWWo>K7*;s3E6 z4F8Xe@q_$7GJG@S|B;dZhWfu`><|7Qne~6k*%5u!|KoUpPYD0d&G7%o1>%4HIPwAO zFL?Q{E|&hn|Ks+H#dmAd`axs(r*FJg$@!8`Ru;L$+TpMLe#n>M|MC0`ij8vm{_`PQ z9(?kyrN;2rcD7t<{YBp0h>ewuyt{^B%d8!|?}JK)PdBOP;mUULy;@$a|^_AiOk&*X#CFXJCqNs}czq}t%U$^CmC#)UZ z^y=fbeelj1PZ*=VF8n`kzhK}%_5aB50pb7g`eerqRR52h89z|{KXSVGdDV_TWyeeZ zkK=*<9~pUc@c+n(;)|}Ru_EG~M~ z@b&Hd>+|A%b+7O5zxn%%{_MX$|Ks~R{}1_%?)_&D^gW(Z8L#g40;wPEX8%0DzhmT` zy4Uyj1^UB5z z`ht%5e#rlOGWpL6|F7!x>i-os|6TpR0nt(F|B;iDlGOhr7Zenz|3^+QDpLQCJVoB; zt#iKEOMd*p2h{%~Kl#uSr&?UG*J=5O`h8C?UF@t`Tx7gr*#pjZhl;F!EAE@?Y^q<$ z^T!QS|BwC8E=W}WkK4=4i&y`TJgy*H{Xg>klP75XU-GP})71at_8z={q56Nu4=+>y zkNnK)=hgosuY3M!_5a8lUVKLVzg{!`@@)8FU&OjK&#M1N-t_8A>i?0qtzWJFAK4@I zd{O_G?A@_R{lBk6ulawQ)~WwTUh~W{_5VVSIqLt7EKOJcj~t&8uKwSGG1qB6WVc>z zo%v1Dy$AogPJO?i0Qr3_d4f$JucGyPL&X2=eNUP(^8OO`q5y5GQ9h$R`cFm<%0s^$Jgh>{G|JS!2IN?E020-ZHQ5SuW6$?PQNT)Uiro&KJ9<@ zsN~xkOP-zhe_S67|Bu|PNj=T~Gj7ya{XaJ&|BsA%DaijLqn--!~Y}W^8)#QWYp6|{-2xS|B>nck?}kM`F~_Q zPk{eNh98LhKQi7Auf1-Oaf_Sls{hA!)K7x{M`r#Xne~6&4F8YE->7Ic5F_C;s$&H^ua?=w%U|A!i<@c+tRd{O;BI8WbXI+2HV?9lu_GJHJve_S3s zFE!8jeewHFW#$^cw_~%@BQMAJ;FedN`--xSPl~U1t}M&=jMNYAJuK7sV`+!~$Ne1@ zUl8?w-3uLd%kfO^&=1ND_8%I{DJKMpC86p`*Ep<{K~p0+unKc_o}`c zS;>-TDDTr7UwQXUXY2NGtt?tI~^Lo_pW_Ly>MxHe_T3x*ulTa^#6E&f#Ls=zm&W{_n{8Lpl4&;rHXpI*Ze;>hc5fT^V`IW=KI0_BWKI}Cj38gq2&3={HAg7 z?Gft#u^oAG@c+oj_k;guEcJWg|B*9BNxfn5|HxV5_rd>jGyFd?-p7Xj=VthSJf74M zlJ6z{A306xgTVhIXATe4{6BKqke=%Qkuzm}9{wL0^?Tv}k>Lx%|0Cy$4+a0vSo}u# zf8?Ce{hT@THyOjq}^1LzXlm7h9b3P3JkIU2lb2I!uGS)}_ zA31ScALm~yp0wl7koohD$xj%k$@nP!?J;B2_kCpjKa69B_fr3l=dbS&nZF*g+|GBT z_J$QaK@;Q#UZBuL(1m2a2Wc#0Vp;XL@`Vvo#8tM3;*Hr(mjevv2WtF!9+Aultz z@P5zS24~gx%aZ3$UoE@WBQ--S^8Ms_0sKEV!~Y}0*Fydunf@Pnp!js~|H$2Qx~Tt0 z?vvC^{XcT=#M{*WV}Cj)-lG1Wo8kYl|6P)rs{hC1>n_g=7WTW{ju-RywRep3EZcWp zeZV2|zCHZE*rzV24;Ux)a^e4x(i=*|a zyrCP~RQCk*Iiqx@cCp}AAa$MV?I30Iq1V}etXv#`GS{z-0#DyzV#R* z|7q|SuNw~%zpv$`ZN}*TxsNv)m&{9bo;m)qG5S|}@FipH@4NWt%Xz(U{x*fJG%i|@ z>O8gQaa(?v_<)7mmm3d}{ok@_i80Ra$#n~T_|BUa*!IxAq3>*;_RihzsAS3STibG! zamoB7=Z=sPyB>M6{VRqMQ6eL%b) z2LJE<EsUe`QZCqXxPPv#nT&b|0Bby?Ur8{IW6qzv|cTQvVO{6Xte082aJHUFz$>XDrFPU|jQtDw_YdtmyTMd_b8_ zg#SmbS?^}`|Hw{sl2dD0eQWP`?-J+c9=91kzi6pb`=hqTs}?@w)EVE+_{sVAI7!2T z!`PpWGQW`aTd1*9y{`Iy?0@Udf$IN}Lj!xN|3?lB3Q+%#jQJ+`e`LImiu%9gi2ehd zpYEF;#`6~~`6=-K$jCpbl5($cNLR^+6913wVEBK${@q%&QU8w|(59XGe{M$oUo!na zj_+NGH{vYojv|s*kQyA|z)DxC}8@F!O*y*@#XBh8K~#-E{p)TdgGum=C?Lo zK5C5ozhRAT262(;mr zV_YUa5Bxv2mq`8Eol6VC`FjK3Pd^MSHpchUOD9W>Go(Mi&Khi-CH<}0a+opJZ?%7f zF?_||qedGKm-kPSYK}7=G4shG4lNm zT$yEzd_VYqJU-M{hW|%K-WmKqGU^+{|08Ek3Dx{RGQJDWyq^gFkDORq;s22nB(D$oe{M$oUvgwo zPv^evE5rGFAX@U$;s247OM9#TM@}6SqW&K_McyZb|HsdtB=P^kPCRd)H<&+w|HscC zF#JC^!~b(L{68}C!r}js)8u+cp0x2WxnIs5ec5=35}6#PFj{5|-8JpMt# z@c+nV;`_B3xz!kX>fdeIW}G7P8}R>leegaa{69B8mL&e)wfU)`NR)z8HT zyw;BKBlAPXW%Bz^=8uerOpQ|ikK?IK@&V!hk@IEz!2jd+@?^Zh|082O%KVlw_6Pru z?eHVv|B>M{!v7-|jS5!(kDM>_7c&25?eGKP|FJzew~P9Ji?1BQoE@C$MfAb zt%dr3Wcq((`hVo8>~`w^@p?v!e~A1)H^cuU_sQ(6{vSCctBbSs$2^YGlqpY1NL1tE*U2EF=~EoTp;%^ z{6FqLy&ypSKXOWLclH0s**QJc|08G0`GWsPPRr`5{-2xS|FM4=(hmQRoF@5^KP>*$ zI5nxc`hUE>=_wWdAIA&w0g?abX83>P_<>#3|Kt4-9nnGlUQ~(T=Y4eF-cEyI*Biq} zfd4n<_ek~s;zD|>|3{7q4pje-jCzXj|J;oHKQf-*BLC0L@c+oj=zA5}aGW;a?e`NSc@c+oDUkd+^44>_l$xG~bilyFgag~RR zOJd`k8p|sg%ftWU^+Y{e_*|a`oi%4$fy?#|BqZI^_J({ z@Q5+;0=qos%h%ub4?74?M` z;p+Q=;s24bf7JgaBVQ8vf8-MJ{Z4JJWcZE9|Ks*?JjnkeBM%Y&ADR9i8F`oR|Hx=} zKab4!%lpIicDG|ZxcTq=I*fn!@_$#aHlx39-X8Kr-Rt`^@*~~t{{EkTyG_?i>}!l@+M}M}BGc zRIUHZ^(W4muKpi+)Rc+p|B(~!zgzu3a_Nf4)c+$tvg$dl|I73F)Y>)b|B*KcBma-Q zb<;-m|H!*v-Jt#-dGDrI)&Cs(GrR}FtE%tUy-$F%yiun2!K+o(*Xt70-FYl6!?@Pl6|f6&^myQ!*Er)wowt6jsn^T`LSy>{)|&WUQ3 zTu18f^qsue+VT7W{$FNLtonyw_tCsqIWaRt7|0Cn`3H5);_fd&IVR zcR9`578qZ8WrK5IaDf+@WymXgX(9(YZiLn?9owuzkRP%_uWwfW zk9=I}``*zk&z3(ad42HzmfhM({lPb-zVC&OIo7^!&vxhW?%Bqtx4owRAD2Hb>%;$Z zGyFgDS=k@_KQjD2_(fmL1amnLbvtppNpM7V)^XGFh#-E5U znEPV1@uj!lQ2&qXeN!$K~MzqW&)#J{i>~H7Jm@_ANiAGht>ZhUpRhD{Xg=R z)2Gz`Bh&xm{Q+MP?jIRGA?_vKPoGKsU-*CIZ%!Ul|Bw93#dAL2SI!-MU;V#nt1qkn zH=-y@{XcS#=<4eKkyD3sQ2+0l)mPO2gWuMn#%T}RbEKXG{68}4^TPjgKDtzq_b2an zAG_|<5*`^e^2Vm7^e*hQUA}{ zWxf#pA2~xY6VnjghyI)aC_au|B+LM1*-o?&KTZP{Xd@XY*`=v9~u5%?Ey<|ynx~VaXiJz{RRI|=BU;GL;IOk z3qAk*;A8duFrNFKyw5Z1mow`7pl03hy@!mZ?{O<+xjiaW;J70z0 zZQNIUS*fRK++#$T^VFEx#;J`Del$B%a8|B+L~N1VF0 zpPj#i=}GGU@q8xENLK%koH04xxfI^Z&VTZRXvuf$Vb>>F>LJ7bLm)N$J=fck?)bATA^$yprzR`Hd>;(1y*iQeC zO#hFZKQGyNChE`fF|AH`?s@Em2yj8{zkRr2;!i$&IOU(lS>n$;id%5CM!2cr`&5BX~kDMp<2yc6Lm9=Nh2zNeybA@riU6MZ~{vVegJUdSP zKXQrqpowjlSbwr*`!}>%=);e%zQ@)tm>Z}5AJ;FMm*C6|on*@+FY(uYBYimU#lrGA zQ;&I$rLK<1694ZVZ@O`|_6HYn?F;s#R0-|I$}%RsRqE9Q;2w!~Yw0+cx$8 z+KS%?|F6?K+tmL9!~g3aw_W`|F#JC<^5EhBrMHAYE@PLkKCY! zqy8V+k@qv<|B+keWT^i~o}5>r{vUZteyRF@i>}g zLi(uxM{e7tv-*Ez)Z2ys$Lrg(ZF}|q$n9G-RsW9+AMd+0Plj>4wr<m*0 z=ELCsk>T@2e6}y_x!BF-`#H1U30v~^Yv%jG|06e-`LLWW2g7E>z9!$-7DmATYr6SJ z*oe0`d1hX{KcYjUTbx%uI$_+XTVvW&{b}^%6!ri3 z_c~tkiB~kL9nQaBagulEd9)WaJyd z|Ks-aW<)!s-GgoanezSYuUGpRBTs8pkABAJZ`7s%#_;dp|23HLsrr8drGN1M_P6!T%$}FFX@)e>i_%;rsoI z^A{SUo-F)7win(Rt^Oam;EpKG|05%B4gMb)d4ll&$Rp+bAbCG4oZs(9$nPuoe`H*L zi?4A7sCJJ?}gZc9_s(`^Cqph zyZV3R%(4LW|Hui#@c+nhl84qUZ%sHqpJL^G$UV=jHAen^;%DoO@jlwgZZ8|79`+CW zUa|h*{QpsFqcP5Z&HPQqLnn$~H(|3KZ>hX5b^i4&#_{sLAN)U_&m_4Y_x!cp81E0> zpR&^!`H$I8?J^!E_dEPQUQg5~hW|${yQ9DQf8=5E{TTiqdAR)kl=n-GhspSs`6uII z`F#ujkIRGM|B>ncxf%W+8Ga=EKQfkw|3@yC-*3qOBNxi=H~4?#Yx8r)8N;RigVg_J zyVjqWdB`|>h|DJ)IBXmyJ{t1>cz#2q9&g=4N9_D3BmNlj|2Y1lGrOw) zM~+PItoeWB&YA6+Zn+BgaZTTlu#Si_2ylR~oGT zAD2%U)W?xp);69~hW1wfkK-GR{6BJ<+<)-@$XTPp)c+&L$$TaJKXUxo23KcW|1-|+uKpi6 zP3kkl|FiRv)lvOFa$$bH2(ga1c{ ze*yoG4Brp_AD_oE|If|v|H$wS;s250Bf|e94-)?k{vV&;l}deK_%;#e z<9s3i&&}}v$QhD%2>*|qBR<~TxCO>I9{7K3$MM4dBjfzQ|6_mY|B>PM!T)nJ{6C&A zED!&WjJ&Z4`xn~w;RDvpUgX0sU#?`-FHN{}v9;%i_tpBp>>qq5_+ z{vR3jU*Z3e>Hm?jKlp#-VX{2@Kl0#f{vR2~3;&Ot7bzt<#sA~+q8F`)c++TFAx47xlqmz{68}NKklFYAGuKS^x^-x8U7!S z2Yw*@KR2WPFL|is{lWj^^%*=cQvE+N{XaLu|0AOwF#JDqlALe&f80LuBH{nJ8U7y` ze%`&3|L11-e{OdBQ#s;)x*5mk=4{Ddb+f;bZ-3b?C;|t@5;Tszw`Z2-_yN3d>=ReukHD5A3owo zSB87b?)pRhG59m^|8~#&UH!l6jc-x^@BZ$;ssEQC^?l+0k;fGmtN(YQ$G_G81E=Pe zddY)|ay0*sJbX~0`hVoXgA3LFBTt!fyVn0DFPJx1>;IA;UQ&_&_gvn8)c;$x?0)tC z$ctx8RR52B*XTj&|FOUG#tc^fk34n4DE0ry3+7b#e_VgY-ILV+BTtw%QvE;j@H@w- z|3{v^_-^(8$agJYrv4w#=hEk&Q~!^=Va+=A|H#{4+oJv-*}J*I|0C~yWsUlO&zco)MRX79HMyb_9Gq_0QNMTQyIJ1m zJFBXn*DI)p^Q=?J-FtR%-s+oa?cI8Gb{?9Y>AgI-ns?`qA4Pz-Y{{tPE^VFDSJQoX zWAzO0grBRa?}zuL;s22vh`$E^kBoY;@c(Aji&Xy)^W*UU$X)6;R{xLOscu8{|H!C^ z0{^eth$!{{+BL4H{vWxS*|a_qXByksH*lrv4vU9+#;9M~3eQ|BrlQ{aWh(k&&MW|BsCN zMDYK}$Ol|;agj0V3ICZ|$&G8==nUDj(ApbSui?DasgmLMb$tAOYX`&sYf@{V`h@WN z;Qx{F`2_!u`@jDB>(&2rGyFfEf9Top|Hz^PI-fjxkFDQQJ}twqtK_u{7pecZC$+8m ze{ZdPLj6DTk@YV+f!*`H0i+(G@n_g;J1`Q`0A?~&f^ z)ek(fYm3wEqg)?`|HtKzzP{Dz)F#&$^?%|2u^kNm&v@%5CnYG$82(_@ewoH+q`olx zzb~Y|D)IYx2ylh{T=h}Qvc6b{66@9i?0?zwJ@~ zk9_gK8|wd&&qzD+|Hx;r<^Pc{O1>ZbzopGOssDH7y|>l>WBa-H-&X&Rj66Q%|B=rg zd{6y9@_F(3-Z<3P+An-~z-e+k#29&i@c+0x{Xa75`@;Vte|r3&`hRYQ|3^l>;1xdy z*!B5J)`$Pc>-D+#fynU@tS0_)X|407Ud0+qU=m%c)|GK4LQvWY8x{vyQWGA79 z`hVn>q!>AdjO31iG(J#*-o=Z!TN)b|6oUv|WE z%ewRG`yoGV(9A=g%g4^C?+1qeM=reP|B*}O(Zt;!zVCVEue0j=2-?8?BF=3LQ^|mqmDENO|p8g*h@2kWABgcvF*nH$0#*s4Lj{HCNFIwh5 z;s247hXkwtN5=dg{68}MNtqw^VR?Vt81r}Xez`H`@8tb+ov3(pv5$n&i1r7L|H{vXFP{Xg~x4F8W@FeXI(KXUHKVDPf|M7gI9&6LZ%k27M{K5a@cmeksxx~gF{MvutzS#3b!N=;y#f$&9u-QUS z*Vj&~?+1UgL-u{1pFcUJz8~^0;Qx`+gyH|W8U7y`ei-~ea-fW7_e+?u#dy80Sd-9Q;4FBi|1GAGt)P zNB$ofK3vO=wJQogJg$Bpe7Wx)t>Iz#f9`hpf5x&t_GQa8o}8~{ zy&p10eddEb*BXzO`i{5txW~9md=&V9+#b|xg#Smz^7eIEYK-=p5!V?Pir)$UkJF=` zWJ2x)JKpd;;s1R(;+Xn>s7DO{&&}}v$hk`koC^}jrZ@~+jxiifMEE4XNT`p{|~+&{69Ct z|Lgz4PWAsVJ@WtD4F8Xe`o8f0$d$g|%4%HC!}7@JxThDNFZBEJ=hf%K{E`o648L#x znFAh%|HtX+|B>O}t(}|}7XQKXmGycr`+sD7p9uet3_lD0pPS+Tk=wRtDL&oqu!gH% zsPz3LuOI#&8To+l|HycrZ#DkAup>iussGnV@)ME&M{X+lgQ)*Yb{f=E|Bu{P-d7?2 zk6f4-t^OZ5M!x?<{vSE0Z=m{r3V98F?tk|Ks@>F7L~b|3?lCl)M(n|04%=>*+K+dAo5x z$+xSx=k9R!k8bTdsQ*Xq*{L&p*6`)KcBs$Vv|DHO|H!TT^i=npHh8_oYCBkvFSf4sgizJ>fhUcVSmg8xUR{}&qeocVu) z|Mf=rn((da_o01XgZ;+v|5mIy7#>-%MSZ`{ZQ43xK0OkCeXA`MlO`^Y=y>H-&X0ec zFmBNIDre=DXN?1scKxcD||E%ozUPy*IQl&X#`{5bf3WaRI`|8q0^KXT%XAoc&q$+Lph|05%x9sVCV`?CK>#`6sPKXS3GAO0U1 z#~c118RrB3A3005?^@qd+dpvZUCUhTbDCbf*~9Svc)aNUx%uhgD}8+4g8%pJEvq~n zcJfwZY|n}ww;N-7k6&|#F^)g{KQ0d}&u>27-)GDBQ}F-D_#O`aAGtt$H01x0@qGKo zkTpI&kAUI-k+bFdN%((cd@q>2;(j0R_fbFKgJbKA6DEeJ|HpPP{6BKEd@l(9j~pTO z1mORX;rBh3`k04N|CjACl5Yn8kIxTL;!h#}kIxIpKSTZ>*;gM8-@L`R{OV|@<l4z8dn1 z@hItEFD}__TrR(dHy_wzJX)?__;AlN`I8`DPt^8zF+k)^8Yx0iHvu^ z|0Bbnh5tuJz9sxWGPW1~9~t`t|BpOM##@m8N6wS)N8$gGF}@|^d&U{#hpPX__OS9{ z>i_Y0g_I6a|Bw9({R#db*_RWb{vR3ne#rlGGxGn)opSrC|HuB>t+2o5|B*xU2C4r? z4lfv@{vSD3@-W3!v-6)I+YA4X?MdZB)c+%6ybt~#`!jr7u$Y9U={n+4v&XW7eBGRM6)L%j# z-Jj2u8>hbBEr~cogOTyI`L|!)hKQjCX_&k@c%e}=I{{p|Hv6ZBh~*SWB@8 z)r*aBe31Xg>A~>-$T;5c|Hx>E|3{|(M~3g&DE%fozVHcOzEH(D{!^wcwRZS2SN-ng zH&-sRcI1D-|Ks@qBma*KpAY_@o0sgXV&w4+$X;&k@R#8KaeKk=|Hzmg{vR1W5&SN4;L;|B>PE<=0#1 z;UDhz^6$OZ+4f=jXJ2r!_=N>=4_N!C_+-uhkBt3?|3^+wic|lOoFYCU{68)q#}ED=IZN`c;Qx`4zjy4?qqaQs-@E5O zW?bE0t6m=$d4g^qtDst5AlC10&kpz2zs-?6Oiz2L*H=S+r@I}$Pj1HViJOrx>gGu4 zPyat0QLR32_58r^AbuX_v z`-b=TwBzrwd;04BU%dw2dc4)!tMh;J`~I)(&FUlZYVQ*M*HnBQ{u}>CeH8eAPdb09 z|JS$umFoX3uJwode~r3c<#bvw#^3$IZ|d8njV)CFZ~x9;)dxhL-&f7b{QubXi~4_M zWo7FBk*Adws{coxJyyQ|mHNNrd1K4e|06FLKU)1ia^dXh>i>}^-f*4f|8aZPEL)=f zANl^}OV$4)Kd@k?`hVQsTg3-FbUxotE}uF<{Xg>fSyMItkMmEPGgbXR^7Lz_ssBg5 zdGdJm|HunR6{`P7&L1;I>;IA$EM4l<`Yy|k=S@#M>AW$tif`Yt)mbq=)7n=*`;_MY z@qCnAJwyFJa(SN5SvMrZPYw!fHkmfzts2ZHn5}f)s#$sVa9*d_Zt`%;4FGD z)BoK3zhyk`%?RATta~ZTzwIMO^ZdXIe$Dl-Evcn>eM97WTQs z-ksx*{-&1tem#cuSO1UPNBq60#yS3a>uRgt*Q-xgXHsmoG3u4T|6}{`e!ZQp4`umx z23Gog10|nz^3hD=n1XEQmn+3bTwKR5{y>}v_Z$g|ieqOFI z>IuXDi}=>3{vXD#;s23`H>#`tA30Rok^e`A?+5>He^jLUe;6;V_sG5eywy>a{+`tP zoz}q1@c%eHd_DMoZifHI`Fpi#ss0}s>qGrt_w=a$OYYLPo%(;AzJI$b)&C=RllLj` z|Hy4*|B(MjzEXalYV5z&mWTHr<3?0*yVlK}H=kZ*?E$TtJAGPLao2|R)c*R^k(*voQ~f_T!~Y{AKNbETxvmI$x7KoT&05aavv0BXIyGvl|HtWT)~u=ipPS+T z@p#p!QA7PdGNwoVA33Z>ZO3=I(7$(9SO3j>e~);5)$PuXj|z-mdgO7Z&%g7HEB^VE z`hQ0Xx~U)d@}m!`|A!i-@c#~O+wAPEDDc+}@1efmfnD3x|05rkygm4Ti2qKD!C`MUK| zAMt{;Bma+l@zo0T|H!AMzHhqtf8=v->{b7dd~xq9&YnA?ZTTO`^mErl8J~Z>!U=pZ z()hv~e&?gdB8*Q8Kk$^#`24$XX#O9UkG#KzFNfRuKYjNt_5axZ{=1d=e`NZ9e=^kgL-FxY|CjTBEct++elytG zk?#lpkLTx;qm}u8Wcq((`hVn)j~r0{kBsHr+91&S+sESX?QI@l{E7I0zqIM=VfcUS z@0cF`9~u52{6AhlpPfFb{vY{^GpE%5BV+mQ`bvBii3sk zsqYs%DGcL(6{l{wP+7lM#<$@Axf%W+xny!>{vUbV>}d7>KG=R<{l8@S-X8uRIYqw5 zNB$oHKI9p~|05^K_q@peBPUMO z@4t<+CrEt)@&DKkhW|&-7vB&5pPS+Tk+a8$?Q&cdKms6w--Jl z{69CZ41dTN`DMueV>@`@zwfu@jgtQI@uO>vi{{Zl)s|3?m# zdcg4ixP48MTdDs?Zj{(U{lDX3XVm{2lG;lBKki@V)FJBsNzESh|8RZ7|08G1`#ku6 zmp(XW{@;Za6FvOex8sbF7Xkl|$1_`w2mC)W{5|-8JpQQX3;&Od_u=sW$ar54|BsA3 zH28nyTzNkZ|Bsv_{vG^3Ti?~8>i=>3Gv$3R{69B;@Jo#CFWO%p7iF9w^KUrpGe*5J z_EDzn#Av$*Y0? z$McslVX(9Nq2AVi;J?EEmU9fIYIUZ{vSD2^5o$Eku!zi|BQ|I3mU^+dKX|xn z>A#JOB!BM0gfEPXm!zxz$K{P)lI7GYylBfWlYBXU$$4Ys4PIA%%EQCQ9W{op`2EBK z9^N$dEo1n5lV`r>;U07L7{m9wIPXPc_<#>xyTcgs7cAaljQYndZ+g~vf*ha2H$Um& zTUS12JVyMx_}d>ehVNJN?)yAkvHEUfOn>eDw;30U&lmL2a^nKIKEHePrYe@}5B?v| zZ{c-u;$P0PcGP$Lbmh1`MSmVq-w*XM;s24bfAIgvMN3mP|Bsx%Bwzi%!Nt$1{}(0o z@GhNhz31WcTjlq7Wkh^YwDaemjrN=wvQ_<`mc5!fA8e~_4F6~8!C!Y zjWf?(_5tgw|99(6+dTeXCuh6*e;BWV|F@v`4)y=A zJotZP_=UbzDaP;%>pjxf_;Q}#?nY1VP(P6VpPP~Y=jD1HmK#v#So%)&{qVgl{68}N zKQh)2|Bnp6as0RS!X_NtSy_))_Wy={fgXnc$9Crbk*|{P^WguH;rB&6`e0b#{O8s0 z1IHiOXxz0~rT@ovF#JC<&L8|g@>Q}u@c+K;^n%C#BVQ%{82mr-l~-P={vWw@>(=W3 zk()_=AL{>-TlDOv{vSDD@F4a7$YC+j>i?00VkF;4^8dJf1LS=a{68|@cftR2GyFdu zAB=ay|05@ahp7KY4hxg|^Wy)JgXH}t{6C(rLGpeM{vWwVzsmeSGW|dD;7(oD|6~8@ z(xr>~f8@4p+p7Qf$@=Z;|2f^-Ifp-dD4hMfMz2ol|B<_OtE~S^?%lgLu8(kDAIUv> zssBfg?ojFf@p|glrM>!p&k+Cb zxu7i`|Bu|EbyM~KI_%o4{vY}q{J(-Go7Mm8*1VPaf8_dIn>nBMIT^m`t7p~s>lZsz z{XcSfX^8rN(@rc@lp@A>zt;>S>jK}|Esw%?tkF_@$Vb% zC*l9`?-dySpPS+Txf%W+8NS};I^B%(<$mk%%{`3Ai$C>U&ECdi=f=t3m%hfx>kIlj z&^S@CA$OW?_)&C>I7lZ#t9wYT~ z;s2506HT5OZJZ`~#kYPHYn&nVjJy4w=;Qqho_}H%rx+)W9prp8JHz+QzLWYrM6UQ< zH~pGrTsUR8`hR@BfR6|Nj|^WgKXI&aw$v~E*B9fBGbYROZkuGBDBPz1RAbaT-F#@e zF~0ALnLW!G`DbUF&oRdH#jG83jp3)&&RbxNd^`Am93Oy>1^27Y$0G5RC?KTfapYrkFN zaa|$M$S_euMu<#`s9U^ap&r|4)+r3x452WB8k~&cnv=3A2(PG0rOu zaLU#^YMeW&uQUDq$Bfeo`lOF!vEv?lB7Sv|0Ac1Zwdd;c&1PNKXRfxe|+fM zX6>Woc^>{B_YWMoWT!E{|GVYk7wmYK$oiUH+GU&|zT6{2UouXT^B=I}Wn=hu@c-<5 zOaF!cM~2^*+177dCeN$z|JXiSd`9?xOu%`}?rXpDEYhvSml?cx23q zQ2&qpH-1{Y`hVo`vEl0fk+UW06#gF>-@C&9Bm3n0WaR(x{6$E8YSjNFCrUJ`{M*Cg zrd6?w*TMhe^eIy!)c+&n`)6n9`_^C5rM?FIKlUg1eDMFs@crQbk@F^0`hVoy@x#>r zBcq-O{6BK`grVyHky-!O&G7%oIi-Wu|8q0^KjX{!e{M$pA9?bqAoc&qWAg{9|3}Wq z8>snz+BpK@~8EW)WlBCqf7qs z@U#Q}sp8n4>i@BSB}H{p|Bt`d@gW1%|05@a4ssU!Rx^T}6*Nfwzau?E)&I+uJQw(X zWaPua|8w&%pN}zypEtMGIAi!1-**~sToN9k{$KRiF!cpON!2feI z^8d(~9{%6XN5jqkYxvhpW7G#u=rG$D_v7&YI6c0{f&WK_@AAjB*BE2@@c;P!7I}Ab zUz}&{;O9=yH!cYpq5dD2S3ImT|Bnp61pXfxz9sxWGV*Yc|Hu79-WKxz$ap?UtiRa9 zPxZRN82NcMW0x4?_-!3@qlZiVRgC?E|HtLyeLeg?GV;CP|B>;$1OJZ|3`-JcK%`&BcJZpSu3m^JmNo992FMse17{%Ymf0o zIBVOlGN%8>W|8aQ*GF|}xk6hh%tDb*{d`tKH%Icge`Kj)9)aQ0H>UaNd zTs;r3I#>7o{u|@>%Dq1PzPP!%|5rUfFj{<7_w?0$zyHR#-re($@MV5E2X$>HAZ zOAPfMPhYr~hX)0EmIpuHy}s%UKi=K`-}3+doB#KJ_4)qW{0+qSac^&R|F1fCZP3Vh z|F3cWs1?7d@7JSoQ}zGIs80d^@98nWs{c1`LYZ^%rP0RoCy#U9|Dnv^IP4eo0cVXF zrT*Wz$e+~*oIIvP{Xg=w@n!1&k*ALztNtH(=EU*p|B=flj8XrOJaPJDC+T33t?%af zSF8WW?OU~IzWRUUdlt`E|Bu^u{p2y~|B)w;D^>rGJVmze+R^#8e^bVdQU8z2n=xsE z`hVnWCyrJBk32RbMg2c=r>tc4|Hy^6-K_o}`LR21RsWCt%-Va^|06$o&t2;O@qCnL zXR7~49vB*^{vWx=pf2kFEnEMG`hTdm`%6id|HU8vQr~ZI$S~*l_1XS;ohyAms($pB|z*9MXvaf#+_5W%e4p$#Ap=mAk z|J?lW-h2Ibb&9C;{aRh6{vWx|RqZtYkBs^$@c-J+j8q@6y?p-+|BvnT|J;oFzhwA? zsQ>F`_7Oj z3jdGo_`QJtM{Xi{fAIgv$p3@?M@F8)ZObIz@AC4S)W5>{`a8+t9hz z{XZU`dbMk6{vR2>AN)Tz!~ZkB?EjJJ|B)T>2T}jm&8=TrW(?nNVJ|Nu|Bus$H|nbX z-|$6U)c<>K$r|0n@5%Kwu|Mz)B5A_k@@4^3bGyFd?@&Mug zkx%S>N&P=E>H)+5b92C)1mkm(|M%g7c;ok9t8msWmb|~q>p!)x!pT@Bd4HGr^y_}7 z&ML|KyUb@^-L3u~`Mk8l|1*B`RrUYe4F8XO`mI;h|0Bcy%iI`l?eP2H|E=xSQ+-AF zeW?FSe(%8Bn*T?J@7M3OkyY~xfBcr@{axN()cb}1$LW#(mvvn7{w}w}?}PtG{_yC# z>i>~HI(9()Kk`N4{$EPo-{tu~lzPDM|HvOp{viB6^5@4Y{Xb)=w~PEgGW|dDN8$@2 z|Bw8MV}JYjgwzWb|If|v|H$z5;Qx_7x?KO)&G7$t{am{2|B?T7?u`0>ib2=_pb2&$f;6)3jW_s^)FP`_Z5c!w?Fv2`hSm^q;5HKvRWoH2HU=KmQ> z{@UVa{T4|KXQ`z za1XBDXzgJ5e{4s+9r%A_Mm}M)3lAA1-w*yD`)}-wF!le)F_JF_|BuT<{TujyWc0Un8TT2(&qMwn z+u`TI|0Ba+g8#?!gZDA;|HvictNyk94(m@v(m#>^$Nm>9?;qg*{rTo;_5X0Z;s4#) z{gnEDINtF8PG_A|{}1om;Qx_v{NewR^TdaQ|3{9R5v~3oc|h?%_5a9GxdYYzBM(oi z%>N?~N~+BNBL~E^Q~!_K*Ey<%*8h$B>6H3@eUjU&|3@C4(N6t8?jPRooX(kU`wJfw z{-2ELs}G30lkDb`jgfB$|Bu%<82%p_@8{MRjWNz%7_0stk1z7@HvK)yjyJgF#A4%Y zsh_v#K!I`YqGa{|c>drgB|VUB?S=9_ecRs|#u*D@)c@o9Q11)*f80Kt&);r~xBbEU zQTTt{U%dZ>|L11-e`MqZ!v7<~_k;h(;~95NsQQ28#Q8q;|9JfIehK~`8TFvx|MC1G z9~Ax{IZ^yP_VRoGASn{vR3p2mg-zKv4$1m$f@6lyugCC^*s##kL`Kl zzwKRDt77pzN7Uzo57@C|4P(^5{UQ3VJ#0r_ApAda;o?;F|J)4!kBsHR|8w(wGe0rL z{22>A@Nk10&l#hB?Y@;KJuJ&IhQAm5;JY6F?w@ZO!ynwZ@l_8`*ty%oUH0tq@Yy%E z8)r(M;Oax0J)CxWy)k^qx)-1D@T->|_3)za9`JC`?`w>a$M;RmyFCp5&wYO2|B>OV z!2ct|S1F9U);L@81>yg(9X=rZzc>AdEA#$@;r|(nZwUX7jQY>W|0Cz!kf;7%lZ>tE z{{@c@cG@Mj-ZQuF7WMsnIpOO6kz4g`={VW7_dLFFv)2D?*6u3D-}cwtK-zvbZc-O&$jQ=baUpZ#01G3JN=*SgJi^##Gm|NHX3?H>Qn&G7%c zT+hQYz~*cV-=Y2=p0DBmk?H@D(Y|)_!O)vu*>TzTYvhcWT|X>&+)nlNu)pyK0*&GO ziQi`2tXVT>+|9F%QNLis>{T9y|HtKFya4_m8TA92ZP*jmwBhsW^MRXRI#k6nUeTi0 zMPuX(!vEv+@cF*lP$T@4mCsjvf9#Hk_A*}cWkv(z&Ye3uU;Nm@810uHXm5N~$KLAy zae3YP3{n4&JYabjep|Hu6WkIF9(Cu4lN z{Od`^anU~Y|9C#Y@c+nopI0{KM&pnHgVg`y`5fG{x90zm2X*VA`G4eoow}(1$Ntl! zV<+|h$epfggFMS{_TRc~TC4v@ZrrK8bK}#Gg|okR?%K|2aPA4?Zaq4x|Ht--&Rv{> zM>dA@dI{^$QS<-E%>N@}yb1Y#yx#ErDf~Y&+L8aq>l5Qye?7j>81;cs|CiT0d{gBA zz1x4Y`hdujME>6|TQ{lyhw(4?e?#hRQvVNp(~2YESI>}p>id>OH1E>X>2T`_gNjBWDT2|0CmmY0CIk#_&VV%)82G zf4}C%Ig7q)Yg{hASEm^rJpAgVPR8)3#*gpn;kp;Q8<)?M{MwRU#$|I8oV3$@jB!8z zZFZn>n%u9iKGfeBe%$cnK^{K)#t>uVSzR9$WDFmx%bs9k_+hV&2=OrdKmPp~C3$Y} z|H!46{Xa5%H~4>Uo-`!U$NLd%fBhZF#);w=1w5JVOUV5h;W z(|mkBNf$o~{vV%z!0`W!W&QB~+zkJZoINkudFbbBJq-Vk;|I8(h5zSf_p7FQDF%)0$?V_$A%{a^M+0@pCuY@_gfiogZG=WE?XE`Q=-T@%>oS zl&!}2J{0~Rw-@y%wyxN2Ts$>Y^3iuxu{_Tww|(Atl=!g4EqB@R!ugwA`l2z;AN)U_ zPx!yP_P=6WB>gq^%00&P|JWbs|B>ncxf%W+xmf&9_WI$XA8`=VthSPk4Ldw z=PE|KLS|BsCN+^GLchK~vVk6b3-Pd-rllpSxJU-*CQzsXYXL;h`?CBCP)XvWzx zz5@S`)91)yqz9<~$KxBH*~9t!_^)=nV8 z(;!6sKQR11GU`LZ|0BbHga1cHeiQsZGW-?ze`NS1$p8B^HdOsTF!KM%^#9xp|If|v z|J)4!Z{ZSohZ55=659*^&&}}v$f!RD|Bnp64gMb)>tFxz)t=?ou5pcr;s3d(hyO=L zULf-S$jAdk{vR3nd+`6r$cKXeM}{8*|Bw5J?SubErvFEVe*^!IjC?)#e`NT8@c+p0 z0pb6V>Hm>Y9~u6io8kYFlchc~{6BKK#yLb z>9-o^M@s$G->bMVI^OZGxXs#AB_FS(<{h>?aJ_q~xHKx<+12?@YX`&s+9TWjQlwGe{6?u2>*|qFAV>WjQqQx zs5Qo=a=tz}T*bxWQ^EgZ|Ba7|cA~z%&!$g~i+8?RwAPsUf1JJ~A;C#`;C^c#EqQwI z|G54!2{G#bkxSyE)c+$F$?<^yXDr(b|Bt^n*gyDx#^K@W|B>P2!T%!{L=1OkKJu_F zFE4zU=KrxB;{mAuOHPfg^#8bi)N@AuA30mGyVV7|HJQzd;Qh9x)1n2^8DoY)jfapyg~eax!bFA_4VQR%RPPd z_Ugy8P|m-5dia-auI@WluZN7^Z};@o^Zn9;y!n9D{XgHZ!Jhe%x9VPA^*q1-!BWrC zJ$?0hzcm_r>jzio|K|JsxB9*f8hG>nnlx$R{Q1gw{}l~?Ro@TaXT$#^52#y5{XcTo zPA$~`3;6tJ_5Ws0D_8%|c*a!q|1$Rdr2gNO$rIH7>-El$>iTX^>HnG^+=ShCv(2YgL3&)RF|BvgND*1q0TNL}bJy$QdM*TnXbg2j2e_er} z)0a;htNtH(;kYvO|H$*jUxfe1`RA49s{coxo|~fnA9-3zkote*(UAe_|B*}N_akac zwk_}OxwF;(WBaZ1=d1rmzHZ_~_5a8dveVT6+sgzA^m2#}C%1%=;TQ z(E0fDJpUc#H8sz#|L{TT|B>Mn!v7<89Mng~7jpeMbt-+o7Ck$v|3`-Jhx|Ws$KE}i z`v&CrBiGeZ->-MyZqAZfIsQ5kwf$iq9FB-jjB+|}$oI#;QAd5hQK|7xzfbc0ji%RC zzwa9HHP^JN;)Rmm_;^ab|5%H9{=AP*MqEF0ic^14p7GpSQ=B;)a*a`c8u@>3Zw^!c z5A|tQXH;=t@%iBY<^B<_{$J~>nyLRsZr7o;`hR5le;+1BSRNq!Kel&}d_d&?xf%W+ zxqIto>i@YJ{vVnC9~tBS@c-OAVC8MLKTVr9b?*7)R^x`v>N!75tm3+jYCCzSR#`iK zUtWx>V)%gVo?mJ0;Ol#M`Tf-^tQ~ox@c+0yjqB7^|Bu{6>ho?twA|Xkt;4IB{vVGY z^Z(q8{6BJ?nl&{4kL-v)2>;K`@c+otto|RlyVTpcP`kwc$Fwf$?@eykPW``)%R8(8 zw_3heK>iVsgtU3X|H%8rzk~nhX83=`FYi?U zk9=VF3rZ;<{J*fU-RJf8^5@mHr?3?B2@!KQjG4H^cuUUy$X&|091W zzTZ0W|H!D%3;&ON?#)X7k9>CDUiJUT=U#tR{XaJ&|Bw9MTd!;WANl+nuc`k>MmzjJ z@;RyZTX$QSF?_#@7ebBCiN7~*cZl(M@dM%iaenw}@c-QW;K5+y58r*;8Tv|)9q&&M zA8@9;Hq7{<SHWUJz9~_ z_N@ARsE;Av{~G5@{RtT#G%l9+9q|7+J;wLo|B=UveIz3GN zKW-n!kKzB3G5#pucY9dszZmCCm-?BXy=0s#^^K)|j4|pF!~f&)%$DUN|BswMIZFLM za>0~n&Hp3kPObF+$T`vu|BsCAi|+HBF}}wher}5~-uDFFzS%fS#$P-8HW`;(E%i>t z|6_kBo*kq99~u4`{68|@_rU)nV>}xE9~tAj@c+ojbAbQnX83<()VqQIN5=Q(@c+p0 zr{MpQQ)Ijy{vR3jf#LtT`HkBjG=|T3UHAjW377ppPLJ_o_ricGW zhHnc0kLLsD7yci4?6ffT|Ja|(Wc+wt_-)p|;X|DqyRstky%TbO`b-4s&kkR=yyERf zC)D>#mi#vOe{PPweOX0T*l~TII9BTa&P!ZsTq?fg)3t9h9yB#l{Xfp%J}*%HKXOcZ zZ}tDkq4AwH|BoCN-CFbi$e~fK)c@o54v%f6{@^cwaUzaFj9H zN3AI`&b>B4{Xd?ceDQ@o8j@$%@7P5t@;)QWrXM5uFFyxo7$=EOcH!|<<0yIm0soKN zlP&LC;Qw)dO2jXO|3@BmU8eef2qWH6c9)|zN^M}06vpoZ>f8l-CPe1pv{)6`+l3!JEcG@xZ z{lM+t?o!d}jic)KA)n)q*iIg9*1LVh!#^HTzYo{ntf$*}82%sIQ^l8r|3}V{^9}!x zoF?^^A8OsCqGyjI>idD=|B=%dM5_Pi=CQ5nRBXyQY`!1-KQ|{oc1V4(+{Fn_ zYV4nT$f$pNMfNYo`Qq>GDgWNXb7y>QoGW>H{TE#_Mt$N>SAJ{^Kk(7D?|V4^$+J}~ z{$G>rCp;{!hVeM@)owVr-^0P@-!LweyuoiS?e*~bpI`BCdF@@s@C~nOvE4ZJ2Jz`S zZ#GVodc!OGuQx{iU{vT69{w%yQDgXr&*eYh;VI+S80Rj{5+CI*%bJ*Pe(+Ts80thY`5KQR2iw{O|z@&DWm|If|h_q}pgzwPGx$$*~Y zX36sled5{e>i1#!lFw(1=WqCbYzM>to07Rh{lCU7D*ZolqvrM1|083(4*nk*J|O%* zGR6ZM4|phS;4eGW?}M+`bowS^i?0ub?K@8A9;8{Kj$-F51T)H@KEQ|kNX*;z8CyIZht{an)-j_ zQ7P%_|Bi_cm_v_h9{XcT=E?u3w+TLUB%>QG5YA53j@c-C<+q7$`{-2xS z|GhD3Yo+fhJ|+A=a>tI9{vSE8b366_czq!6Ph7unazLlHn*T@c)vmSrf4shs_Xq!v zjPWS=e|CLd_W#^GzT}PYjA)Bj_8K(kir|23|;QT@OEEw57l@7?M0 z4UPDJo!VFWf8@ltk(&Q^@r!5F|C?GiQuF`F%NAriHJUZ>&AM=~;?@2Ch)BLZ#X0qB zL*FkA56bxSKO*8J5B2&PO^k6rIcr{Xn;yLStCq&__wIP_N*{j@k&pIVep_SsdnXUK zH!i&<-uW%DlX0fpe|C7Si*bhdC{dx^jdA}oerHc(e9yD8e;;Gq-*0+4z{5v6_xJFR z>joO*`Qxe$yz<(?##sNd#UnjDVP}|+e}C}&Qh!i{hc|AFGKQa( z-aFRAo2DlCc)yV-_j^Y!B^gJ_{p^OJX+GY+;QNYY%QAhuUxL5)WSt!2oN@gff87Ef z@8^r8UT}+v#XjC|50t$9LyO9NykBmc)ywJl#aJKj7gN(Z;QrXdMHi>~`1~aEVc zeui<}>;!rLJlki_FLFNM|8aZ({w4fBa-VhO^^OLKM zOU1AHF=maOpRxtwABz9S^M~gV_x5EG9^vP2H75*PNR-Vt0|3^l>1NeXBSowYt{vV$|LdFEE z|3@Ay^?;H8M^4D^>kRw-X&;|Ak_rPI_gD*UOz!?7Gl&=nY z82%sUhaX;W?_t}2@VE;{j7#Ks_3B>7jN#wjF#EXijJe6qZ7-iNo;D{@{Xbq0_HqQg#%Bhq z|3{9?2vGlz{UbUn&>437pVnXE#5a8P^k2ro*+ZO%8#xjDy&aewp#C3!pA&om&Lbyl zM7a5h>uVarr+Bt|Eo0Q5g#UN)-y_rqgg*uUj|{&9{vR3jAL0MG8UCM}XN62KhTjJN zZ)NWg^#S1%PP=-NwWmv7-=*6p8>>IJeu^=Cztfr1ZGQN1!)DGf#`eMg3mY9;nGY!Z z@Ab1h?I~~0HinM^|Bu@PhW|&#^2T(U>*0#fdB*Th+853D@WS~EjN!+eT)og3KFE-5 z*BT=a5dI(6hx{q{e`NZ9WYpt?|3}90ga1c{&jSCCjO~N}=Vs*pxf%YSo8kYFaXjGv zkT!)AGtV0@^KlWGT1;PI#BX1D?pPS+Tk&)j9|Bvg( z^#cEoJXw|p|BpOATz*f*|05$m4*nk*{vG^3GW@{V#djOSH-rDjcGRi?0;l9Sc{BWH>~b#K{yHoZ^s0^$F$Jx<<#!~Y{^NIl?3 z8r<*Uryg8u$FDdh)*095eh+th!NqZr&WADUti4eD$H$IVF?>k)e>@-XCE@>(;Xfk( z&&}}v+>H9aZbtqe8OI;~pPNztm;09&8>0T7o8kYFk>3daj|`s&{vSD4d_lM0g?hwp zhA;TParHdFylVA+tG5^Uy!CKVpV+_%*hkg|Kswno<7m}vRRR}gKx_%G@d_s ztonbP{+bDu^?%6=#+R%AM_wq~2mg=zH=`_F{XcSfW~BOm{4|MJEE5x?M_2=IY9lAkx)@i(sdZp1Lji-!OARGmuy z5BY!a|90G8L;b&?Ve&o9pnU(e;WahSZ_vP=&f!UU#@%~%QvZ+bEn7En>c1xIJ5*Es zzAGEIbTWRGJip64uvb54L`bebZEh{~{dx}ykb3h4{>?vMp}t>AZo0E?M}dFt!*$g6 z8{ou&TY9k++759sUAUhDso@jX83|8jbamydbmo+_5{apeC!-QB1DU%QsAH2;s& zx4N>a`hR5jgsA_^>G6Fv^8eV5^}+um!{{ts1NUXDsg{;Qx`4 z&jz@@7wa=KD9>@x$`r|M7UrkDmkoj|{u|t=~)h z&E|Jj-!DB`-dBtNN1mQG%=x}av2l51Z}tDW+}lZgKqsob`hVoOJ11-YALrk=ZjF-| zoNx0VcBh&vQBkvFX z9~r(O^8efn|BrlBd^`Am3V9`Oxm?HUE!%RHldjM?NjSApAcv>hrD>|Brk|d_VYqZbtqe`P3V)s{iL^ zFZ|}FU}N}zf9@D=jQYRu|9HGn{}=ur8NMIWj6Xbb$hq#b zfySu6``p(9j6ak-LgfE(`{Db+|084h@c+oD*9-rT>!bfiM*U&r|B*kv?EjIG2Z;K= zZhFJ5({`hVnr;r-SBg9CUmV{=5? zoJ#-izH#T&{~ItlQ2oCzr=Go>=NIJMwe3X3j)%^u@0VCMSp7e;uegKye~S*BR{t+` za)A1O{XcT5)IWm%M}|L#{6B6#d_Wn$wRZS1@_n~4 z{22NE+ZfA}`Y^_6vqIGW1-<_5au(z{vk2XGy(g_ zCj37#&JX-QGV%f8|B>nc@pxi>d4FW*H(%a2d>wFy^$+ylp9bDqA>Y8OF9&}r?!6Ti zFTHh4eZQQ`{vR3dJK_Ji8UEi*zaCZp5AQeO|B+E&82%r5c=P1H{j3^85A1 z!_&K~|HtJIOz5EgAGu#tGxh)6jQYRdtv#;3;()lO>i= zFISES{68}NKVI+11A+hNX83>P9C<$>??059^SF8 zu!_YWjQK0y&JW(l^_`e&Tp;yF;s5dX0(oQb|Hx_L3l7|wV#|vbKebhtB;&Z5Bb+_& z#@YVDU+WqYW1M$gl5@-YNMqEK4J-?{{*iG*veV>nh;jPjBxmsL!FK$ye{238W}Lnt zO8q~cALJ{-|8w&%Tl-mmLOc9Fo?rNa1G0NnB=tS2zF+Q)U?(i4dxc~?sP6}c|3{7z zA8`9K9V=3H9#-EE^~2%+k#T*(|08G0`=pw8x2|aQ=^^#`Qs(-ci_KdaWBV&sH#0`Q zBK$v2pDB4q@c+o^vj27Nu2*rc^&$2BG8e@;_ug?u#S`%d)$c2p_oFjg)$%a>KeiW0 zy;}Hx0@c-Nl|If|v|H#M_g#YK}o<~30gTI0BGmzhM;iLDAG5zWv<lGOs;dn zxL`@DQ=`pcOZ!T%$7Y}!EmKQeqj_UHKp8P*Ii{BQO z@$q)``SASTYW&s4En2jY`n#))>Hl$h_W{68}C=-~gk8U7y` z^$y_wkq30_qWOPhRS9|3@A2!SVF)r1sZ_^Y{-NILHY) zd!sS@MfiU_e?xosh2Lo$*rTWVf9xMUJIVLB;{TDmcWR^gf9zivKWY`aE}Z@I$~Mi_ z|6~8f_z?U*_HRrN|Bu|cT`SH1BX?HqQifS(EfkK9-4{m%SzhjE|F{vWR|EdS%Q zSHgMyf#Lrd%lH=R|8BZ+lls8OkA(lX|(cU#}~# zQvZ+KL*`HJel+~rOHZrc*P(rVt^Z3-O{w(%$m7cgtN%w{cukzVf2r?#^60zj`(?=A zEBJrpRPmGG|B-X#{;1nW%{=^8eoJHI1HL%!N+17TTsYUpxJdk_8rkiQbLPZ4 zJ>ThQjQqRg$Sxk9wX2&ke6ZC6dV2W9r+OPBPwPU50OKt2XKJkJXAHlrXTyOWPF_0L z82Np(ejDoH)w72iBmeKk&qo;J`=kqHp~mnB-<{?2@$Uir!EY`_8Y6!h{vZF|fWP}^ zyfN<2*K|rUM*ZUNC#L#%e*%9fWoL$u_dm&F2RdI5%Qns^4{%lu&G+$sD^H$R%kC=j z@%}w{VuUmCol+m~-`Xd47yo3ekN3~RLz|0lGTt~Mww?1+rzt+(p9bglav~p??&I@l zn%sY{Y%|-(=atcNe|q@gYkYj3DVsjrnHW0X82O9v|2Te-GJAyjf8>lg@#_DPv*t>E z^4B-o^kw2V_1kchEw4nLR~G!X)EIu>zQmi2v!uT^75|UhlOp%?Z%tfo+nXx)j8-^2go@xlH5we#<^<5w!v?`?mVkIx@v^1N_h z!rjK>W&P*2-s9m*zujw0|Bv&ROFijff330el_S?{&G@w*hX2R&nP67ebF|B;cu4*!pg{tN$)jJ$jJe|)|}eN*KBkyFe2 ztN%y#<@HqmkNr0yznA)d?k9>nMzCVTk$M&>w!`1&ICyM{q@bN9y zo+8^@{MlCH;<-uA`hMGt^JmA&^U-$W(ek_;_tFmIGWlNh!h)m?4(8kb7`_5Bw_X4P(>~mhm%V_ z#^~Sh|G58{AO0V?L>T@bxlHn9;s22*%JSgdr6!v73aZukd)V`hUn%g8xT`UjhG*4BrF(9~nLf{68}C?co2B;s1S|H_K1qJs zY-1b`_d1Uba+zkJZTo@Lt{vR3s68t|h{3ZB*;K`@c+p0<>3F3%M)YN|05TRe~0`( zGW<07e`I_w2mg4|Jw4VPg4JneC@PK|Bt*xd`0B{kr#>Ycj$b+@!W}{)&FBV{6P4B+@I;A z^VI(%Pb|(*|IaulTKzxrxXcLk|H#={>FWQvxz=}Cw*2hjgVq0IdsNRZ&iB)^?D)dB zJFz9x81<{+|MC2w9&fLIW%*|%|5};%H*A=bQY+WLY~vpleFncB(NFR%Uy0B2&uIOh zip?GNMHmex_~7@o^ZaX`t*O3WdXFB?g}6L_NqQ}r)HoGbn(^8d)G zql=w$XLF1vXJ@GYmo+U!{lAgjyQu$19^9m!`hOqn3{_t+s6`|7|H!Ck0{?INf5IyB z|AdkM$M(iowNn4j&G7#?J@WnF|FIq8{qX`gLkLL!Ml2?eOzf zx2j_Jdq3TLi?t)45B?w5k9xh6vZ@&K@85f~wS)T&s$%$kcRsev+QHv8sp2NG{IMA& z{%KEl@TUd;76IG&gPkS*`yT12{vLjvbN3b-PZ%@WdFS0Ced_#_mLAdDAk+#3cBCf8>~5zYp(wWc<+><8$!;*bavOXDs7&@c+2H z(UNBe|BqZaGfMqGa*_CJ@c+n}^8N?;f8-4Lei;6rv234wpKXjhIrx9>cKCl}yq}Wq zzis=FUnTWnjML{vI?XQavgy%&%fl}ir(F}F{vVHD&ioYT-`jWE@kYI+ZWDJHC(HP2 zUfb=)akBsL|9HNzz3~6Y@B!ifk#YRt|G63dpPO5LyTKUe2mT-X3-UVP|B>;&5B?t+ z^+@6Wku${Cga1cPk@08vf8-=tKKws2)`$E*H^cuUMv!T%%E z|05%h4E`S(z9;-YH^cuUW4svtA6e`7_Pp1Q7yLcs|M7SxN`58$Kb~LIKYeP&?bbiQ zJ)T`v@kHh^_2)4D4F7M#(xdACmCE~rPg*Xo*tYYC`h97_t&ZGmoQ!+{@&DK!C;c1# zA313BAoc&qA*Dmq|0DO$?5X}AIV!D(Gjq;$Hh)NbNA>@>Jz>dh)&C>MW_Q*6KW=|y zR!{Z+9_n;lea2*|=Tv_C>b9~pUZ@c-Nl|Bnpc4*s8;;s245ANWA+d}I25yx#Ht4gMb)@7t0R({1`>$qRx1 z$K{2|`vLfWPa7^lelM)-d`e#0c+=TMsv>o39L zd%^$X@y}Z%y;J-@a@K-GXXxvLtv{hYTI-O3#<-s0|M7fg&XIb1H}tjhpK&$5XYN(; z(r1S&{XePC4*&0msKe_2AzuOhA31VbkotdrTyseMzbJWs4F8Wz|Bsv@{TKdUt)~yF z|CcDfEBrqjnf{-f;s3cA{vR33pCbMrnfZTihW|%~4+#Iy&G7%oWlPi4|09pOF-4C53~R^s z!T+;%SwH+gH^cuUm)(@E^?%8wOY+tK>wM(~_5YHm$Eg2DPAQ5}|BrlSk0wsn?`!QL zWBlkp6Mot4=9fSJ%($ntBmZybJsZ>)>~XpNZ`17?J^r7Y;r~6^f0O!u@ad5M7xL^T z_5Z-||D5#A9{+FcJDWZJU+K&(>i@ydL;l~lUu;qT4~+c3AN;@CDce2%9~u4_{69Ct|054*(?R_| z^3aZ5)&C<$bnB-6A30sdPf`DuJVL%VhyUkhi?4a$#~V;faBq{mOWFkI6~edcB$)3eCSm8?7Gj$-`ATX ziqnIfzn(c~JbUyI=k}&`ecAW#SKsfZt7FvvBd3eM{-5OyeYbu8PQ{rg9*;;9-~FlI z8XM#95Bxt)pRq97f&WLw-&gp5{QCih|3}9CC;UHhg500M|0Co10{)+y;s24-q#gdB zo8kYF>HoPI{vSC({1NznWZdt<|0Co10RA5tz99TRGVXWa|B>;%4E#UxM9D*|aVp$+ z{H#dz|M>R-_eU+p#`xSU{oIESs34Soe$NLf7&$jwB-N*ZtMEPD~__!?N z4EcWU&gXM|ygy1AJUQY$D|(43xmh_cz+ld*-m_uamK?2 z))&8Il8^VBorhk5`)eQXN4p2tclxBw^znW+$5+pJeCHe=pI^$7S~|Nj=NXseUFH0B zcA<~YKeMI;I%^g#GRFO4;8iym7s>Y*@c%geFzMQ4@i}g?<&Bs8uP3fwYK-q&w(MVK zoGITUywc_tV|?!d|Bu_3x+uZpN##lf6KTbb!p?p6h z{vWyM+9Z6RWyhmX{5<%7JU+++g#X9m2j39>9~pii{69B8FzsGD{_vwF?p$q*{6F}A zJU^%}4FAu~@c+p4|Hyd$fd5B^zX<=241W>+A9VRjQxZE zM@IhT(k1`2{)PSx|BwAINBT4TKXTfHA!ckz3~URR52B zWqu#^|H$wM;s23Cv%AUj%O<-XVoL`&b$;4xoGp3#twXjN`)0;EJ(fIY95E|So{zQ} zkCVK&==wX1M@v5cn!k72`bs4KZTzn<*#3kLHt$tf9wyr z^7{$@kDMd^9sEDCj;ECSZGJqj-LihKF?_n5?_M=lUoT{zG3xt%v-EZ2Q8GTW=iN7q z;s4#*>Mai!mcDI_<@b8}9b@>>Km2>YG5tSoFQ$k8N5=M!dgqW$4-RN?#2EhHuf<0_ z{KgZgL~kl)`At-WN1jK^I2k@2XRk?Q~PdMKD0r~aRt z|DExfO`kD6PW?Z&XU>RM|Bsw8BUb%Ca_ZD5r}xZ%+5Gv_i?2cWV{FdA2}^6z-jUEFUF~vebxVC z|45L$+P0Jbu>O*m-P`H4{ZHeltbtB?_rLA;HatzziYVqfbh@Y|B+D-5&j=JYRDjG#3N&Ee&k`F zd|{mNFnPZW|BusSe&qj=iO zo`mn`8^d3Dz41b0tUtQ%wI24zUT2K+6E=F0hhJWFy)pbn_x#aJ`|Ks+Q%KpRuBZr8u2mg=k6Mqf<9~tKl`F~{ia>)N9 zYd)L!e`NSc@c+p0^A@+h-5B+I!=9*OM{!vAyg z&Y$kG^}*Mjv+QnTGrYUE4q2C)JJyn=-5aP!%uX#SLf=> zhu`}DNV^Z{sOok9|C^40fJl=j9YQCCgg_<>wE1zCDWMM^P1=D-XH5f zySx58LiMlC_C?&Me#5_V8~%U&P8RRz-kvf(aNZxDf9~z|yZ(B<_5EIb?^oXg)}P;p zf6v^PSATwCeczWdVno3H|5w-dfA!A~|Gv2|zhjF)pVvYBjC*_i`F;O?{U45By3fCB z%fNYm9qY{_tndHO@4r~(du{$t>h<7-9{q8Wbx_C%o&T5p(9h}v(-P(Pw>4G1|K9bB zdcYag)11&3CRxv!QSH<;sq}IG+0!RGRnZge{AN$7R{wWJ(U0l@XVpwr|2M1Z2lanb zYN~YoUp71;=Krzh&a77d$DTLG@BesyOT+_W{vUg>ctFhmV=tOD*$I8P(5}x-Gpn3m zPZn6;IHkNYn^mPxXG7w+H{n9x^P*@xGMr`%A_?KJe}S=qr15Q~$@t@nOvW z+qKqF|JR{)8})zeOPjTHcHEWcyL?Oo|GYn0?_=%3Jl_W&HBj$2RE|$Scv-&h>02AB z_lp|P*I7TN!1wxVjeO@19f`*A;gZFLzW6^ItM@A`EOe&S7W!H~-9)`#)x-kzf9zS) zC#nClp5dSW$DT2@RQ(^jtfD~uAG@SHPyHWzTJ8jA{3SVdc`<`~>iWOW-5;smZ*cd{ z&dT8{e8C@#QQwF4Qkp;UfOY@Qm#hDCZ$B{qe%p@qct(D9UqHkEaeu6z0{_R$!|{Ij zKQ`tm!2hwaUJ%y*Wn=xN_iwt}`f~A#@P8eXN2_Oq7l!|1!xO{*-QF-l{a@qejnx0K z8_3HU{2v=05A*-r4gbf+JU{q9cfeO?6*d*n3v3QUAw2`l{dm&79Fg{ojF& zFRTA!AC>ulnE%(g@=E`Fz%3ip|FI9qygkhSV;{Qc|J)7#$Hw`=|G69f&suyT{2%*x z?I!hq>?7Vy>i^h>YyIp0vN`{cjro7@f9#`PzyEVL{2%+EoL~9qMCHpaDf9wz6d0W^2b@!rM zqU`+O|6W@**80@G-OktdjKg0$!vAqQt`FA#Wn(@e{2%+1L;KYKu|JpdhyP<^yydV4@8-5P{k6k9;x5)8HuN)IpA5<*!?d14nU5lrZ-#6R-6J@@Z{QkMF z<@+A_eY7>^H^Be#`rvq>{Jz?@W1gHGf3?Q zDeLo!|6^mGAN-%YM~eUB?FB#hQ0jel|6u*-4TtZs`#)TMPyXPAyX^6d&gp%J_pzu$ z>iyELif~>nxZQhh&O!Bl`SSe?{2v?ZBg6l(@%)1SV`Dup_&;{K-1*m0#J)&H@_ z<_4+%V@Kr-RsY8xmD*qZAFp3XT37Xd?6LWM)&J$TIIMmV>pLyzdX2Z$iNosuvSoc6 z_&;{sl;P_C`20?vJ6io88;{p9JEqy~lQAy}-(S|X%m8?FA2&rf{+4gbf6CxicE!~fkhC&wB-tm;&zb%A_84*$pf;q~DE*jWFquq??g zKU%&oTGTS$ZV$}Mga700gL!%If9!bqzIevUv0mQ39(n%3|FPrb`osUROK$Z0KX$=& ze*ee&3+t=F|FJX0>%#xB;gjM2c>kx!^9}xQ&~pdW|Ka<6_`fRWfcn2wxxVm!>^M1C zkM)1u4ga?$dv@W2q7B=n|mz{=-DARTTfn`>7?9w zopq)BJzLgaWnCbiuixQG0lngvLhH(#F;6kWy6V<+r~LEYwLky%ym#NzOQQ>y6gnY0 zx>#o}$W;Fq*?P5lz`T;N>i^h1`!`enXWjl1^?&Rh?V368e{8HT0sq(bj@9b_`nPVW z^Z(YputxnKelLjif7#u{)AhLNd29GM_&+gD0rUTQ#I6hQe?MU z1OFG$GXIZ_{W~_g(K=$-VD*2zKj{D1ePq5L=Kt~j?JDc@wtVmIC_X;0zAxtgv2pvu z|MBq!zX$)v$0v^e!2j{_3*QO<$HzCe!~e12@8JK~I6wG5K0na#e{6U@_&;~U|J~Yq zt@>JQ$NInS#{55fK3?>H=Nqk2|A)T^{;zt)D)oQxiPWsGzF(Z(MBdr%?k$HM=y;dzSMU*Z|PWsiD4 z_$2s0HarjfpSx48Y8%k-e>^|TADg+agEjnIyO_?_aWW5h)5b2=<7HlOSx|Rt{NAY1 zlUG{f{rswSy{+;7A?^0Q*4Y2&Kl)o^`@?gBtnvBC^VwkQ1o0@J77eqe|Kq=BI6wG5 zcOTmnX8U9Q{0&1QtTAsM{*U`ll;4}d|FO&E{d~W)7;Aj~NZvIrpl6SXw@$lyjI&}x zqBY*nZVpPe&J!M*D9;~Wp)-(<+V?oV44diZ{7tgHvQC#uB5 z_hW<8`Z*alPW15oThfGn&Qs?mdHDWs#K=pX?=osUd_Q^V;AVJ#?cw|F_Q9>4+egpz z@cnAL$Y##m{c}D1d^sSaoBBU~zUh(IQ;t8+_pnFF=cDt>ZnT~-H(dQ6KOf~T80VZV zzS+aBl=m<2e>{D;cs2Mxb_u+o_&;{(f&}${?1BaH>i^sg|HtcFD)0B;|JWseOIH8K zu9oKq{GYok&fMkU=kW^hv+#dx%!`)KZ+82@=MBGqx!r!~KR>wFx>SC@vak330S*7h z+Z*c>!~e0dKl~pX^WotC*v0aG9sZAv?U?`PZumcU!~d~M#h=0dv1{c0G5jAJ>&?Rd zv9aDa{2v>ici{in*)op~{*R9*tRD{l$F7p&De!;nQt@!`e|$W`w_^QYc2e08^?&RE zx&77uu?H0dssCfgi^hD6Njn)V<*o@Q2)nHxhhfpAG`P} zkNQ7$!L%_>R{BPJewE5Rz;p4h+x17o|MBlFm)GZ;Z{K2FEuW{-mu|J&ujpEj)9t`E z>*DL8ov%82t>O1Ji~r;8T_!#m{*O)n=k8wO|Jd+-@PF=x|6}9$0sJ2u`@{dSG5-|) zkB#GJ@PBN~-`gI(-#TAjub1Eat~FlI;QzQkj#t6|u`9*H!T+%*&5m{CzpZinPb`|< ze&sUHRi2C11@iBStPO3qKYDqe;{kno+6il1-@z}xZw=pluOm)MT35;K z0sqIx59SwQ{vW$cuJ6e|KDYhhF@wf^8PM~WePxZ)zkT3q>mpe%qNxAAFSc`7IgjDu1{L}Ag4vuF98kz$NQ81&)sJS|7P3AXAf2X z$A53eWerjP$BxSw=!E?DPkX&Z$0l5`PV@w+|Ksa38vf5(=JmnD{LW^d~!~+vUO2Rh*e&4KH%~_p7Y2K5S{nS=R7^@PE9%N#Ww%#Q(V) z{*Ub$?e~9d{5}Z&kDV74tNxFjGe+iVivMHN|FPle;Q!e0dhma2ctH3+cfEZv_#p3mTopP_89~%CT=bt$)PW>M{UFO-t|FKKt_igZh>{6M32>-_}m(#=l zvCG8s!T+)IW8&2RvGMsC{*R5zhyP<|$m!w#*jV2e{*PUrn56!XU67Hc{*RrXo~r(j zU7DJz{*PUll%)QTohs*t^?%tJ$tmjp*d-HWy*}}O?4ra(^?&Zh{6BZY|FH`b64d{( zar%d%pRn!ldb#h`b$0xC^?%$yJJIj|*jWi4o&U$idh2eFl`E%rH|`&It*m`M>%euzu_F!{r0(`@Qt&K;MVgWB2vJ{7QEh$m^@S>#t7?UmdVr z{Ia|2uTPBENB8#nU4NcneV>;ZJ~H6+8M6Lq!1>Ag?e50>T6fp?hxNOste5NFzen>x z4_JR*U;VB>zpsA(U-SP)H45~G!E$Zf*C)6^!+kDK4AA8~TSL^&gp8lR|W~={W-#&Ai`akv}@qqAu zygm!3SF8VH|4rr#!vC@7mKLc0vo0@I|Hr;@N|pLQ_B}Nd)&H^omYb&jj~$Z|?WDYr zl-@MnUYrEn_l&&9M9e#-E%~cbJcD6)|dD1qy8`9 z=D+0l^#15Z9WQs5{3i1e-?||F;@xN*zlZ;0_i5SOS&*0SE1K)5_iHEq6#kDrq+fsa ze?8m#{om+81D$98oA1kyZ|HmTox{<1f0>zB==M!McF-tWNwtsm<5e+6mD>i^~) zYOMY*vc&KI*zq!d66^o6Gbfkp{6BWOculPT%TAi)_kZlDf>iZ??Bcu(^?&TR=+VyF zh-^E(r&kyCfB$(kQvF|;{C*q$k3Fir-~X{g+sXPT;{Vt<9t;1+#_?SEKX$LnTdV(@ zHfywcLwp|s|HsDnA@G0hhW}&33&Q`g@%;k)-^qaye*f3pzy2>9>y^X*rF=3<{U7H0 zVg4Vxd6Nd}|JcpM*TMg}8~%??|L1P_KXyZz7g+G?66;2Cd0VOjyX*1Aw!MK|KKvg~ zkMoEBbN5sKT5NxBGx2_y|ChVHi+}!~_(Ax;ThCsh{x7vrL-l{`Pab_l{okUEUDf~X zd2N&WzpTG^Q~$T?6`8Lm{*S$V&1&_3?49e^ssCdiUFY|I?Dt=JN$3Cdnb%$Y-@#X3 zQvb((@1p<9nA$`A-+u9ZnE&T)_&@fM%^P+7Uw6a*vFZQZ4gY6-(f_eecsHy6V`Dxa z=Kry=o-pSBvEP$g}CQyKADYKi;>;NxIQv z4c`a<$MZwO|JC(g^?&R$2llJ~t82giW1p4vdolly{pG>^>i^hZ9N4G+kB#+y;s4m5 z9XX)u|FYo;G5?PZp9lZPJ|lh){*QfDw!{BfU!4EPhWCU2V`F_^_&+w*_l5sse}43c z`agHW|FP-+*q_MthyP>a@4@^(_IdGw@PF*jj`{r``+J%H_wO6ede@CTp}z0qlgFHI z2A;9LY5rXGf7~8B?h^HX?ChK_4%R}zOh0(Pf=ZbOCjO6&^-XXr9OlpW&o$ARRioAa zxx4Mb!`{cc998d^C*M!N|FJRu4E~RuF7xPQeGsp#@!|J=;^pA~*!kl1Af|6^CojaUE2>z6xE*H^Lq z(eQuVAM-8X|F}OI{*T*BuT4<@$1arPbMSv`_!js-cfso6%%r zK*Rs>{=mE~_&;{G%$tM%d2mi=Jmn20#>pnAEHa(TBtw#<9^&;#oIu)Y%f zAG=&U+XMG5^*&PhuKKHrtH(PH(w114$no8)TP(JYo8e#om!}Ua4Oaih=KMc)c=2%c zf9&YoLAw6$-TyhD9x*C=p!z@SjGpTM*zpAe)&KGD$&~pF@P9Ymdr19Xg}h$C|FPlS zuKsM6-5v>Y|6=|hpWo@%j8*@~&YmBm{*R6M3GjdHJh^?~|JZ3VuLJ&%ohkFt;Q!e9 zH>SuufMV-BnFsRUw+pP{w<^Q(taD_(2>c(Pztyro{2zOg%r9AfbDHg+Cf}F+{9Uqj zvRps-Kf8Q+e!~Cp_Q;iadGLSi^qHfb=E2eS_&~$|@%BxeF-rX(8(tOukB#+vv(iJo zynnEMFXsQT@%)GXb9YG7A@+ES7Y~?rVxT>q66E{5vIG6RN4@*i`@svt|FPkTa|ZVG z7X7@>d>_{TW$Qdn@qcXW-?w#V@5cl7srSpeCQAJudxG4*58TwwTV48&dOq~`4cl6$ z%lDNjw_j?VA-)0rkNanehj^`NbMLqJ?N#rWE$air|FJPI1^&<7vqKzj|L^wr=k>|= z(SN`Gk6L!Vc)gT6|7D#c>odduaXT9Rj}5N}|L1P_KQ`vq!2hu^@8)dh_iNYn-lN_x z`=bA2=U_cx@qcXkKQ{dz8|&M`|G7Kok~eD4FWRj>1b(l1-`A|+|CSwi+4e8Fd4hP0 zwE_L}AJ1E3ePH-MUjIVzbY($L*!CP*Z@68|!vPKd$Nh7}+rj_28~)GT@PF=x|6@;= z^N0UqPZeJX|Hsa}HC6o|J7=lPvlsuzo^)%r`agE%Em`XS(tlm4{x5AwzWP6Q(xNP< z*%R$***Q~FohkcT*2diZf_k5}{Vs9FJM#_b`O`Tbvh(^cvRLt3?T zuAO##o4c|8?}R5-tN+92TlhaVKL5i1xqHX>hqje>TI2UhvOnhkjR{?={trIzk8fve z%X)Ebfd9K9Yn}SP-ZF16q+ifBHjdZ9|Ba7dAK?Go4gc5bi}mXN8ntSw^Z(q9BWyh< zy%@0mZ(uJQ!{+?IFB-q(_kZI3;Q!dz4*$o7U&Q>smtJ_u@BifQ!~8!sd?5TEyIuQB z#oIkLc2}>L)%Rh(+-IMxvxWzR|KoP9|I3C4JT3G8*jPUn{*TT1e{9bGV~^_7U;Q6D zNxtuc|6>mi4^{ui4wmD&nE%I)iS+wFc5+;j&i`X${a^S$cACupga2cvM8~TCV^4^R zmcOUMwqsrd{2ylkfB3|JXf;4N?Ec`y(hQNaz2tG4BulkN0o)D?6+I z#)eS&a#dlSl7t=xmLp)d-(dD zd1Hq2>eEfF)8?nD|Ks-Q^8N?@k3B`!SA_p#!vn(qvGe5L(;q)-XN~#E@PGXGW5Vn) z>i^hLGe@caW5i2HBWyb^f7tjCYpnkX|Hu7{f`xcK-;>pXdXx~oG}Ku^0f+IsAqNcDgG z_akPWN9OOwd)SyS2>-{%;s5w~CrjqR!T+(-dkh3`2ECz3%6L~_ZN?)F1E%zzbTI_vBvwi(DO^Jv7YsiS8lWGn>Rn!+4A4p z13Dq;4r{D`dvwK}0sU~)T^_!luaNhTGM_!5<@1}}KKQ%=|Hs=4UJm|`P5hE@cVEZqxK4^{S=i)yevc~yeHvZv&{^y;KSmX3Vk31UC+pc)r8a_C= z@(F9~e`3{>)|f9?{lh=4@&5Oh@TaZu`zZK7K7R1~DEL42)NA6@|FNgY=T-PWKK>@i z@6+J_*yED`B%j|}AAG}ZpAtEK^?1i^*6>|}%WJJCUz6Z$S?RT&G&fFu59YIm|2r1?WvNw{*RBJaygzTYdhQRiGLs9 z|M+;o@v;+H@7eu<&%fs%I&NJcpJ#vl@PzeDx&0gW`oMaI96xDSbJ7~?$M;(Mp*8NG zkw2WWo+up?_K`JwV#bYUtZ{s@+;`R*`_F8A&ieY<3C@BEpIBcj^TqF4{;4%i|H#qL z0(y1l&#iTSZP^#r`1fV^GhbTc_|);wzp@S~?C*Rwohbe*_&+wb!~eM( z{?B^!81;Ybgh*L$MEoBw5B?1PkBxa~@PBN0H26O@ydC@>8`mHH&)x8U?6?TO|8qC| z9~<+>G5^oq@PF)hx&D~{#~vR(TKyjz-)F=Bxf}k^-SB^GcuV*{HvDAxKNebJePQ^& z4jaPM17iJ2_&+xNAG>5sl+OQS7s>U-{6C&QydUQOvEgMf|BsFP6aJ5<$M2!w|Jd+H z@PBN0ANW5u{1f~i&kqg%=Wh5vHvAC$9~<-Y2JE=a9xv#BrQdFyJRw^BANNm5j#2-| z#{4$;KQ`vI!T+%_&kyVWvN2x`{*PTKz7O;N*d?-lF8rT$Lah2f{=FsA@PF=x|6>=) z`NRLQ;q~DE?EJ*@!T+&wdt&~dyW#)XrSkhV_&@f<@zLu4*fsIv)c>)oWPTw09~*w~ z#}6N{+Y{I4&8aJ_;ot82HL%NX{kv_Sn2@OckLQQeWBwnzFwVdJue&k-j}71U@%V?W z^O6$O|8YC!_rd?UyZg6wU76(ff837igY|#eod3t>{69A5|FLm>;s4mUe(--)d_35fyw{(ty7IiBI( zj`gkG4G-+@{HUmaE|B?@|J(NZ^ZV+1z*0|4!0Aim_>24ea-srnpZfl<{yf0{*RDS= zuzuI~f&Zgr{d4#AoiH|VzF*wf!0qEA1ASoqd3^s@*Y|w?*L=YCO#{~lZrd=>`(b@e z_w{eoJkTRXcI*?dy(B!)qsGa48}8F5Pe^sLM^yWsS^JY$j`KukIDm{%ALoiS6CNUS2&;VD)Vi-^?UV))5LGB zYF5{nC)gyR#P{Ts@6-#Me@C(P)mP6@|HtjO&Yh|Lk9~{G@51~)_5$&Q@PE9# zg|nxr|6|`g-S7X{b4#+-|FI_)W~={W&yeej`G4#s)n)4c*d_A#nO>diJNd*9>L-In z4paZf9wz_3!~d}(WIi(dA3J2&aP@!e5tv_@mhbD*`QPgM(7W!)v+ffz#QFJ9zHj$+ zzp3}@HFA*pKQ`w5VgBEz_y4Z*|2p;TqVxaQnE#0RfA{_HU%&s8^?Km{dWHU_{txpd z;s4wX{}-Kc!Q1JB1JNzpHg~EY&G${2;OM-+LBj_)X{Ymj!@hQO-ruN@;p+ctuWz9K z55Gsj{J-0}G}QTjcs|1awJ&d^^Z$yHlhps6zR*bhUvhee&i`YVR#dA0v#u&p|Hm$> zC{+K)F3eBT`G4%ZoOtzr?27bg^?&S~*kJX4?8u@0oRkrN_oW?)^aYi6iW$(Qo%7=3 zE3Aizm&E$N-sPj!2crAS`oF_dBGmKYcQ$D-tjxE;qx}f*ERed=KrRS`W6RZXrp>t3xB2g(`u-P}FY~Rf8#Zj{ z!2j{@6`tr!UtQ|^#n(kWUlVyfg#UZ*yUyzWYPz*m|HuB}`A60NasSgBH>m%sd9the zzY{O6Q~$?)!h3EU&`!~F({_p(--2&$Sv9TWSlZ$hGYQy3AN%-DulheW*7wEyKlc0Ht?K{SAHL~T|Hp<0 z#QZ<@xwqd`|HuA78uS0yCwK2q|5w*L)&IF0{*O)n$3C}zulheWJRtm^yW#)XXJj5A z=Krzb^)Ua>-B|zE-SB_x&t(4H+v~!uKRx)4`af1O;vFZPK{#ZW<{*PUCZKC==cE#0k&aSFAZ9DxRx8wLa{2v?JWqlTFtPchM$L%=& ziur$R{2mwnj}6ZT|Hp=Rga5OZ^+411zGj^=Bhrakw9y*JH{t(y`{VfLM_V>nuFB|i{;Q!nW|Hp>!f&X(i{GYqw|J)7#$A&M0 z|6}9&!vC>TWWEOcA3IHsAH)Ay%jq{RdMcpd|F|8uFZ>@Hz6k!0jd>*Se{9Svf&XLU z^zeVRLyxI1oFLy1!vC>3|Igj)4TB1cm2L@R;2Sv`(@r1SMFEehuf>yk=v~CeG~j2w-?L2 zL-;>-zRU}R|6{}do!fnjHT_@Qm;2Qh#)$V@f6F2-d#oG}ZvFcLYxqB`|I6+4f4sh9 z<@=VhyzA<&zkDC_^&9i-?@Q0SLj9i{^H={@ebor{f9yp0J{kUx&*v0b{~G>}ohkD< zG5?R9E%Pog|BsE^1OCt5@PF)7ndb)o$EN>d7s~po@PF(AnfC$z$Hw=M@PBN4{|Nub z=kFx>z7GD6T_xYA!T)i8d>;n?$Ig)N2Oobl(aXO-_38-qf9#}Lq0UNgtlfU8;`!kJ z_;^W{`5EwkY|r#y^?&Sfvqm|y-ydc72fiPN|Kt6I@5kqK7-{z>eCy$RhFMRL=ljgk z!S;B8w}b!V;|UG_H-6zh^?wuP^%4G$jqi8h|1Np;9rb_k!tj6YPPn^^_s|!6)%(%^ zvEl#1esAyndyl>9{V;C`{?FaLu5RNk$=#!#FIir{{`^lXYdn5VE^1*79|-@){j=o$ z+1#s%cg2R?wjS?_H4OtA{*T+UWj+f0pS$7z*z|wwJefBG|Hm#C4+#IqE|T+u|6{}R z4Q_b4w)l&;)%&60|JdnrewhE~ZumcTzRb^&Sx&VNB)qMj5B<&2o!0PwPkrYN=m%4_ z)D|v~!O_lB(eQtXGd5bo|84cWZ2Mz9-PuKJtua5a&%EcY;r~{(d&aI$(Jg7}|9Jh1 zWd0ufAG=WI^X<-GVVx)EzhLHa>s&ei;3aohXUX>Sk1ny!k@bGVs}@<8-IA*QkGCh* z1BU-&XUlv+%>QHOF3C~<$F8{O|JY@VGSvUA{^2?Ge|d|u)&H>zmgcJeV^5X!;^6(NUC~bc9~&O+m+14`*qHwX|9ACY&#MO`>(u|@ zcwNgY_HT7J{NGo{*Qx)*@j0yj%f@^^{9knD`T+kI*vrPS>HnJlv_8Q9v9Z0)RYS%e zT=AlMKQ#QGwH$we|6^a?>QeQ8Z2G^xm%gO_uS2J{>i^jAU+{ly`ad?-i#;v=j|~q9 z|Hp<0{ANvqDE5G!{`r6G5&ix1|Jc!CBh>$~hsy7*G5?P}JVMq-6#vJLxVZi=J3e88 z`agDVqRbBv|Hr2PW8?Tc=Kr}H{*R6C%i#ZbdufaRW8?b3|FL@y?x+5b_YZ#0iuHfl zeY$m5|Hu2cSGSJp|M>X8JU#e7Yw>lLmp^EY-+%6H_ec~UZ#e#Q?Wd1N?ccgq=TqYN z5Bwh=&uuPi;e4F_TtLJB@$rx2K{5-_n*Q&BrK{Bg!W+W>xf}kE&nIlh`oH#klj{%v z$Hwuir}n)W#pf^jgOz-{da~g#2w+?UFQr;gPvMwAl z#2Gy4m~~82H|O$*1|Gg%Pm|v-MXqXOT_C@As_fj&#r!}1doWQN{*PTgU*=PY z|6}9*6Z{_=>rcY}vGMOQ{2yPx)8zd^)UHmp9q*q%9o5Aezt6dIbvJ9w`ySElO6v*o z`33%u=a19F|FQA@z0bV<*7@@L9r!<9ey;pJ2mX(Z_b-_L$4-*p6Tttm@%u9PKQ=x; z!T+)058?mVm{$+~XD!>||JYd16#kDLKP$p%b0O9mm%s6vIBQ&f@fQi!n16Mlbb@uI zynj0NRH}#n{!En5moksm8o&SfDk9s%_b(GFhdDc!<$3siD7k2;bNKZl58q$K=MGf= z$M@?QGQT^rf2GIWcP*dn;rqdqydaq;HO0gCk9iYAWc|n)9=;#VoUHS?J$(OKDxarn zE3fwO{cfo|KIXN%&cn~AOC*5}*l`>pe3{onWdt_W!O zKi>W&^ZfpgT`Zms{;#gbtN&wT{ZjZpHZBkTkFD27{2v?J;s4m!4*$o-`oZvj?uP$k zm&@lP_&;`ud_I8xV^_-O0nGnnSBX!8|KsDWXl{b~KX&HSDD{8r+!~MiKXy`au=+nX zKA*z>@$np!H(322J2rQ?`agD*_#&+T%kGxj+j;8nOZNO2RuiiJkIxtUeh>bSogkn0 z+dT2Ab+)`-!2j|5@cJ*&44m2RgrDe}D1JSf~5Mt=1*8#>wZqZPqxx z^~Tq=0o^>JG^a; z-`fuBv8Qf-nOC=P@?LAap6*-ojy2}}b@_3hHRh{M4S&}f$M@vEv#t=&Cw9*o^HpWm zqFsKW%wLqX&8>@MJ>4z4k60Io$K2EESU|)7@&3T^6Zk(iK9BmEov`~4^Y)gfydTi; zf7~BFbLi2NwjCbuza39mm&xt5zxZ@O!~gO0*be{aZumd;WVt=y|JYOH{(%2uWBwxi zAG<_uZ}>lUnH)dcEdGyOEM6S`kDXO9RQ(@2rFek)KX!J`F!g`z^o&93|Ja$C1JwVq zGi1Id{2!lx>1hMi|FKh&`#JD`e7+~9^>q6G^e^j_tiJ01`1%6_{(}i!cgb4e_XI0A2Yxyn&U+C{OZp)f(QKX%M+ukszcQCg@=yN z^?%u8B0_cjUv{R<_k;gqXN&*)smEk%_^{cL)d3Cv*J@O-dPDd*_&;~U|FM%~zBlIo zu@l9s!T<5{;632~+ztQ7#=JlHKQ_KEhW}&Z`osUR(?dcW_&+xOUabGi#{5J0KQ=rb z{2v>a2mi;0_k;gqdxAsN|5?lY9{4{t=J&w=vB!r7>-xWJtXB#D$Hwgo|Hp<0g#Y9B zpQA?wtN&wi2){hW}${$^P(v?uP$kV?A28vc)sd2aB3?uP$kV}JNRc9D26%>QF!eOb)^V^_wUaJ5dYC`y_Ez=h>DBN0r?21HoSC8}m!u+w1$l`q!s^ z*Y|w&J3cDV`_*r}KD#d;^V;0~|LXlNZ64_N;APzBSHC-me{pZ`(W+HIJ3)g2x~F(N z_x@FtH32>As<{E3J7Zcvk1Hxr|2J^RkLv%fD#}y;$G*P0QvDx0P5R7lRleKff6{q$ zv9f>J$VooiF6Z~pxs}#gWhIVx?L^-@?S4=nSW{l=eBY|v_hhf{)yvJOs&u9&m-?cc zf2TgMYFf23$9OqnFfnA^Sq8#;q++I~)sQ!;#US8lV>yu~uj~X>x{U86HkP$=F|FQA! zIs6}cSXijj5A}cFHu+8cpVP60`ad>~FT($ws`x|w-{l=zJ3oF=;M=?PPxXD> zdUSHaudM5VgZemE%JnJv^Dpn%GY6xwesHtZ1-@&q^n1V1Q6ts=u|vj=QvcU?oumFQ z%oCyh@7vS{>i_V24*0)?%Nwfy%S-Y5zxd&P{}-0!_kZk&+-&uK>@-<#{;8CFA3HfY zS^Xb7Em7vhtjV?Q$ukA1M6fysg-G6wH`oH#TN2~w4T#om`|FH*L z(O&)El4%j@|IqM%zYGXh|954V_UixG_&qrM9~-~VhyP=@Z{J@19~<`v{2#l0$2QLX z&UgE&&WEY*>(imFGi=#i)}3WNa?JnZcKAB@KX+sP-_hqn)%P`M-caZNv7M&=^?%v) ze{8%y!T-4%{*R6Q;s4l8nl#b*f9{s|pT3g$A?o`uf3VZi>dzU8(*r=+92-|7wSIRsYAnu-@(xU-_*1Kla|uudDy7>y7IF*t=ifp#JaPrCt60@AX%8{vZ43*3Ihw*zd^vJ@`NN zUh#Y_9?Z6e_k;i2dR;g5fJemR!T+&8l*anMY`%ql!T+((?R#72|FPi% z;s4k;J^Ua0+<|wUF*irp{dIQ#KIf-p;nttM`;N2f{!!Ln9zNidJsM_>^?BPr8*2TL zc)`7EL+V<5ALjq@^5E~_|Ja|(db^na$NuEde)WIuhW}$@fA~N4M{@b_e{9ST#QZ-t z<_*ICu|GZT_kZq&|6^l+_&+x01H%8Y;R9>_{i(M$`?xoI^NZ2&f7d;8&ig>+d%E85 zcORZm|M&32$JGBFd3U$^KlX$;k29#rY3~yUkE-_@9Ow6c?DQ#v)&I@!a76uI{^T+0 z{}!emR{xhfX*AZ?@M5MPydUQO;kT7Ae(-+T)nnBEu?u9L7yg@FCcoE}^*_9_=7;*e z{OMz{K8SUmte*n^$L&SaBGv!78~%@-Df0y3|JXTld=UPRjmyLQKVCkLC&K@+bLDtA z*8gSWcsu+bJ45CbVEtb<*5`%)W2egTKKMU&lB_=r|HsDf!{PtfNpids{*Rq3*BAbe zog~NS;Q!e0e(-{2v?N@4^4EQ{?+D_&+v|zrz2y8~%@-cG3T_F)tGS zkBz?%{?Fa;e{3Ajh5vIm{2v?ZbHV?yu|6>T9~-_3{%`I_N7VnNT%7;M#`lYPZ631y z6EW}O&A(g2FT(%v{L79^X2}YyY4RUtXccj`=yA_j4imsd*i8h z)ca-1`NRLQ@pw#}a+`OrNGE&g z&9*(Pc!aZL=}p!{WxgN$-!&`usSk|I?5+NfJvyV8&i~`}56|?^|6@ny^l_s1U1NV= zMnQKuUVODzz5`J2IAwO2tS>X$I!eATh5zI88SB}?|FPk};Q!cozQX^pG2adTkDWd* zM(6*r6R(L;|HsC9yqN#TP8IJ5|Hn>|^}XQ#*roFQ82q2R-+DIN8tdZ?YL^+%@PFJN z+hyL1S7sone?-Iou~X#x#c?Tdc6%hrd_DL--d=eZ{U1A9=KZbvW{lmw`1|geG};<} zAN(Khk9he$75<|CP$4jz&|GFS+pgq1)<@-SRKRzBS z#8<-qv5Un&!~bo*dT)ULV`Ke3_&?w3J?j7P{Kfn~HvBUD-_EnU)&Jr9qlB+7^X}=i zTfHB?KZ5^b!;ixMvFZQV@SpI1?uP$sF#m1!f4D#3|Jb>5|HJ>W;XmR3*zlk5e{A|c zcCLJ%-OBrQZL=5OQqNZ-^CjOrcHX*5{Ke}bAJ@iQ`j&dVtQ+H;>FKAeGjAC0^q6+S zI$mz?!;6ntCyDP{`sBOTm>0O{o87f>aWW`cJYS}GypgSTT30Vhb3PgDwVr%asssPW z{o(iE|Jd+*zuozgb;ZpY&e}C=tS8ERy|Q;!TI2L>zIw_Ur@wRc<97YZZcZ03@(=40 zx%?kLdcYc|U-{cT*7@@H6t%y@I{jw3J%=x`#ymgxKiO?z=XiGya-x`(yj- zA(hs7OESe*7TW&Bvc7O~Lb^4);x|Xf+x}R8IOmc`>$2N(ojV)1ul@JJmFoR!ZY@*) z#~xcK^A2SGAA97m*6RP*y{~lC|FJRu3;yq(f2~yihsONBTbI3{{;x;dmOB5>-SB^G zcqsV4&J9+n|3lCDap|@fZ&;@_Tsr zKi*!W$BfeXe{A|c_LT#BtN-KuGq`U*^?&Ss7uWyg{oS)`2lan^e9-@~G2ajVkB#|$ z@PB-~(f{%B2+!B|<)@@L&zH7q;Y?q;%9{RMKX%$>jn)6LZ;6jk|HqzPFhczwU!U)}HeLN6J9$Bx`agD({Cl%(S#u9NSG@U4 z|7l^JE&skBpL(e^-cSDdej97Nzv?@ooprYS{^H@R4j%q{l`HR8;Q!c|e-8i0hEIb3 zW8?iP{2v?d=h}SL)6O5;M-}(6#^uBRasM3gSbNV8w9b&<@60Y5Y>m$c9rh2kPM7x+ z@PGXG0p1S&k4^u_hR0d|P`I5QEwA_1`2E%Ie;XUn@P9l#KHtFqvGIE+_&+xN9~<-S z;s4n1f6pCGv96HyKH>lPegf~0`rVsloh+WH^@dyz-_PV!MmUe3F7)vIQ)1o_=ZhU> z9=?Ce6b}Xe$M<{a57t*%rxy(tPcp^B_lE_OLe>BA{b^=(s1x_+Ob;8sziT~zu7~e$ zOXT-&YnsoqE|AY}@sD0-joat!;2W%Q`z)yan{}c5-l=28P1gAR($H^j_VDv>(VWrF znDASz%jQKnzcg5E`)7$)-I2V+I#b>cS9Q3}_D>d%IA`MR)+yov7p`7rjroAT&Ah`- zpD#WT{*QkjJRJO=yW#)b4gbg6hyIUE|Hr2PW8?RQ@PF=po3kAELN@2}5)-X4Fca=c{QV=q`|)r2|koLyy| zBlGq?=(ol?swPVPA0NLF@_hLBOY3ZVTi^hzvc5I^A3M8jl=?q*W=W{}KkK5A>i^h@nFH1Tv5PYL zsQ+UZXZBV9$LDWGWqB}*U-f_N%&h+E|M>cunlV`YA3HI*zxqFRXlj4; zf9z2*PZ0i(9h*E{{U6(tI7Iy)yRhE;qI_Au5dQD83Bl_B(&YQh8~0aOWBtQ_e_m-# z|Hu8&nEyAk+er0&m`C@X%>QG|*hF@PF=x|Ff3)h46pu zGMPUJ|Hqyv-VgqdT`qnT^Z(op|HtPaw!{Cii{<>`|J)7#$F7ja2iE`P`Jv(e*jT?A z{*PTGzqf<`W2cOdRR71$PL5Uo$4;LRul|pnn&|g`>{5Ar!T-4%{*PVgk?)(t|FQFB z{b=|~6gN{coKZ9e91}-`-d+ z!hQO%@W8+K|MGwJ*Yj=G48I@VzKH+B{4M@B{y*k#xx2m0?{as(_m+{%=Ncruskjb=4)#f;T4n z(suoz-f!wuzyD*`$a=WrMpxBsFV0i{$J5U!D|9}2rNYOaR8s1k{ifX4=E3jO16Gxm zssGz?&o}D-$|hB+|6@;_T&4bxT|T)&{U5tR)`x}vW6zlGU;melzqk9zLSNO&Z`B(v zoL=Ev=vvp;ROGAw<97JRo&U_Y{n0Bw&a*Db$#NF_o@duTGI)gZQHK_v8Do&a-w}HFwH)6!H5FjuWX>}|HjJtFz|n$c^jzz!@t*4Y72cYmN(S-f9WZS zI{%M7LA*QG|7FL@?-Aht+>P~rt>yI{{*R6KXYhaQaUp*H$BvZa*YJPrp)Gy7^?&S+%^RuzV>g%eaN+;h@PP1t4=)Yz`#*WT!TP^!M}QsX|FIi2 z_OJiTZrr4y`ad?#AO6qX@PF*4O`EF!V>fT!9KS#DT__4x|A%>n@PF*i7w7-6@p=gV z$97~p{2yD!{ptL_)5klj|0^vibk1xn@v+xlH`U4AUTpp4#^-hZAGg2r%3Ae*_iwmD z{h#mor_}$k-+00A|Jb`_-e2(00-w7v|Bt=rwO7>t#V_yTU;lU0M)iN}W81c<|6}hH zzX$)vrvGE_m-&3~e?Kkks{Zdl?H2Wa>|?c?)c>)MY<*4rAA8@%m(>5UIscFS?v~B! z|JVn&zM=k)eMl}3>;JNkZuk2?HasBwANzxye*edQ|Dyk6!}nqRUpD;T#!hke_oJux z9B+;Ndj^fOKD~RFb9`j1^+$W&a_)|d3268~p8rQOFA(ehvf=%({x6&J|J;rFe{9bG zV}C63^KP3z+Ai;tclWFR`xE**Z;Ma%Y*-OH~b&_)J6ZtJ}uV={?A(G6T<(ov3@Y-|FOCL zue;&@*qHy~Z14 z)&Cv6>4^Hj-kxSo*c&Ik{q8;N_f1nqIDgxJ!u!gFgX;a@`7r;F4etm4hc$fR|I#n| zKg{$~|2HK{yvrdkjNi2@Rz>H^JTn|?VdshG!+*2k+2H@&4gbf^lH+xLh;@P-Zqv2pwv{*Rp^ z#{=R2*hw{G)&IF0{*N799ije@9Xlmb{U1AX$|&`J?uP$kV|^$1KQ??L{2v=02L6wY z?^F7H{fafb82lgauUuL0WmoT)t<&ZEJNQ4|ziHx&;Qy@U`zZK7Has8v-&MO0sSm|` zIn4iK7s>H{_&+wj&w>AQH~b%){*R5n2mX&8E9>cE{vSI*JQ(~RoBq$;@PBOjKX=3b zu`y2s{?Fa;e{9TSg#Y9716^76kGk#Rui*b|e`)wXHvHi5^AFhVmnQQ{R$O|&-Tv@P zZ5Q0*mEXjxf204K7_?9QUyM8-;s3sTWUu_Wpg3dcR6pp9=oZ-SB^G z`agE8%rAK8nOkjpMCC}QY2_`}BZ`95|MBvo@`tMbV~@@bQvWB%@GttmAoYLj@U;Hw z|9JgFvi$y!9g*Kp{U1A{5bMQUZGV52JYV7eczeW%_ml4z?fD!l^F(C+h;^!bzX$)v z*9)w_4gbf+_i6Bd>}>h|5A*-n@PU~B$IhBRUi}|CQ+yZvpS$7z*xB>_^Z(fRz8wCK zoi67O|L5*wn^W!jK90;Qx64XUY0s@PF)dxqadP`1r!@ z1^>sMDDzd}|JX&co)i4vl;Az;|I%gtAm;zM8~$(I^xf+J@cID%=k95f+k3-5d`rDw zlFU1V|6`}h{2BN^c8c8J@PBMPUK+G*;hjC^E%kkw;vG&s+{_wY5B`tav3?o+pS#1W zF4S(kW|#Us+&*95@OwZ%bKkGlnSV=g@?ZGDI(uP~lkwMAwK9WGeP8KKvOe$?=dFvy z?=?w3TPsFSy|%1tvrv`!Z9H|?I|)-lpu*B`cylk-|Zi)8)d6Zb^e?NPooJ>dAz)k{j% z{~f*VIrV@!)lusI*tzio)&H@F_GqB~k3GDpfBoMz-#w@PFZhzy&Vd%Yw-tP}Qr8n5 zDC-YAFz<%3|==?u6JR9c! zvGMyw_&+x01%CNUJL`eHdaM8A_Wu3*tN&vU9V+uo#Q(9eo(23LJ0c=N{U00iJK+D= zv2r{|Zl5UL9us0CoOZVtSmXEG@PFJtB7CU&Kkgqndbs*OHr7MK{6BX8fqk5oS+`gZ z>)l=bAMd}Q?wxi1AMbDczO&_fcSrH@fa5cm|L1P_KQ@l%!2j{_2EUh{^Mo}{|3|N< zqxkrw|KsBs4gbf+@gL0pcf z`NEk0$Hwm$F#nI8Ci9Hp|JZrg%Y4A;Ej;}9Ap6=0&L!`+vc~$M@PFLDNIV|=9~nF1RkqdE}8Rth48im)HMp)|f92|Hs!;{5}KzkLQo~8}NVZbn!@K z@AR{VXMz9Y=?mra1Nlo%3;vI%N5lWIaeDYa zHhzBv|HtHpYe^7|zCKX$p?UhseRendXM!T+)0ACsHr zTI2I$@ZbUu-~Ysy4|DomUgqKZG0gXCo>bxC`?=KoLF)hb{%}I!5cPk2|Clprlrw+X zbPwNuW=#%J|Ht>QMe=x@c=sF+8=r3$biKwJpKsv*_4`X_t>)GXE}Xc)oVNyRGs2Ao+Y}w-@H$mG4+?jnl7hexEfi@4xByTjTv| z%7YIC^#0@(9=ku}`Ec^yzX$Y}#~uvm|6K8pfNnPNVQZ{6+VQzZ0vi60_b=8jfd6A- z{Z{zDx{h>8bN?C8Yae~e8qW{-KklC=pP%9X*zjKPe{8JZ4gbehe=Give=nYY@PF)V zIer5F$EN>d{P6d||FH|?_DNf}*&6fiy8W=l8oyutI%KQ$ zq*7@74C(7&Vom*?I%jNZ^=z`a}OkR(I#&5UA?GOLQ%TJZ#1Mq)r_)7RccfqaJ!YpqrlDZCx-WLj522N6UZPb{roR8yC%}eqIc!}xUDjhBd(^sU##pE4&Bv_q`&#%vUcWSXy@LN^m&)xA|Hp<0g#Tj~ zi9dw@b2t2-yW#)b4gbf+{SW`g#=l?ie{9SLY%%?ub%8vdKUn`sUCZsc>c>y5vnqp~ z>%-1lr#*e^X=gO*zj)ff9}ToKQ??F z{NJI5Bh>$4{vG@u8|&%9|FLm?@PBMv9{e90o&)}mP5;Ns!+MRF|L1P_KQ_)E{?Fa; ze{9U_ga2b=fA~Lklz1BWKQ?|Jg!zAL_&fMNcfi^hD;gRb9 z*f>4>ADi?4*tk6~|Bnri2mi;$=N;H0p%sa#UKb{|a6Z{{$EH+B#|G69U|Ja!S z2mi+|6b}dg=Wh5vc5&i3o&U#96+Z_5$A%Zc{6BZY|FP4O6LkGwc9zTs#QZ;Yj?AaS z{6F@j6ui^i+7Z$7kW0%T2O!z-`L5%!9T>Kv!^ZMZb z*jTR^{*PUB(f_ea;^Ni+u}k9<)c>(-WPQ)C-&d=8 z`x3;DyZ5i}0qd`?i`O&v{&@X$ccJ)acjwjfe)TUesh(%Ae}47n0b(Ah`~0)&dBFO< zF|VEvgl~4A{(pGEdeqqr|<O7op7cU4>0RFpfI3IZzsgy8{Ujf|x}?l$zPZwR zdU3JS@282r;Gy5CH=LM};T%pc^YstAYHFPM?E||g zzu2~4HKo!S^Kel>!~gO8XHT7^{*OI(`edg=c%d(+)3@pou|53y0_zHy2Uxr%-?}(E z(~18z->!f7@S)D_VRa4vcWhR^{k`yi;V^+3_F!?_XoV+$)G}C?2ez+`;8nn z$O$Sb^!0xK7xjJU)(;g}Hy$=X{U5hG?OLk;Yw+E#>i-6bFNObO_mxKn{2v?MEBUP= z-@GG#sQ2q2{x76ev9D>{Kh^j3?%UnDA*RSWEPRABb5fD-vwnZ6_lqAD>Rk6+k#Bz0 z1@HMoN1|g!4tG8}UT8gfxcpwTLy>Q3rla0(jI4*8nOJBYIc$XbzqIci^?y+#L)8Cu zT;4$aALcC|`li6=ZumcTnEYM^{*N6R8mjaE*ukN)zJvHb_R!&joUr5BK3?9?LH(U4 zn$~r9@qLZMvut~KyUU!F!&ms)UO7sAUu1{&PV*-ou*UK6oh|S8-Sly&dOtMg|FJLY zdWHHwcDrs})c>*DT;ZSp$8L6+-~X|3{2%_0jqfk6Yg^ZtCyM!h-#jZb!X~tj5&ozC zkKL@HfBv7l;r~i%g4O>y7yY00MgPZcEa!*yf7#8NHd6m*Ew5+rf9&QmUjhD)-J(Sc z^?z*4AJ`)6|FXNu`Z(}^&x{?Z948Vp|FKVP@;Rp(m)PldZSb%E%k$f|W{vtk_VzU|==?wS-dFwp zkG<>FmvsIgd*{XVfB$&s3iW@x-q@u6&)r!6m%VrMM)iN}J)2(D`G4%4+g?}yH*jee z^?$o+H>v+)V}2m!|G69U|JZxQ17iLk`(57_Cw*_KT|WF_lOrkCIKMYeCR-oazSWuY z$%KIJ|4ouL{NJfx60PC=9{4jMpp%*g_Ft{zZTpA2eCq%B_rmMJ|FJPo5dM#STIK=5 z|FO@A7li*~e=I%_{*Qm}8EN=G_9rsW5B`r0--r2s?uP$!H|GDb&&oVL_&;9W`2+jZ z|FJ(mxL@c0vEM(iSN$Iw-VXlH-SB_xGw&Tz|HsC9!|;E+d^G$Y`;&tQ)c?7AysZE0 zZumbo<`uR+JJc@kxLp68UktJS@aQ4+f877fp#$pw*k=zPRR72Rje4z zBIf^bdyg?q9p9H9cqiU)P(4>d)i7uLpU1t^zIj)DUq)r5^ZG0AS*KTwmh~-+fz3ddC{; zzrg=-d&xCP>i^g&*CeR_V`t14?;!qbG#)c^7JL1X?O8}k#+ui0e#qdQM} z-8x^6ufqRve;j{=|6{|W!T-4%{*MhG2mizb~*6>sCf1hqRp#Bqn z2L8|8g^#SY#`+_7rLM8Y`Xk#ftg^=UTR(4jA)p7;Ja3Kf$4ahPX`L#6&+`4xT4R0E z9gCi^#`>iH3Vzxef8U_<|Fp*Ud+>jJJmdRC%>QGj$oFaRe{9VAga2bE$oEh1e{6g| zHFNF50S*7h?eItNf9{6=W2ecy3iv`eJ;nfHOsyVd(;-!M-7AA6d7zY71yu9D{y{2x0(d@JVvu_LNN)c>)^ zP7GE5#}3XLr2enCV2^sk=&U~K|JboP{nY>Q`eD8w*8gRPrT0+($G>NIdRJZlmpw+- zm%;o$c0oxmr&sJ;>)F?gmgCE_tfOU~O#2Qqy|RXo`p6jZQ1E|zey7TOww7n6TBnG| z`!1u#8sD!S*E|K-e9(|_Vx=c>L@bXe?c(%$VMFB0JR{}byCf6Ds4*rj? zZ*lVd;tz=#wjB-s$Lo*pCl^khV1FMP{*Qkzo}ci4?*80~wc7{JSNK2Po@n?#Hs+h8 zt&6bx2Mzzn`zue@r`!K^u$T95w#=J^|6^y(kYRTPL+$aCK6Qli#IZrvSYH_akB^_& znPJXDLH)d)etO&Q`)0~KkX5~{Q>Kqn|HtikeobxB-TTmR}Yt$cEq`oGk9@_T3Tf9{6=V`F`}ez&*sp1!ct@BO6V|JZ5QC#nB) z_xVQ~dnb+FslE?BGPZw1Yxqd`KW>Nr3w`mo+D9JUp`H)@#hzcR;q@N-@qqAu z+&|}UiR%B{4gc5u*qiGA;5Fd?+ztO{y&y^bA3Iz89Q+?UL%iDCSMIKT=F&IS`=!hJ zz3_kROqsU_|HsZ)m?EBSvvvN$RP}${j)woUmU(=i|FJrtAMUx*I#2vyQv6faxpMmd zOnb~4+gC4t$U0x<2Nu41zjdKB{2%`wctrR=cBOd0$W@C2`h$BHTEpu_9lXXGp6}__ z)2%VTut|D_HRcyiyC>fo>koJQBgL){)*rquZk#oIBK#k35A^iJVYMe`ZI}7~PexC; zHP?A)e9PMNhn|t+LAOQ6EzEFcw`*kmxAJ)Bz8$}A-@jB z&OfXEFSMn6p#0n0+fJ1|r@jd50mJ|OeC#>(fM~Hv+m3v-QoUdIHvaj4Yp}*yXU_U;Q#LLxGKQ^y>QPe^?&eq@PFRMtIhvyXuHgs>;K;V z>}p#N7@s-WI6eH|6J6E>_&;~U|J7_+WAp#u|ArT?RsVi^hS9~l16-SB_ze(3&>$F`ZZ&f6q^c{KK4{`F7R@Pa#g zH;m$TwC`XG>rS%X>l+I$x5j+9FCOU{#q);`!~8#XaOZC7|JWhjd#V3pkLeer{*N8e zZ=m`=cGRGu>i>BAgby90{x6{WS46RKybSaI*uldGtN&vU7&cV>AG>>BzyD(o?Bn-; zy#KJ?@8lnrMe+WH|NA2R9&4i_uo#{5k9KR*890nhD!De8;L=l$#dUi5$LZsJ4p{y)m@13IdDd;9pI zN$;Uc2PuJ60wj=02LLkA-H z_d2*ujsN4{GoDY(|2tN6ulm2p_U)Z5>yAY3{dB9YCtfD&uZ3-W*}5{Wuk-TmW7cbD zr#lrdoUl%~GTS+{+wt)ICuU)qGp%<6Yy5lFc6}r3RQWvf^q-Bb@p%RQkLOR6&(rXK zY|QI=Jg&8Mf&BYixVx=2=4ZqI@%7|FPjq;Q!b- z9u5AFog`if{*R6MUR%z1YFqqBLgg5r7C&wc|FI!H-WvV~^Z)Ggg?xX4|6^nRlgy*F z#`hoiKYo6};|2f6#`>i2fBZZ&M&@~WOG-Tad{tUD#EHMH+{4dr`Qn=fygJ^)&wtrP zeboQ)^JLk?p)x;es)vnvQ}X%T!_TK^Iey0)$G6GxJ=WP%M~eTL=i%pH_#5~?HvA3z z9~;N-JzKG)_Wa^^%D-P~4PV%P)N(sL<_~VY`fBSe`Mel-bcJ=c?0-1Wc9k_=|0zY+ zSmX2aJ6o=`#_>0kPhaQL@PE90_n8ZiGR4?nMCe)Zo^Z?MLEzE}Uc*{3&-xz!rSe_gujHftQeH|nL^ zt+Bo-{2!ms@v?qu|F7?|E}S~T2@BY0ojpO0_n&)@HRi=-@7-iwEZ=7<|JrPwF7Fq! zW48MARoC8Yjn}_?-?zr=KX2AHyM36C*Izs!?|+eax}PuHZ=Ew$JW0e(pT_(@-k(_c zzA^sr1Gat46fBq{#7dGcSJJ zI(K}C^LN=3*3q*5FZ>_>o|5JJ+;_A0Sf|MGs7rSL$2w_-$7yllDeFq{Yw&-(J!tqp z_IUYwfd6AplKF%1e{A?M_&;{B{Jl(H<+aPl@vVOxIcOa_ahU9%JZzm(In3#n_N+Db z?>(^oIcw~ng8$>?=gE2>@PF*0iDByh*u|5EtN&x;^zeV|T)BSuKXyU+Q1yT8+|t1g z{2x21w7>d4cD}s-!~e1IdV&9Am&*Gy{2#mM(rER6Y^=8o|Hp>6>^%RJ-QRNAU$|@U z+t%2BIP#BotaaXC(gWXUv^rSzxqG+*zBR||JY+>{ciX_>y#nt|JYGUzU%$v)LFkUYn1PNBKWql%<`z< zuLIQc!JGXtwZa;n4hW~Rn{2v=W1pd$6@PF=x|6}9vfd6wh{2v?F5C7+G z_&;`0_$c*%?#BE-HqHDr?w}GH;If{YuneayU}TJthVo8y}@~}s!J9@%CYTTlhbAk$51?|6}K-CaeEr7s+~wnE%I~n3k^V z|MKq-J`nT&*kv-W5%d4t4gbgU!ym%`vEeh}|JV~^$Eg2fSB&wf|6{{)7ygfr2O9p*-SB_xN|}f0_FcID?#6t<|DVSELHFr%Jigu!9?`wM?s~v=*B7q4 zy{-qWyMA!phA(zs-+y(T^?xys)P4GK;)~r~BL6bV zZvU^#tLqW#`oA_!AyR7R`L%2A>;K?)+}q)E+})sIW1mh<%k=5W9N*)ySInF3vwhY4 zOMUvvnG=0_#*|WL{hF!XU*9^To^Q&80;k>4DYac$tp2a_H$SKcoI1Wl{hyt_vPAtK zyQ;iM{U3XLX|ei0_Uvg>)c?J6=zH~lOJ__~|Hr;!>Lm4l>^bFm&h%d@yzKEAan9tB za_`=Uzf%vGmoDq`%o%4rxuViZc&yZW`<>sa&nulgS^eL)4}GIvuz1oW2mX&eVPd88 z$lPK(eU`t54_ojlMC$e#ysNHn`A!TzmNB@VEMdzqQE=y@3T7Z59i^umcXgq+`S_n|=KBrl=Nx#hz`CAa3#Zbr(0k84Kg<5=SE5=qZRE^}D)b(B z{DQ9U3w}CsO`$jA`(Je4ALdVfd#czgYe1>@YuB-z`agEROM0sRV~2(XsQ=r&_D}VH zp5a5)|HZ%fm-@d5nMVl!$Hx7E|9hvwKh@1oose;%HU5u{ zZ_k8a^?mSriF2;EZY1;k;QzS2e*K#Df7w{S7xVwvxP16OcFU%X)&H^K5#j&b4gbf6 zk1qImr8VXY!2fZ(fBQD-|KfTEssHOHw-@XGvN8YfvNy`T`(Nl(ef6aUBaKmWwTI{%M-@Zp{6|J>cZZ=s$3&?CEa z{vWq{AAd;wAN#P(+Y6nO?|po8XZ3$C$UMNWugJ50UgihF|8e`lJ&&mWV;}m@qw4?I z&;92y=iohAcKRbv?{*g4pK1NV-Y1+Pk7iiI`@#Q>TiZpw;LHE|Klbs1?7<-dBc z#{aQj@z(f1_Ukh55B`t+#-Rfa{2%*-_(1qS_FJ+ZF#I1I>jT68vEM$l-}zhopS6sM z!Tdk=`~UhsHrD@z|8qC|pY^}~kBxbNF=L}@x4-zD^J|L7`a_w=2mi;%0}cP@?ygm% zYELhhcYJ1qPs9K5`o1`NRQ(_O^Os&y|HppswO7>tu|E(`2mi-@S9~D+ANzyXUs3wtph)`-U9|w#ItC-##B?jrD);eJ#-X6S=;EQvuc=AFJ_yy!;a{zoh<; z{f_v)Md$qO^dHK6!Jyv<`}7y}ef#d_gKYapZ@lin|2;YRb@hKApLj$4pSv;tkB#+= zvHman%m?qN|BL+KnEJo>b;`I2Re5)JXsz1R|FN+i6z2cA8~%@t`4I4by#8Xj ze)vB&eouk_V`s_!X81ogj^Bp=V<*V(J@9{Q{C))g=Wh5vHjY2Pdh|2aIR5;}^LwpR z$IJ1z;{SO1%&Ktpe{3Az4*$o;8}k$3|JcbgUk?7y-SB^Gte*@2_x_ew)N^8fA^abE zjO?!;DgKWgC%+#(xaMK&^f_bI|MB&aCi4Q||Ja!S2mi;${6F|VHs)Qx|FPly;Q!nW z|Hr2PW8?P^_&;~U|FQ9VBmAGc%kJD{jo&+NO1;M#>kq^K<@mp*-WBsf;Q!nW|Hp>! zga2bE$oi`Ae{AgEhyP=bmESM^2)V_sFGeU*z|ww;M|(|f4u(D+5Of3u}5X~Q~$@?%k_WRBhq?0$G=%% z_a`j9vlBdFo^@iSzxqE}BS^ht?Bqc8f9#z39`%3hgn#`XAFrf^V=;fk9zV?Mga6~- zI~xAa-SB_x?1ixo{2x1C=F`Fdu?rU@ssCeV&QDPP=Wh5vc9!@s_&+whV2e{(*2(gF zAp9Sy7tH@-i^&+;Q!pc z{N}$8Bvc+!?^htcZ_T5>9%#1lpnAQ+E8@hPowv@A^?QFfbH=B)w)(~z>jmcod|_Q6 zUIYG*mzT3RQT?C0;s4m#OOn+8v2&NEsQ+WQ5Az#aTo_?pCg+F$a?{omN09o7Gh%)3whU+?BkoP%fg>}U7;cm7|2%+Q^8^L0^! z+O~2|pSpFwyW#&{JHOq>|FQjAH&y@Ff7<=#|E8@PxStKLcOkR!{vR6eP!EXqT>tXE zxTQPH1H%7p{Aq`JK>EL`4Lg1OpS$7z_BYw3{tuo{e3(ze|E;=zm-;_!hyP2DeZa^6 zxf}kEP5*cQGY|OqKWjPO82*pls#PoXe{8>&t(^Nms2)8_ydiuadeeyG*6?NUf836S z|6^m`9Q+>}+r8rd*lpUhQUAxr`UUWRynYpp!+O6XXJ2oP{W{#GyNZ5 z|Cs*=|94UTb|3%eZumd`J@xnNr2cRH%lE0j?bFuJiRyD8l7GLQ+qQFJFL)!Tn? zD4u=&p86iX{}jl4+mXE+S?7s2`gm<)YkdE@?$@T)Y4Uj>WMT{JZ25fq?y*+Z_`JGe zR9kDz_lE!D?ZM}L_&+xMKKvgW$AiKDv7^Pe!T-4%{*Rq3>mkDbu@l8p!2hwcriD2x zBL-S$P8}xmXa`&4^9lSPPmhNGW8?c(uRnr)8vc*}zURn%CHOx!j_-p1W8?D>{2v>i zm*D@{@PY7uZ1_Oz#m9v|ooEdo^^t#yPs9K5^9Y`gv(IGu^sRw8*7&|P z>&ko&Ki^<|;AYE;J^VZczXSir&u)g3<&Nu5ZnRF8 z{TJ|meEe}d5d0q-^ZDTa*qF};|Hm#C4+j6oE)rh`|Hm$q{Q=Ee-f3Mb`!n9nyvrJY zPY>L3w{^ypP-oHG8?Ev8mw53e>sKQ>VGm#b zSRXj;&PVL;Bc?b|{U85chKsj?|6@l_7@_`;9a|Obtlzxbwx`JB)AN%jtutjF`Xhb* zv;7D5Sy#&OekslY>nhn_^IlA~b)|UPE#Ft$ z<>$%kBPj5ob&7bsL$eQAr&oqKSx+3c&XoHH|HsD%elOyU=dE+(_(IucojX3<5&LM3 z^~hz`s5SO4%39>sDdTGVAD@pL@oAX<$Ih1ZY2p9a0pc|=|BpR-x<~yVyHtED{GYqw z|JYcs7xVwvSkD*!k4^u_`-_JEV`Dxb{2v=0@I~=|?BdyD)&H^KC;PYmz#h+06@kv4 z+z)*k{*R|mD+y8m$4)H{R{zJwcKAOwwkKqNVVzt$O#L74PfA&s`ad@PA3I$hU(Ekw z0pb5{ zJ~mW6AR7LU4G#zZ$4(vPQUAwIkBrv&f9yn=X9oZ0Zumbo*Z*}l{2x0%+@t=FT{tRQ z{ojmV0@VM(m%;zJ8~%@-<`M5E{*R6MSMYyq_!sy;HZBkTkB!?0|HsDqxA1>#Tt56C z8$Jd8kDVv}1?&H^bHl@R{vR8@5&qBJ@PF)l*$)5bZumcTa`tDkEvEljP|Ja=W$Hx7E|6{`+V*Vc+>yyI&v9UfW{2v>)AO4SBAdd(9AG&JoY{Rks_h;s5sRtZn$em0>s8_QLph zC--n|m#3vUeKR)L_Q@$}>i>B86|pt`j|~q8|HsC>J*@xBhJS-{%dcv6h z$A%}w{698sKm4D&;s4lKV{6v`W#_~tsQ+VUCB&-#V`nGEssCf+@qqthqhyUaKN5lWQ8~%?CU+DH+g>~lrVSNJk_PSknzF%sTuaEmLj~C^8 zd3ERgWy|`~?(4&RNOu>HjrHmDvA$j}EymaD{g*eaGr#bE-G2Q2yRW}wl<(tJcRk;_ zU3WfVLWHkx$NK8-%dfkBFy5cs+p}d}n7iSz-CfrMW`_IDW31cQf9O6xJdC?LHTT`# zx{m*=yB=^^S((rIE9YG9)6fN#|oPMtEziTJ6=8tVmLIjpv?x^#+@ zbXk#|e^zOs^WbBJ)@eBzPOGy8)&pe!VzJEc5O{IfFOVMe+L)* zp#Bfu5A*-BA3v+}|9Z>*bIkvH^4W9h0WTid(}DloD|B^?$>M3{d~a9^pS!{ok&tztsPY z4hqrvf9$~FVe0=Pw)`!>4~zec2v`62+B^SL=Y958)L@w}iur%+fiiCp{*T>8=80nd zAG?wNK=ps@;2vGo|MBtzFYc`VkKMCpPxXK7Zr!@6{|jgprv9&6_m0lr0UNwc?+(%V zex19vcb>WDM(@1JVD)}2JNY@6w_5N0Y(S8DyTq|g|Ht07bDR1<_9NmCvHmanG4X@VZq2rS?mv&K z|Ks)-pV_1Sk9~CC)9U}&uU7AOK6@(N&VNk2-5m$htWP|DQ2ifI|HgCGI{%OT`m+ag z{vZ3bSDsh@$3Fhr5%qs;tZxhd$A0hV3+n&an6C%_$A-6q|6{|q!T+(bo-F47u`zEB z{?Fa;e{A?S%>QG5A?xG9|FJQ@4*rk*q4>9lb0e*>ePY>YYg`}vA5RZY2mi;${5|+T zHs<|}S~k-9^H*y8AGhQ3u>LRmGnsz}|HuAV=HtQtu|JY|dRYIL{h_Rn3;)Od_~Z%o ze{9U(ga2b=-X8oP8`lT_=WfjZW8?ZT|BwCYTPM{2u|GNamij+;!~d~Ae(OyK{?FZ6 zegmyPkjumRzf=8=s|Wn()LT0LkNx@ECmiS1PpW5T9@F)HzkK&Cr}NGat7Esms^0I! z%ZHtho_Mc1rOPYo`;ujTcj+zfRA=VBtRAdiWMk)e;@j5A6Nak)>pktL`oC=1{|Eoa z#`-_c-}grKCHKFi-mh>%jsIhhll6V!|Jc|+JKlM%8io(v59`0c|FJQ@0RE4iA^W?r zFNj?x$4BG8-Hr8s**Lx*{*R6Q=kR~*GTGk_|Hs=y|HsDfEAW5pZ2A2H{*OIM_IJbo zu_I-FH~b$vQGVZm|6^nSHvAtO{ssQe-SB_x;>qFa|JaqXzY_ER*x9mw7ygfrKju@w z|FPi@;s4m!4*$o-{EE(7AG5~%3iv-h|CmPz|HsDfIq-jM9ADof`XTFl@i{mB^nf)y zT*Fp`QM1t2I0u{2yP> z*be{4#_u`se{5`r|6{}dJ@?Pu*6@Sye~BNwq8>0o{384x8(t6ok4^u_4iGN||HlrJ zd1~-~ygoc0?>>5yJ^t{T@P7e4UR3{w*I&i^YpP`*x_UqKFaE2mFAIBKy&vW$VE!LF zU*^YQ{a<#n_%-;yd6zw>{%@?je&GMC<@xigTwxtv?yvrj=MOEbS^t+kMArYxUbW0_ zPfT_n^?$s5V{`hd|C3|>)hogWV*Vc+J`nzo9hci%{U1ATVzBzZkm4ii|B|MLs{do> z&yQCB$4-)Yd|wQ?wA$S=f5aN=ZN2-)WP3a@e{o@++*dUN8I~ z-!ITFjxMq7STEQAu|n%iIsdx8`PMl7x!ZDl8vc)$hwFdp%5>X~hX3R9kM+mk|J>cD zL%iL;RGHV;Xw6t__$~N9J|0+K4E~RgZ-LCeg#Tkl&IyN4vgb4Ea{2vP{2!lB%j>kB>){*SK@%PRN5lWIgXR79h7UScFYkX?yhl8*s_%=J-*>C_*RzH{6@PKy!UV5+ zzY1Aj5&qBJ@PBN0KKMU2ydV4@8{6Uk+ztQ7rvGy{{2v?Z3uFCXc9yIk-0_c>5B$El zTD@P%;yCqx?#BE-HqH{ zKK1-Vn|-?fH+NYVUM|N2w7bo^d~vM!lAEm4m!ybCS?kjuuf5h9-f{h&tF7S|uiU@b zIz#3Y-tyKQyZxCmpYP`$Q?2vm{@wc6I6Hlwc%ut^>i_KVxO}wwKQ`_k{2x1ij(7~2|F`kEE$aW`XQ!zDV~?67-nZh5{p?j^ z`>X%^^W;|bfAc~+IKkgOzn|T|{YC2kZb`jYJz&q4jw5RW@Ap4^ugwF5|ND8|ed+-* z9}w&R_D$ZVz6tB4V*cNEUvB$%{of|)|5lc6SN{iZ2mi;0=Y#)C`)#}WKflI})c<`p z^M3VzX!yUypWpA}|KgVK@bQ1_`pp~Z{J-}u>`?!Q79Tch`^`Jm`_*sN$btW3*K65O z{ol->UF!dEd>`ijxf}kEjoXX)e;0`#{PB$&qHupO|BsFRjqrc&eq_bNqmRctpxzJ1 zC&T}-aeOlT9~+kk|HpZSnnE&T)_&?sB z_A(z1{*R60|FHfqyGxfY>i^i-|MJ;Tk8SVJy_e4ax#rFLbe?9rcI|ZjAOD{Ew(H=0mbNd_-H(2}FS1d_7WIAsoja)iV@pW5EW+EXRJC-nC7@ZSgY zu5}%)ljQqU=AWH?`q!!5tRtq5cD9`AZVkVY7}v`hUhwP_eXQaC?&#Iu8s9JA|M>48 zZvR(*46^O;N$aN$vBu*u;#7b&{M$#d!9JZZeVAPy?(fX^hFhmk2yt#r3AYXx-?M+; zC~JH_g#Y8`hgiA2@PF(C`8)#u$Hx3M_&;`~cpvybHhdub9~;Mi$$IqGc>du3`1u75 z|HsDnhlp)?)>vN`{*Rxp@cHYLcgj5cJQg!P*qPjAyoaCXvgCLn_&RS`V`quKlKJ1YE#F_^|M>YA-*@5v*qCPs|Ht!Ve*yd-yHxzn zH=boa{o9J=*6@E#Ub@;E>kD*hwbB}&2mOw(wEKhpy!|!S@O8TjuC*?Zd6hYRuDA2U z8)kiUy=}+(!!p0!8s~@q-(@PBOlJ;MLF8~%@t{Xg)3 z?EINy)c>)|=E?CG;{VtcbCcBnu?wa}tN&x;_(u3Yci+5pmo@z#x6}Wz<0r|ydGUYj zsBt0c|M-0e6v`m$;JttZbX?ga2d4$oxY1KX$?RQ1yRo%=7!?{Ij;5{*R9r=J$z3^RV&$3IE5&`zQP# z8|%@+|FP4>^EK=Figj^WsQN!XKUGtsoWa{(v+YUKW1OeIJZ7CXE8a;O^tv_Hw|-~( z8`h=b9j88W!W#RVemnc7PhTH;(i$ER^Z$7JFwYPEkDV|3C*l9t@Raa>?DR=B^Z(dm z#pl8Q@$n2U4N(8b4yy>!`F}h;d>-ciu`|nttN&x?O2hxL;U(e!tmXB4@|G{Hv&FMc zKJ}G#R!N|)|I5cWyEI7s9~+kk|HsZ7C&#2URbd_T@B!v36d_WlSz2>-|J z>7}9S|M>o%kr(Jh)VpBs_vk0XfAw(xNp@kV`ajzrDvkAj*<-{9V*OwC=#0VY|Jb8a z2k87i_UN>MKEMA*$N74Z$QWM_7#$g|>;L}n-ca>)m?wwzf8CAsf7w`H7XI(&Jwwz7 zCPhZ6|6{}ZVg4UGK|BZi9~;}@|Ey)+8|MG9;p;wocA8z^1o4De|CiT4UVIzo|FJQz z3jU9sJ$jS_|Hp=Bga2d0yTSjlv3@Q59~&MI{*TT1e{6U__&;{M_!am+cAU)nga2b= zo)r8a8<&sye{A>@_&;~U|FH{XeP#GRcK+~@I{%N2^*7=F+%zJ9_Eq+Q$7!owvfa4>Cy0i+>ZH@@PBNN_$18#W2?6k z|HmFXDn$JsFE3`y2=#y5UOp~Y{U3YQ>=`=$kA2(ix2XU7bG^U%zlYY=_&@fYi{m0`E z|L1P_KQ`tKy1iH39wXQ1-X0^j$K9#2-m$y?e|;dH5BK@8{&!2# z+jZ|xn)qt>%XNpg9H`cfOzq;-`K=>B->FYK1^??QDr9RsiUOvaCmn@v`(^p+S zL;c?*?>FlI7XIu1*z+fhQ~$@FA>I%Ek3GA%K>goE$G=toH>;?||FKI-i`4(I$I0!( z`oHW7X{`V2?wIficKPGW3e^Ac`ld}PSO3SJA?xd6{vW$2H(mW7yDUCI{U1Be6Q%x- z*Ee!(vUA|VIJ^FY>>?*RthNiwCppi~Ewk+<ic9+=oRmi-;6+aeRPn>zFlNMNF zr=K@tx^sMntcUyW<5QNG*4;}V^iauliw6t4-EEK|Hth({`jj3@p&JAr``|! zo zx^-0l_r&ra)&C8?xRd(7oDJvI{|)NgP5s}OFa4zcuS=8WPNN%(z1`aVqU-&3sozxn z-=j&ts{iX;uZj9UHhe19|7GKNYpnm9S^S&&zux|X)c<{c)9>p4`UMP8|HmE{7^MDh z;Y)w0{|g@$=A6$i@;0ycmwLYtIX>l|8;ZPJM*gkdFHHX4G5?Q^f8XK%*jO(a{*R6M zf$)FqUcGv$|6^l+GUosB`mnzj^Z(fWx_46l=kD|aH+pw82~^KFpj#W~@u9Wdw^IwJ z-KO=n9rOR-|9JZLt(vI+V>fNoz!~|&4YnQg^f3P~B05O@U}N!pe;!-w+TOq!7hT)% ze+M61W82~X`t+{tCekZ!T5a3W@PE91_(1qScB4j(bp9W^VZ(+F{2%)w@qO@rZ1_C* zKX=3bv0FE(@qg@Ajhi@q?qBI$^Z8Kqe9ap+a^`lb?Pd)cIxk$e!nWi7!~gO0X!t)i z=KnqO{&H(a=Kr-wuk8lnDPQed?(P0~NA-58$w}(}PQTkhyZE|MB*$TfRvBAN%HOmO9tv z<=FMzwR(kfPkFZW=JnS(yQgMZZ@+b&^Wxl0>s@zlQ2)ovdvN1j>i^h}-@8TqAN#>w zTh;%ucR#*M{U7^9nKy{_f7wU(KCb?c{o2z{s{do3sD4`gANw6y<_-Rj{lW8x)&H?S zda1_$xf}kE{l3hfga2b=J{|lY8@>(x&)x8UY|NX3|8qC|AN%9u$JPJ28~%^|sdzc~ zKX=3bvEk|9|J)7#$Nu82x77c!KYim3o&U%F=*<)A|Jd+y@PF=x|6_ml_9^v$?62Q_ zTm2vV^gE~2|FN;2F8m++wD>ysKlYc>@PF=x|6_mu)*I^o*gw8|O8p-j*N^#s?uP$! zH~b&_tG7=&@PF(tPo8udcOPK=&Aab9)%`EAKL7qH^?wuoepUV7PanMPe0oBDuw4JL zdZv@l?sX1+`cAc9ub0&G#f1!TcHi-~bb6aZXf3V@%G~P75G1Pj{H6W z|HsC>2>3rX){}w%W8?P^_&;`v?Ei-UW2egT!SH|XhW}$@eH+aGW0%Oh2>3rX)<1&( z%YMNvEd8h|JXV|LHr*Z+u{G%n77cp;8APLtAPJ|w&_vzplJ9%cJj1g>i^hj zGe)TYvlb5s|L1P_KWq6t0{)MUc_HwB?uP$kXUXpw@PF(=Y4|^P54mHDHGJRZ)XmoT zJq7-6*(*oYyK?>?oBofD-;;iO;x0Qq))#~S{f9Z2QZm5=H=+*nd170^{O||S(SMLXJ2>-{%`alKaudD7C{H*%EY?()QQJ-tA zljbC;|Ks+sabfEJ*n>-ls{dmLR0KQE_PW~6kNE}{RW7&di9a9jX{*SkJ zO#V>ye^uGftN)A0AEN$`9iHc}{*RrU+eiH$yHZ~7SpTNX<%ebQ48t1Qism$IlaDMnd zo^`L{*Rq5-VFYaoqBn+1OLbS7quW- z{U3Xbtp5!E$A*7||KsDEBfl5I|FPr6Bfe;fF8kQ$1zoVfB7^KY{*u{a@Y{N$UUD`HPcv{vSI-*6)q|{rdxA?9}6- zf9~(_#T(d@_Kp7IzwJx`+DrQ#_!Saf4sf~nRk;EpS-mD%lQalR$AG;z?{On(ETBnb_#F<#~ z{Ql_TEjk}Cb#O1|%%ywwcR992ec*7vX6pZ5+`Co%UuW@YhsWNwf9gy3s$c3M>zl&= zMSJd3{|EmB|JUr@`_%t+Ygyy}K1tuE{txGe|6_M-)=2%I%v4kV2Y)yFx1;;mIGz{& zulUXFHU3YIZ@cEkCj0u$zF++xj&H;N*w{ZZa(2^E&oA4d-Veva!T(u{--G{iH|GDX zyLhMiKinSpKenGN5CZ?l#_fautGa2Y`agI-_&+wT5B`sh{gLp0K|^=d_&+&4{GYq0 zA2~j{@x8m$^TGd(8~Uj=ykYju=dE#h@P9l#t`Gi?mj@3B|HtP1Ki(d!4-Egu?$WNk z`ad>&+UM7W+4hbdJF5TV_D-ETssCel?%Y}ZAG>GgF6#f>{lTFMyF6^i`oDZUwI^O? z-L-31^?%%shW}%C>e5dAAD=%Q|B3m3Y|Q(^{J%fMi(WNtZB!RoZx{ZLuMhe^cfnrkB#qB z@PBN0qo{QQtm*%_9mhw(|FP32k5K=|E}SCs^~C?N^JTst{Ga{%E%zV(kDdCj|6>PN z1*rdHkDL+aeCF@5)5nV!X|^%iI#GNN{2xD0;QMLek~rIr`D|Bxmtc+WOYna@J?5#w z|FQA?&cAJ@Prtq*ySC-@3oqnaAY8FSmSuK^EtDvGvxH}fBgK4=cg=hzICoV--|z5XpQ;r z@P9l#{(Xl3W9Q59T=0MHzQ5seyFP56mw2^L$F5yrP5;OHgL!=Le{9VEga2d0?_GWO zb=EjP{2#aD{P2HlY={42x=4wgfzFjrn!wWtd zCr%%u{*SjG-V^?hT`2G8@PF)_i6QF$*tz0K<-cpU%e+6aX7+f||MBtT{6BWKJf84> z?5N5R^?&Y$|6>bS4ZjEf$Hx3g_&;~U z|FPAxivMH7ufqSabLIVdUiv%scwl~FqZ{9~PAv)0`F}ipO7T$je|$W#{{{2^*h!U` z$NG_Vj(EG1r#`mM7VkH?%cs`4vYziR#h>}~H5)&-&Z-cv{oxnZ8RA>v|9E@gEiZKW z+8Q1c^Z)pG!ym%`u`wSI{*PT$9H#z{@4tmb!_@z=v3@Z8A3LKkNZ$X?Tj$9BBlth= z|Hv&Es{W7re>3xgoUzM)^RTlDg4O?V|0vc6hW}$Hrw>&B$BxRVS^t+EojKGgn(aif z;}Yfg1=sq6qoW4-cDV0+BX~gf>EY$v4W9@9SFq7v{U7`U*8gQ=z8(A@8y*Ax&)x8U zY^=u!|Hp;nCp#*pV`i4*rjg`v?EW#(X~b zKQ?av2My-<+@8hV=UT(d!T<5}@nIv?|G69f&st7@e#HWx^KZCkp*6f5{2x!BF8&Sv zkB#et|6|97g{uE!!_V#LzSJ%celB6eRn~Db4+s8_kMG!FA?p9w(J~(g{*N6a^XI-h zw=61h;b8S^cs^daa=A4;%!5s@wx<8%`Eh@`)n8eAd7;71H|uH}w;%qGw_g_gbFSOD z%1-Z*2!Oro!YkTbQ0O!!C)pma;6=phHkJR?%bLOc3Wk0g|MqU4xz3GZ& zy8bVFQPouSf9yngJz@SIyFi`~_&@eI`Fq@W$$GmzDYBmIk|%r{{*R~6@QhLa$4(bd zi}`dr$<@%YaBtGnKBUC)R0+1tFEKsSXZx_reCPj-xO{=n_RFSCSN}KI^R@cFODEOL|6?zjSg!t$jd_3Y zf9$yhIZn=>RX&aRe=X9!Q4d%s9&qETD(lj+V)cLAPXEWQtSHm@f4uxj}m~|6^xnrK|sA2gl3)Eb)Kr?jeKK|FK659qgPdD)Jtm z_MLja;X?*FOCBip#y@(d#`6UXbSl0mvhFpgude^g?E`xCc6MhLc?VYipx&=fw~L+n zw--;;)}h02|ww)zhT3J)&K2U^0WHC zXxZP2`G2FIxS;+oKs;Dzi`tH9+|0Qsu-M!4&@bx!CJq|nw3<`w-F@L#^?v@LLF)h5 z0rGic`R7I6#38?%_rv!~gN}I>_~X8It84(8kZZ^5E}Le)8^K;>om@@rLUEczX1Q zS7zAx(OCc2u1{W{nE%IiTGmtl$L>FDp!z>{VO*&CKlZqka3`%ps<-~V9d-TSl8E-| z|F}KXzoGg+_PF6q)&H?)#C2Bx$DW!a$JfgIKlXykIGz8;o;0mg{U3YY6_=|2V{cft zNc|uC))h+}_&@fBs~4;PW8b@Bjn4mLdvCo_{U7_pu5CL1k6r!X4)uTThW}$9etd`e zKlTfI9@P1N>?gfXtN&v^b$Gw}KlXDn4-oVJ*hgeuAp9TuUGa_Zf9y}h_hJ4Y``pJL zs{dnO_~JA5f9#(=`$YX8`>*f5QUAxj@by>f|Jc8N`?UlA$NuNcH|qbae>~%~{%f$k zzJ59PgVV2ZZU1)uoD?>kp|2qDgoh9=C;s4k;J^UXp5BsCx|9F4s|JXWTLHr*Z`@iA; z*qEOH|HsDfG4OwETt56C8~YF8|Jc}n2>-_(KYg_NKX!%ee~15L?$H4!wu|6vN9~!T;^P>ZO`_ zm-70;{6BW0{N9H7e{8HT3jfC*BmNWqkAFW{?+Ek%+ztQ7#_ubb|Hn?ARWtvOmj|DO z^?!N$;$%Kx=SSC8%bGgs{bIyZ!vDD&{*R5{zu^DgJbOs}AAbLW|6@nYl=Tf{{vW$< z!4UO->>)+{)c>(V$_K0eV`IJn{2#9m^9|tt*!cZo<*KFC-O`>_uQ;MOK>gqCt)5f= z=Mf)>`G4%F!a((Z?97r&)c>(3&Wcd~=Xd-$^?xyQqtySgV`UzmtRGg*PL+9F@PF)d z@mKJFY|Lxh)p@dYhMa%Rx{21Ai)#EIPoFLG(BS{r<7Iuk;IpOH`2D0^Rk1bZpZ)w^ zfpxz4L-;?QAKT&o+ztQ7_aFF0_&;~U|FLoZ;Q!c(bLIF?@qfI$pvxoF|FJ_CM5_N| zXUvOM|HsD{4gbf6PlEsB^M{82W8?R`zso}G`Nr=d@PB;%@&1STe{6Wbw+9cl*BgA_ z@COF?H2fc5U-;~N>Trp zw&#HQKlrouBkNTkJHKDOU%Jfuga2cvElG4fd+e73IU)ONe4oyn`?0oVy;=A_ZpS=3 z_&+xM8vLKT;s4lJZx{a0-SB_x0=Yf#f7jo>PyJv1q6GDS>~wkk!~ePar}qyYXnFD( z^?LaG5X<4y@P9l#*0YBHV`Kiz&YK^$(?`yWRR71zi&`LlSNtD4NxUWeA3IrI@9=+Y zcun{}cfKQ{dOu~t9tkBHr*UI>?W<=)S&^QVng z|Ch6Ollnk>euDq&p0io~-_o4XPPeb0v>rdAm$R&D`~H+sTXY`aC4M#jFRoe)y&UJ? zt*N8_Z(PW|>i+`d`!)REC9mGA{x3-U-tO?^{ZV7?Q~!tch2j6$y_z*v|JUsO`_%uz z)4~6_8~$(PbKBJa!2`noH7MV%{tw@0@jo`a9Q@xGGw!ePf7;hu9mKeA$| zb;s6ioCkx3TVuUh%>U#4L4Wc_ymi<1e(L|Y9qZA4DD(f^4gbf+>EZwQcxsFPW5XYI zY;c87!~eOrui3K7r{VwjeB=D^e_c;(SO16kdhmaIeV{S_kB!Fz{*SLO`agI7(R*uT zugq;aj}qJA|M>c(|KsbqdyCfU|M>dv(Xx&DKmL7;Xxdu+AOC)W>NipUH}TOe>T7$q zY^45=ofR3T{*QmpRjFa>|Jd_Os=}Sj}5N_|HsDX?^pA>Tf6^j z8s1}e!vWSQ^8K^(>_OI8zxU94{?@s2|7Cr4Yj~%2yMuiCnkPa%{P#6kZhv5};npc~ z`!WBI|NckI_fO3KV~-KP1^>s!zaQ{_Z20)#7GtgPc?|xK+tKiU?!Lb?*&6@8y!uM2 zHRjR%G&;i?>%Vq;ILjK}hvEPDc?LeM$J7FA{Cl(NhGGvt|KR#J-8Rm{&s*><@PGXL zhvU!S|M>Z`KwdBKf9xXp{09HW#`jbBKQ=rd{2xERVmtgF8}t9*|JbAD`yu=vJ5u~u ztKXN{Tv z|JZo^;Q!e8_Z{DL_$>H8 zc9G2QhyP=j%I9hLKlT{;eh&Y~9xMAF;Q!c}^7{E_-W@)@e(#;u_p7^oDo2>D8jBB*Tr_Us8wZ`lBs@3;e)%$8&{N|?C+kHA9 z`+jSDU%~u8KEBy<{3QGz8~Z1){;#{?|JZnZ{@V1AU0$TTAHx6f@ky=-RsYA=e}Z_a zu0tO6@cYf^@?q-#*iqw0sQ+W9m5)&W$4-&;SK=lHbp4;6v7R7aw|(e->vEaz`B`AKU0;E`pNG!&S{I7%UisKT zYpl;J_uc;fGbe%>U!#hy90`|Hsah;}hZk*rDS4F#nGoDc|ql z|JbE7#;E_}^EGbPSoMG0o-BXQ@PBN~hh4GaxZNH+|9;QE?$g^YI$@3dRq%g2Kl-`r z-?Hs^f69INq)&g|;%#eue}(_!;}JE^U;Q6Dr*wdG+w1Sy_I%m@g86^ko>?BM{*RqE zaisb`cHxB4>i^jJay&Nt9~+M^{2v>>68?`(|HsDl?dbWHZAZiZ@&4oV*OY!^oh$PI z;s5yf=g9sb_&;lz_t&q@4?d0ge|*2@{6BW096t*G$Ii(ei@X^HX~<<^ZJXwdun^AQ{LuJ>y(T^&UXcWS;xsdz%Oq9$HV=pX!t+t3ZxcrCX_fWLtM+k5q3^?z8O75 z2LI=7_&?sBoX}wo{2x0jI7Iy)PmkM+`G4#f@ost3=G*Bb<@ay+Kb{}n4gQaf$1Cuu zMb_|quO7d`dPIoKxBX_Z^{C+^*t*Vw;dt^Od_&=T>^9$ks*zhj!e{9UdT61e{!xv5Ky~4Jm;s1F1Fu(4ZZmX;l zVx!gnaeHFi81;W_%vZzwKQ`uzVg4T*^T(chueP(~^5Oruy;yu#Y>Vsc_7sSx>UT$N ztEUqG$J1ww9-;n^T_CSl_&?s?OH&fn|FL5)o9QgeS!3ICmR+gy|G52{MOW(jzw8+m z6LtO{dxWfq`S;Z~*!i0W2Ra|LT4z0J#Bk@pU9~+uvc~`M{P=r>|6}9vF7e#x(^&tP z_XqRXy5!$v+cBT-w@-Zgof#W^w(tF|wz2;59jk7(?d9U#0$Sf{mp@KC++TOsHoV>| z18=kK=)3m#_OzJWeYS@mt8Mr@%>U!x7yKRk9~<-Q;Q!o>`G0K83xxmU{ipwPH~gQw z;s1F4@v-sh|G2$E?jPp=vGIC?|KsDI6CbPok6m|tU94B_^L|=qz8*ZMdwbo}!(Y0$ z*PTaK*UQ!Q+yATU&c}-y?d#z%|J8l{bv<3({$D=se{HYp_u!G;*I)Pic)xOQ$NT&L z)%h}S%)LEV-f!KF_iuOO{oCF6_rcxSb@fI=H;Tr)Nx@rvC5j{;$;k&73q{*Z*ZNs~WHVk3FxXK>Z*4(t>RDf9x5B zIlBIDyQ8Po|BcVhQ2)oCn4hKok3B)&-!T8r-I)K!%bQ$Ltp1NZrLsi*AA3%DiO&CH z&l^8Z{U3YgxN++L*s1b)aPB;b^q_x1N!&ttp1NZv};H8 ze<2}f)c;{U+pUk3c$eOPPJJKN-+keWV(Vn_es8xf@ow4uqk6x**a-E1?6_fro$dFP zcwg@NvwA=HMEE~8JmKa)ioM?rxS-xILcHIOs1onhCBLZmiwX#K9$#MK?X><^^?gC| z?^hRDPnjJOK2rT38}ApZ`xJX0I{ce@Km5I8{vUg=%=?4?8*}0Jn)QDFo&U#%&&B*d zcE}|I)&H?C?$p-lI=8@^nE7Y5r`f5fUfnu4ytOlXd$R zE!F>VJN|y*|Jc|cj`@G=W-^Zs{*T?dQH}p&x0U_(@PBN~&x8MSH~b$P^8?`j+ztQ7 z#`VMhxf}kEjq_vv9~<-h;Q!e0b?|@eR?V8K|6}9*3I31WrbA2he{4KnnE&T)%>QF| zZ{5s!eb_4R8@v3~`(ge9{2v>?SHSHpa9j_`kM%twU(V`E++{2v?l5B`tcr9or$ zf9z5H2RSQ-jPqW1*iZf4fFV89|F!?2y?Vf=tsLj2my5i2cWbZSuCo9=M|cJl7J z`_lqzXzlKO3%xu)8vc(hss4|R+ZQ?~->$zytJdoOxE=Em;s4mpWq=|4A8$`n@qqAu zZ2CW*-jVI_e{9^I^Vg>PH2fd$zf-Tq|FPT4`b+6ArP}uB2#>5MlI9KH)j_>q zQ~V!0dPp;8<;5x15tlS{_VrD+?$@lIb8c{wbyvAP149z69pUZc!V_v+{3GW7@%G^U zVg4Vx(M1i^|FIppgP8xvt}lNN@PBNle>3%e><*s3>i^ht<}XnH$G-jUjn3MH(e`+G z?_BR}%^GE0eaAZIsgelmdpE9eUYQhbz2&a!)&KGG?zrm)=a)qzZ2P7yH#;p?4!7R9 z^)9E+x-jcUcWzbx$MZk)$S(DN?1QrYGyEU>wY_`P|FPfL|Frr)_Q`_>)c>(RK6*s` zAN$MWud4rJe<$k)!~d~=egAFsf9&5sd{_M+Uti}x{aF1U``53&Q2)pN?ev%G|9Jj? z&U`1YfZESH|NK(p|7`p3zxZtb>yJNt`s|rA&TB*7tNv}x3+nyee)@i$|HsZBQRDv( zy!^cSzmQZv^?&TN$$>imkB$9#clS6^jWu=Q{pkPL^ndI;`Mm`G&sz4!!~d}hWPd&8 z|FP3#eGbh3b2t1S8~f+s|6uyy|IqM%Y^;BSeMRgN@gMkacB*(O_&;7=vUsWqOAcG( z_aw~!v->NJ`G0KeUxxo<h#(8?7;q5B~3~kQdbl;_-n0W5-V&;S8y|(;D;0;Q#ub ze^EUx8vc)s^-tmd*eT-MF#nI2hu?GH|9Jaw{qTQsjJ^6l_(1qSc9Q&lvg6+Ct7RX& zdOzGh_&;~U|FN-NG5jApymF}eKX#xT&yDqe*+JzY>i^h@B{lQ^c>VE3fx7Sl-4 z`y~_yssCfg%JJFq`&;#kM-Qw2^DppM|HmF$G*tZ`J9XS3^?&Sfvqw2Mzc*K=zHCpqmdO>dg1?gd2w?`ssCdq&i6Qj z#zx!YlO?||rZ|z+e16dWizBSzwc!7_9lt;J{A8HD-tc;a|KszIzeo5#Yne|8|Hn>} z*E{?lUq4au`v?3V8}A>-R`#ooKkGH`2mi;$`djdSO@qAV|K2**t@`Cz)$0A=|K5MM zb9KFw2h{iB?{n{jj@EcTJCfhN`ne7V)c4``_W87pHSRzBAGgDY!vC>zWIkSzU(@Q} z7w=c!S19xDc5l7NxqE& zWWCuRt@E#{ng7S_Sic$mkDV{`>fry_m{$k?$IiVXMg1Q;e@U9o|6@;BlB)i1PvtY} z|H>C8s{dnWUlH#lJo@~B1zVq1?}vu}V`qq`ga2dW{-lq5$~sT{-yf5n@M-uzo<3O~ zPt5;wH~b$P^8?}k+ztQ7hKC#e=Pd^wZv1q0z!UdGCC`m?J{fwWb*A{j8_L&M=Uoxw zjJ)X@YpkdI`Qhb0-Sg{3*6^MSQfFIZ-r;MHR$1fkwSW6EYxQ^YbFAV0-h3y?8lHDZ zWVAKri>}-<+#2&m;s1F5;3wh#+ztQ7#`^*M-&>x0)c@i6f&XLY%kz)t7{NELqY*qgk zB;U7IR88B@4wU2LKHrtJKlb2O^?;a95C69@^j`IVZJRY$|2IXv;L3xmqwsyzbN$Qv zs-y2yZ-s{c>-gk->i^*5;Qu~N+ot{x-^cO4@I%|wdtn|R{9nV8?dtz(`g&`eAO7#P zpSIh2zwm$T4ow@X|6_Ch9~+m4`G1#8xnKPs8vf7S@PF=x|2tQ2hx$L9enF*obke*X z>iy90f9{6=V`F~;{GYqw|Jd+=@PBN0z}r4;Z;g3?@PE91zm~1k|G69f&)x8UZ2CXm zANoHw{hzzx|Jax>2>-{%{K5CCrdq=r`icMJb2t1S8-5S|&)x8Ue7;+?Z|>~d zcY`(dpG?2%rbxa%;Pv4D`1-+oKlneszPSD`8~a=OJ+>v1uTT0vci+--XCzz6xE&qrcP^6e54m$P)c>&)Cdt2NGXIZ_dF1ea zZ1}&=57+bX{WL<>`)xhAq4g*^o(2Aor;igq1pmi|2ZaA~H`f1U!w16uvEd`&|9Jc1 zyWs!W*be{4*7aS*|FN;YFZ`do;s4n1g7AOthW~Rn{2v?M5dM#idFJqc?0ES+0sqIw z?Subw_r4yX*6=s*fBg40V@9lV>V}cl`3q8=rGG?NXI>_s2gLu`=L7MK@PF=x|6_Ch zpS$7z*jeJu;Q!nW|HsDhQSg6k%)f{KW5fH!bkDWM=Uwlc-iNP*|8uu|{-!2hwae*^xHmzOl9#{aRC#|Nta z)c>*L#B*W(pS$l~wA;h)L+Rq_9@_h)Ps9Ildq$N!p5p)5nR5Is{2v>CU+{nIZ1LXk ze{8JR3;)N?mw9{r<{Yrjtr+NpJzi~HG-;^%Ki=Lf@ql6z?e=HOdcHE7&^rHL|HsEC zPdr+^1uxk91AN+sy+?ey&+jii_uoh8}nn~|JWI_K05p# zJF#St`agC?aewuH?EK0h>i^jApP2v0&KX}b|BqcTAwvBh8;>{qADjNq-SB^G_)X0J zb2t1S8|NQUdDC&l2W-D{MP*dCse{z})%78m z-vs~1?PdV?H4K9~`ez5vKcsI=dV`DxH{2v?M1OAVV z>&N^*cEpHK^?&Zh{698)9Q+>}9ufYJw+HLz!vDD&^Z$7Igoqmd$Hx3P_&=ULQGWl2 z|6?c1@iXv$Y|KxD|6^nQN%%kZ$gp7be{9Szg#Tmbj+XshGnPbo69=mI%NZ4={*RsP ziFR^NFNvBkaDexv`K_W;qQ*GG{=U*0ex|+ORX+Wj-!g0bKL7P*--iF=<-?!B|FPlE z;Q!p6{BUh&#YC(B0Pc1*d(wr7byga6~@ zp(ic7*0vXk_k;iA?Lou;u`$1_LBH#*v7R*M|MBwjMh{p2$J0-e^&Bz(k6j|`QNsVR z=U!T+{*Qg_^vUY~*jJ2``B=ZKwbN&$hO7VM_UOpL>i^hf;#=YW*yS?6DJyuLJwNb# z(ffTH{*R|Gko9&Wj`}wIpL@G=`bN7v%-?f;lRSJ&g!?YdsDZvQWT_rH8yU5{7S>;12;>;39>-OI0g zdocgh{rKVi-Q9IhpDO;^y&eDlxf`C{-SFH0S7U#ndwW+|Ps82qTFL>-uHVDqVcd=N zG2Q)N^8wq+4o}zlM`fn_^qi7X^?&~v^`-j1^$QoN|6^Y}|8n(z?B%m(s{dnSJ|O1* zv1b_5hkyT*f3NUi^i-j`@FY-}SBfzrZdXowT45@9U?&*Y$i; zdh~V{FDUgM^*gKHuOf7~^X)Tb-osfx>ioU{@x(I!!#XT6&RNjEwlROTy12x)C(H2? zxc!AI&a3~62oF^M$BvI1rT%Zu1CNE$REKdcbD#d9Y+fp|vxhpU(elpZA-3z~F8@)&H>vweO_< zkKI8$6a3%15B;wG&(F`#Ir7H_?~f1otM~J3-Q0oyV`Kk)&#!Ov&RaWJy;}Q=8alI! zYr8{}i=4wRuea^kfA1IR+mjwyXWMakPxbWeCO6$syZvAP$Lq)6JNzHJo?JitAG?8E zKl~pX*AM^aZumboE)V|C-M4kS-mV|_@2j=fS$AwI9`WyMty{Kh=B%Do+w_0Dyl%3d z4g4SbVp;Fzs%KZ(`LX^D{2w1r?5~FZW4CDARQ(_OqUH^B{vW%E%tM9$b2t1SoBoeY z|Hp18^HVYZkL`C+6Q@y=<#u~9U!iK@GV4AqnyUY6JD{EVzt9%V)&H@B#Ye*bvAc-} z9e5_+x}RSM^?w6@Yp0%YK*uiX|JWhD`#EJ}^1SSUgZrxgV-J$~WwQrl+vQfOUR)G*!q$(Xj@v=P5WHEh+~`A^$4>tXVH&VxNtt%r*DYq}xLt{?wC z-ElC@8})K~^^ox+L)HJWN2jN&|C{xgpZdStsw(w=?8#FmssCe7s+yqwkDXglp#F~? zl@g==j~$VdqyCSbJYj-!OLV-Ky)Zmk{U2{n)qs)e|JY9V-s=CX8#Pt`XWgr%`agEB z*kJX4?B!Fd)c>&$Kd?jnAD@ps+wWKZ$G&mda`k`gdDDy4|FPpn4R$`AHPRm6eklR! z|G2&Dn11U2*aJocssCfQ?|ZTOKi-}$J>>T&ng7SGFCQP^|Jaxhx$Mah>yGv7ssH2l z9|xSa|Cc>NyzS?whuH0p_s!fs z*Y{svCko%=s^?Ude0?>~xXC%->h zSdkqqA2>Li-^10CXzvu3FHZ;HI-?i+S(1n{)-T&$QSU(W|r(R^g zFUS9>7udWAjuol>c)Q(JT|bV;He8--Vgt$E-)X3|5F#*`lt9m-QV~t{GXcnl=wgOT;>Ux|5KOR_ha}!J$|N` zKfwQ~dA#BO>^r64|CTN5TQ~8`!|wg~{_>kyz3QfnKkVMG*c$(*E-@d7|2yHzN8JDM ze8m678~?ZAwL|Xzcz)ym)YY~>@PBI7m;Lv?qv~$UKIGmn&mJ%MKXsAKd&K{#3v7Kh z{NL@T9juF@>ocnC-y7!tsY`6V@A2n;clf7IKJ4Bv^F;eSzWG0O?p9l0#r&VT#O^QV z|EY^MPIdpMUbJbl`#<%{otf_c)c7{$|EX(EDUANsa2w`2a`E9(!1F5i>y{!gc8z99ZjU19U{ z@PBHaU--Xxt!TV$U z-@gXl;Qp_lz5jjr=SM!WaO{ol{l?n7zN32l>d@bBy3xJgX!CgZKehbdW2rYK`M;{W zZ*u>q^?wJNnn-`HA|x^M0+!TaI=)Lb6^PwmGa zhF+ao`tdF9{pi!ay({&Dnp@rb9ci}*{}*rkpSnd0JKkXaPtE7;=9|7sec&Ir)-9iQ zeg=QP)8j+_PmiC@?OH{b-FQWsn(eIrtH&GH5C8YH z&AY^>vVUx?-!wgb*+2L{J-*ZJ_(bJ3KTXr)e}?(TsW1L4ZDq=J?)@VB{cf|Od(*DI z`dXj&m$GEJ&;L`OV86%id*#8feOX1Z%@h4|nx5aqi|zM4=Ku71U9>1Q!vCrBmrRTP zlJ#*oJ&pg<-xt{Wz0Chp=P#S${!cCcrrv|J3GV;YX~)}oedhmkdfw0C|Kg4R z3w^wK81sMX{IwI^|EXuMtDpa;+e733)CKl_VEmii!r#;O`WG5+vG2Z~q45}Z_v{^- zfB*k@M&Ho6_{!h){plo z%?{1|-Syi!p_vbNcvWHOdG`5W`R|KEGd~gkr}r=OY<}SC^D07D*!v&+pWgp4{|^7B z_fN&-~^A`S3&F4@2pPJ8`tpBUdx6f;=|EuQw@PF~f z|EW1Xg8$S0$z5CT|J3q-YWY7k^Ud&o@y7qDncs*1Q_r>e_{{%PFWflG{hxaNi8I~* zsX5-l{6F<<+n@M9HJ@LZ|EFeu;r~M0@fYU*shLlS|5NjOiW>8O>f+7Q-T$d;?fo|X zFW&e+HC_<^7jOKZn)%-NKXr-yo(KP@{lCmSEB;Sivo14Qx8SGY^gN#NfBJiVpTzt> zb?MTv?*H`pr*P3o_ka4lQ((Wh!~dyyzO(+XI%~x=_kZ!m|LOD5^pzRz|I|6FG9&z- z8t;eyQ{w^q96pe)&r`hqeDSY`LYFL`7(G7uU}*f`C0h<9_44~430=8ly!$_$KW$bp zTpsKH;{SC0Y5bp>({JAJWKutU&r_i*R!nsNr~OxHeh&Yq=JOx^PtCm9>ARi_U1jqM z@qfBMSPvNgr_-01zr+8jxqfr*e<56cp?SrtzxqvR&i|7MFNNmy6#u8cpJ5*K#}B+5 zw$HMEA7B6b??U6{$4q=BG?$0})87}@j&}d2#@8|bPhGKWn)|SZzCq$25_C@HqHZSnv*S-v0Y95gJf8lsX z`AGMF>U=x>+AIGNwihj!7!7>+n{*vdnYLh(`#&Aeolri;=l`i$9~l3qE-o7twS4bC zp;L<|Mo&%tPdNXPS%Ymo`6xq|k57yHfr8BBc~6bk1I|jHnsj>n3jXipq9N`B@qEnx zQ?s4E4e1DApQ{!Rqf9koD?fsPbKQ;5K zSpQe8^?%j)7W|(YAA|qX^Cf#S_!J01o9r_w-{ytYmha4n#twGxSDuyS{!d+M-iY~sYW6q&@AQs?-2d_S z_&;?`X14o3b#-cbg#S}>`|yA9#{cR3@k01NH69TEr{?nUe`zt!HF-1tA;9~INn-T%dVOz!z%dv#WJ)aRw-Zolw?u$}pM_&@zUjsJ`H z>)$8$3qQIjY_H0m86`Sh9D3gL+~{Z5HZ=40t{Hks*iPgBw11cfi2qZ||EZbZi2u{$ zWuBcL|EFdi;H{gl2#pWK|LOTzWj?QZe?#L_@PFDq&z>)@+|$s!p5Xtqo!1ZipPJVX z{GTo#FUtHsU0<5@e?!~(#a~|=dpG89#t^?V>eDxG za{s5^wPCIMKlO&?i=zjptw^Z1SC>XTb}kQnLh&s3f4!f4*L~o!l6?1n>Jt`JMuW1J zCDbcw%cGy{SsHrHit1=&-ICComM@C#{;oFk+L|i&fBO67rG@VQ)MfVk-*>n+vFerg z-23tV0sp6-oioGzpSmD7Jz8`5;>33?K5&0mG&?gI^YWt5#d%rL-`X|w;_8y#hDEF2s1BFkrgz6^-*yW)M**^eS!HuH9imjr=FTJ(f!}MAAM0j|8K$=_kU{Ue=`5?tiONh{x3ggn)|;# z1HW?rH#=*x`@aXv{_g&7qP>4%{+~KEC(Hexnt%WCe`=nu#kp0Xncs~6D>(gY_kdk( z{aM!kedoS^xc@t*o%zWpFH7t=W>lhiMc2&kZ8}By!}cfM{%}O%jiN4@{C>OjMVBP< z4-HQon%y~*#Y|idYmvctVfIgQ_KIUJ0IEH{hylWEB;T-@pb&4 zn%~3Y|I{3x$N#CB|2MyBLo@#k|EKHM<;Yg<|I}Suws!xgW*#B_PtD)s|3cgK!~ew_ z|EJ66^!PtD$EWds>W-al9-{d_b(e1Keg2=$kNJxDKlO3lJG%eV>4$e}@BU9c!q!j5 z|Eckp%>Prf|5*Q5-OT1S;Q!S4KK!3r{!h*K70mxrbNldr@xFUZLo*)`|EKFepl!$K zq8Ims9@ep4RDSR7(1Y6@?f!4yxDM_EkLl3O{hzu|x8vOZr8lehf5-Le=l)OKt9O6* zf9gJc`ndm7j~Fq+{h!Wn`j8>+|I|}@^>Y8G?%(q`_kX`DZ14V$$2Q(jrPrZKK3GV;YYuBuE z|EFHR^hEc6>ZMi7-T$c<&OgchpL%KS4)=fRMO8ba=W=I+%de^25j82w30*dSmHR(k z|4He#KAO${Q@1joeD2iD(7h_FqA8~gOYC{4X(I3Fw=!zh?2Mkid1&Zse|pIMpZ3qe zyYF`Yr@r*;v)%ux*RDI>{hzv|w8;IRy11;|{hxYvL81FU_0*hl_kZefsRi!;bp6|p zpX&Zk9rYdJ{!iVy)zR+%)XkbUcmJnm9wh!R-uOQ?>s90b)W!$h|LOYh>jeCty0!UH z*8f$ro%Mg?9e=+PF~BkQ`-F%q6mRmsb-U!#_Zrp5{U2-Gvc7M1$r$&4>O~bP?*A}w z_&?Tv!2hZF{VD!Wt@(fI%H{TXx%G>6x70o6zK`Rl&7XWBbb+nEf&bI?`6pz$|BE;N zPtAHm_`i7L|J3}xeq8l0>fVbUbN|Ed%lmbCIyCeDSW80Nng7RcHP!j{{XfTwbbfPA zoD%Wh>Vv3Nsa&0?Zvm@|J3+A{GXcR|MAH##{ca-^Wo6)f4V=I_lN(B zH~vq}<>UY2z3Vskh35N#yU)BgbpD3S2>&nm^|HuCoUh$OsK)!#&|EY6r zJyiUkn)Si(f9iajKY{;KbN}G~bbDs-{iMzRyZ)0p_kZc@>(~EPXK%Fki{}4qjUM-Z zeBZ+SKQ-US;Q!Rz9{iu0+l&8GvmO7Z&awF~PxLu8G{?tT|5ulvTQkzv|5ayI4|D&w z=8S}Uz-eUzqUF)ab?SbVz1;r|o&KnM!11f<*Z);BAJM+wt5X-7*TMg(HUCdtur1ry z|JCyspNId8H~vqJw`2aF8jpwnQ_KIw8~+z?{9nBBe`@(Zb>Y@5U;kHKVSb4De`-7; z^Z)ev!u7-dskwgmKb^jCYo_}@b^hl1^?%i@ABz9e{=w_v|J2Ms#Q*93D7JZJ_`lHR zA@P4|JQDs-_bby1M-2bWPtR3(EPmd?oug3qy`^Y!?*V%VW?){jr z(ev>>b+>NN9q_`i7L|9anW(EVTTy7BJ+)J2=8 zMYnv@rfzPlgYNy9cZmN}ZP{cE&k7D_PPJ7HBW~BQwf6%=jjsH`ZTI2uXZT}s* z`sA6>=$GyZJdZ}3-T$d`chvhob(wia{GVF$|J2O;!~d!C zZT)flpPKog_&;^IZO8wqndgW9i}zX2_6W`T(r=DzpVX5tY!MnCi2t+i+};1-1DXG) zF4|e){!d-HdtTD}#r?ZaO6rSuZb<51R?PMFfA`*coqN9@_w3>RPo2`KX*7P|&_~Qv zxu+W6A#(p`YplBe>)5KP`@fejzQO%p=cA6Wd4E4Tblvb9-TQSjAISVaHS_uS-}IE5 z-1~8SfcbyPeO6MJ4|zVR@qcCn+ymn4SpQdzufzZSHT`Dye{9G9#T)+@?*r!l?*0AE z?*BMF{_m_=x77PTJ05}mi#PsH&F5?UU%c^u6>r>9@Bi%Y@qcRO2jc(K9RI-o>F@D? z_&+rs5dWt>`skzW`i%^Yr`!FriJ|%ZA^uOdr&s%& z;s4@||I_~F@|pjq#{1#_)NIH9#T);p`)rpUkFUse|EJf-IkgjPJ-D~h)J4lD+xp}0g=Rifzuh0D z>Ggr$n*Vv|oE2juTU#Wldw=jvL)-kdO$YuR8ZXECzq-6k^I^>Y)A{Gv`$v0y3C-t= zCI4(08ZUOye`-E&+C0_J%x4-=H7GRm2g@HD5*lB{{6GDBN#p<2oFD!#-uOSY{9nB7{Z!bF zpTz&^-)kEGr^dJ7|J1CXjQ>*?n=iuusY}e0;Q!Qo{f{VoyBwKgy#J|{!gdR zxB1%mKQ*79+UCp+&3wBD?kR6*dp~)>_f_e7e>2zm_`(J0dVj?Hwf2wIgl2!^|MY%~ z^^{k?v@+dhiuvz7X#AhvZ&q19z2bzVe)ppdq49wDKfRx=u+OLXKQ)(!|5MBVspp#q z#Q&-JJY9Om-f;drzTf)ADWUnizOnUbq4|AXlY-MjT3V!vE>|@ch94X@Ahn|5M`wng17W=Kra={`kLm1;q8~>+fK0p3X&Ep0Cr)Iqd{9nA8 z|EK2n9QZ%=JbS-x|5k+N^A-M2+so|zJN{2S-`>CD|Kg4R)Bay%zc2kuk2}KlYFjTC z|EJUQ`zHLKn%_6!|I|e`|E}PQpN0LEZ~lz+fAx81+OkpZ|J3O#$GZPh%m1mfSEfez zKRsV&uS|3Qr=GLg=1rLYQ{(>%_B@!b&r^kV{0;x7E-}xB|5KOR>ka--U1k0b|EI28 zo)X!AhsNib{R@{@ZrkyHy8O9I>*xRJ`qTJ7HRq52Q_nNshyPRK6Pf>~$0M%~_&;@} zZO8wqD{Out{!fj+{B7N@lKPJEzYgcmdbQtfdOkGs^zeVW{6cH|pE}=;cjEulQ$AYTDE?2|=bIPB z|Ec+VTYD{Be|+P613wO3v2c8}ZRICP{q%~@!t;mufaO2=JgM=2dVZEwkBXM`{wk@* zF8zDxiYlA$X8updL#nFByZ_Vil%mRU?*DYWHLrA}`#&}F1o3}r)(>uJ{!g7}^V0Eu zI{&nsA@2XwrK!n&qGVdKcbG9P*-JF;nN#c6|9w4Wu=~GR=Ev}VYWx@ePtE$4_&+ti z1pgOr{NKr?L)`!2^Uf|lK5WOA4LN>I=u%ss>gm(ghAy)8sg_@}E;Q=}nXhC1 zpL)*JH1~h%yeYOmg!w;RpK_aTi2qZU+4aT$>GaH_!vASIjsH^@Pqg{K=Ks`Xc75@G zYP`{aw%anYdkk{V$N9fKaC>Nc-3@6wLgN$he>y$;kNJP`#{a1~J^t^O?*`P*|FiSM z|Ea6({$u{18t;hzQ{!Xse`+od{}(@h{GXcZi~mzI9}@qk#y<|3a(d{}-1_-{+Dr>-)eI`Q&-;rjCU!~f~})A&DinR$pKru-;0KJcq28k+fT z?-ZUDw$s1;W327|dt%wyVLS61@B6Hwi&Cbz|I_uGJH_S!nE%t|GmjDfr!KPjh4?@9 zqFHwQ&itPmABX=_Gf$8CfAPlushP)z|BE;NPc8o!Z~ULS)YiYn|HT{sr^fr?|I`a+ z=DGh<&!08N{hzvG`poFO`!5Nn=koD?+CTU}=Krbjp7&N=med!$)6n?HjVE3nw$q!N zUKyTW_(InI)$@({fSr0?6}sG-^?$XU^`P;8dVc3++w;f#U%c^uI{kd}F8DuPUmE|X zo|~TR_lj-((fIeBc7^*^`s~VdK|#JaYW> zRrY!j@BiiB8qX7K-2cnp6;DaNzKy%F_p5BQfB)D1YJ7bfcjNn`aW_8y#@(z<^7_61 ztD78^JTDM$6yM)RTg5xFc~Y(3y%>8lg!1sgZH|5Gp8 zyv6;WdhsBm^PCmFSod5C_3!~S+SsJ=#QHA@zL0Rv( z4_sbT>Hbf>ddYnEf9lH0V)uXQsZ+YA}5-T$4j`#tx81$}zD|5NwwdyM-(b^n3A-2bUN4(t~l@t^q# zbz~munW?e1-zzi!PupAf>JgoMM|I-(eee6czmx%eqS38t6187^?A|ZmeDK2JMTtKR z`mBDwU;3oz<}+$SkItCv{!iN{PfdwlY*CZgRQ9=hK0IBwX$wOS96vUyIblKQ!71b2 z|HV%~>6h~pRSUjw@5lPd_&@ce%&F1r;suF)2ma>Xk7oX#di?ZM_kZe1_U}9M|I}@! zPj&yNj{0_Y|EC^xY`5sZw#sn&pCOTX>tlsi9Q1^d$GyLBpB}0<@U%Z+B7jNeOsac-~|EKQQ zqKW%IHS_!Me`@CU;s4Yv&6nZ-)E({n3H+a~-{>C4x&Ko$->|6SoN#)6KY#r%&JNA- z^)DwkG_M~ycbpZrcWd1;!vE>=IG&9EQ{(yYf9iHUy1D;TcR03(`#)WuK0S_c|EKPE zY)|)pI{nn{-Q54F$F*K~#%fO@BMeh`C3_YrIclUpPs_W?fFEWpa{|h~G zq|g6Tw;ed#{h#{CUIX0!sR#BM?fy?aX82V1f9kPw7P$XYPno;S{hvCkY`ObCb;as> z|EFHDZhJJTVtTlKYd7tQPFR>7di&-b(OnCNCys7e@BMb~*yH|By?N^%_kZdiUvPQ! z??;9v&VI6K;+wf|XPkfK4biXK4^FJ8X_BaY_l=D6F2621ZT`T-WA{git#z+wT(oyz zRCLOK(5G+Q79D$A|InxG*c-j~tA3$RJNZ=ie{(bl?uEhH2sIdpM&9UuG%ooNx0vN`& z4;nYr{U2-E;{Rrr4R`;iE?PLj{U0;$@PDNXZJvYqKXuun$?pHu9N%L8U%c^um^s$t z<@*l&pSr+~hwr-Y*L8n5lyI-d_c`m=|0*=c$MJtUebEV%-T$de%|GG))XX2i|LOc_ z{GXcR%lJPv+wp&)?f5eOPv^(+ZH^tOm)Pm~Z*{GCt(M~wp)1U<9sKBUXpYC@|Fl0i zKm1?3@qcQ*FT?-EoB4mbKNi{d0r+RtG)XW>e|EXEOiur%)c{V=)|EFgE z;Q!){|5NjQ2>wsadY;3 z|J2O)!~dyg+4^U%zjS$M=BMEQPR)PPJz%DN--iEF&$7o0{!cyI9#41Od~x`DZqIZ5 zE)4sBrafO~_dmDpqR$?2--mDd=UZoo&f76Ps_b!Aovqp9->1zuX=XI@)iXn?&*X^4Pd&%H+ygmllDgaBRiT;BwJl{uXy$YM@vfzzS$}itpxV&P-@5ABn$U~3 z&5pk7x*&AT)>%=_`SU{K^%6%`hQ{;t*;^KRfqB1E{#laLSEUt)*B?&5>%M}d#{cQ{ ziSn_Q_KJ9{wT8T_`lHh{TcpGU43ei`#;^kvv(J} z|5H!jmgoLYjW=ZepPKcmng6H956@rxpL({v{^S4bJ16&ld_Rr<>vHg*`#&20r^ZL) z|ML1DbpJQUw&VZQsrL9?_gt5{U#)o9y&umP{GWQR%_Cy|pL(8oJ^Wvj-#k=5@6UWV z{!fhu{LznE)}7MnA@_d#`+@&cvtHiueVf%atvukqk9l;D-4}%}JSo%tpSCj(mHB__ zVmp8QpPKn4_&;^Itxt{rQ}g&`{a{+Gj(9(~ZgU%vTF{GS>RmNDq%!v~u^ z=-v;%IrR4D4}ZG$0r!1Xw*BQlJ`=iZ*G%_++Fri9-v6l!POkTV@ir?G{(kw+S?>R| zeVKW`*P7iGw&UIKf7)JY>j&fi)U3CQ|BE;NPtANn{9nBBf9euj-x&X=F5g@1^Z(TI zZT=ztPhGXMDBAw+w!{QkPiw%25^{_pdpCnR;>N0*0Y-sk3#3qsG?lo369Wobj3 zzdf$y?9e4U>iu81JexOz|BE;NPmS-x|EUY@{=)yMS#KHtr!KMk1OKNkJb8|J#%~^p z_w#rEHFSZk_q=P%Z$sy8o{{u^@XEbglKQP*+QUBfe(}*mk0kZRb?cM5vMe=vz4Nd~ z?mO*z_kE*=ce43@EkhsKtC{;hZI9YV?*H~2bA$W8@%H(D+2<_}U3Sh5?zw3Gx1`^V z?*H1iVjf(pX=;9tWks4qw4L7r;{QfIe53onCavrJU%c^uGl$(&@Bi%cF#a#z z_`i7L|2jQ(llwn@ABX=NKJI4sfA~K9U%c^u@y7qf8~^u@U*7EgkMqO-srh`4|5I~3 zbLH`!lN$f0^OOHm%m1l4zJdQ!Gw%-nr`yxFeJA&S>RxTy`}{xMe%9y3|Ec+V{GXcN zAL9Sio!ZvV|I_~F`r!ZKjsH`(w)I@_f9kg85%GVzKe;^oU%c^udc0`KxYm7Z8++{G|6Xc(t^2>|=w{KW{eGJE z@P*g-`q))=JeK)?*Y~-`{om5dFZcC-)hFI^i?9EyzT}LPef?kcqT+i0r`KnE$c{JP zOw;o>$Gp5fe?!k&Ve8kM|I>CF|EK2tDgIB*`!)QZn%`I8|I~T*?@$R?*31WcVF1MDs0EoA6Pd(UGIkqY`z=*FT8)U^M7!B zZD`j2&6~A6UGLW_S4}h@vNm1s7c1=Z6#h@|KWY4*8Xwer!%3m>fCInY5}NzNK3|09 z_l5TPBlP06S^PdJsque0f7S!W|EZaWkN;ES_wave9&h+RHJ%p#r{?j5|5MBV#rwr8 z&JNpoeBl4IoyPyE{r7?9|J3|G5dWv<^E&=d&F>HAJ#b;zzm;pJMIU^9QRph$KlnfG ze~usE|I|D_@PBIN{|){Ave2x@a4`Lf&>T;}|LO8+{GVF>Pc8qamj8=4{x9D6KXty{ z9{iuW(AF=<|EY`Y_iOk+b(wiR{GWQR&9}$@>GKhO8vm#5Gwl5Ee`@>`{x9Bjm3M{P zUug6Dp8e>qbbY>I-WvW-jn8HNU%Z+Br=Dh>>+Grbrt9-OjsH_;uSj?Q7jOKZnt6Zt zKYgB(|5M{f@qcQ5|B3%oSFKHV|EDgs%g6tz<^ObfH2yE%m7^aEjXztp{_)WAf4aT$ ze`=oJ-M)M}><^ybE64pZ^n%r?(L)=b2|aJcl&IBx&xU6GTl}9MudFYO{|o1DjsH_~ zd=vkto?AW8{hzw1qObcu^^^r;-2bW5%oF1O)P?2+@qg+PJN|+HQ!}4;@0LF#^@|Vw zF*M$>?>}A*&G9k(pZ>mfUAFr_^?dW8_&+tC6aS~id*c7p{5~817jOKZn)QP5f9h&` zJpE(JUqhc@jsMg3HFkRZpPKoAAN=cs(0EAvpYD%}#VPLp)T|fW@+Y5$?fAbdKKv}H zZB|NnzRg{b;{H$1*W!8O?0C`N!}GVw{9kn2*Gawe^?#=8cu8T!*yyBVzD?Kh+x)W8 z(G!cm3(fq$j< z=OFikg|?pJ#}ikFW_}g^PurPah5u8tz9arm&FS%f>WuLz?*INhad7=S!IVkv|I{-k zOp4M!JTaVpW{Ry3Vg65l&-#w|KQ+D!|EIsl@8JKmoyPyE<^R+r<`eOMYP=!-Py2J$ zB%6O|{!fj6#Q&-Bh4?=;UI+iDX8mORpPK!J|9k4M{oVi3_&;@#t(T1di#PsHT{wQc z`#&}N1OKP>h5u8tJ}drDU1eSo|EHdxS?~WsXW4vd z^MCQi|EVi7bKL*w`c~TMS^rl(cV>?JKb^iTx8DD$7thXd|EHG!QVM&HoM;csh3R8bpNO47wc2v|Kg4RQ{xZu ze`?Mj|EK3S`}35?uMXR3{GU$0#O7Dw|8)5^Hjfbhr*6FdFa9p6W`9ft$4HkcDx&JUuut+`1aZ?n->}T_kwwu@h(VDzP_wa{ol4X_I8ce z8*c0a8~eKd<^QT1&8w|yH2<&h7^J+FJL2>J!$jbN{Daw|R~G zKlKS)*SY^w@3Ut9pL*NsdjF?hzjCqrKlO>Lm$?5MS@)LvzY`bL&;L^|Dam#Jr_RZr z?fy?aY}{z~f9k@N(eD4$tk;hJ+xqM~?*Djyg8x%bpESki|An@HFYtfr44Z$2{|h~C znESsrU%%`AugB3xxc^f}N4IqUr#`wzmx%d)>h8yMa{s4h{g8VnEJ#fF?yv6qTC}(0 zeJ9KheawKq(b@+WCOS{}(2gJfDuelc+oMH^7ngtR^Zl~Z>iys93qNuHHz|9f`#<&g z^l{NyFV!TP9RAe3-#GjC6aS|kZI4&{pBnFn|5Fc}TtEL$J8)xgo4S4;s#JZb@x$k3s-xm72-=lYwdd3N%nNJ!mTOT@V+dg_KdtK-zHc#-Z zzH38A&6-Dr(VEb$S{@a3e0_E3NfW2o{Fc1LBPVrA3~bRPvm$jy^!XXHL(j{Y70o(( zR%m{|aQ%;SL#K=z6%D^+T;kTNjz}zR|9-}_$yw2>_lym_bn)uw_n(eV^!;12#EuXC znz4QP@$UaFAKt|0{n5<-Q?FUE-u<8YwB7sM|Go0pChq@EKJ|3>f1OT?-2d%6_s8!4 zj(y-ib@;!tetf0-KlR=-E_DB=KIgRa-2bUhKY3qt@0WcO>g_vDcmKD#TYL9_+qR$P z{;&4k_U`}IZ9m=ppL+d{Gu;2Fx9mFI{hxaC$)~yhQ*Ya{)BT@%%Sqea|EX)&oap{f zUA1JT`#<&kh0EOk>H5tnD0Ba(o|{+f{!g7UBKiH$h{4IfFX`KJSkn8GP93@?b=#vm zBz4rMc~TEAn&AHLjN2b||2NBiFUk79>inAe^?#XhhyRBXUh5DS9NC}I_&<3pO6)?mP0tb zHNWjt*Vy&pSdW@{fZTT7evY5x|I~cnvgVdYlKQwsheG4+@PFE$_&5BY8n5u-!U!~bR7eaQVE>#eS;I=imv zR|nnuF>en4r)GUi{GYnWzR$z|skwjge`@Yu{GS>h*z_-_hR(Cw%ltoGKJ!WNf9g_O zzbhwmPiUUMHzrOFU1Hxq|8(-sy1mCg;y!TpYCHb;z_!o@_Wibfe^)mrI_y4>c`x?; zUTF4@eg79a&(`@RxF85yDRdCdRQ{w}cX_&+uC6El`g3il85!|GLw5Jsi9r{x9D6ztHyl#Q#0? z-b3#HSRW1lr=DmY5dXJ*#6#}?CfoO;_&;@?`GPrX+t=N-|G*FP{xYK9uWD1b{-jsH{geK`Jabe{*^|CQMNiT{f?^Zyz;$NgWt@qcReAO0`i zw*KScrDs3jzK_S3tq&QR#|QpT+l$PbUG&dC93Jq({qFr}{GXcjf$@LyrriI7|C{Ch zPhDyA;+X#z?-4ftPhGfcw$J}l7ukG4{GYno<_j|aPmMRk|EcHL^8x>-E;28O|5M}p z@PBIN1LFVG^LN$H|5Gp6%{;sd!uGN~v)%t`d->kHXm#^_hmYBPpZmUfdy1ousi%Z4 z-?TzmZB|J22H{WomR2+i~7skc%>;~nvT zy1w#%@y7qD@tXKQHR~(m|I~QT?eG5c5nVpr_tAGl^Z0r8%9lcC+3WL$&56)E_MDjX z{_yc%Je1TQKl@Bl|KgULllrlBc}acQ^gizYF5GmTd%yvG>iwVE4)?hKt7&z;`@eQa zG;{y=;P&g?|8+fz<9ShZYP%cU|8=$F1Nc96XFJ}2|5G#Hzr*{_Pb;|P2KRoQ?f1O+ zKQ+fInEw}V{NHU|ZcOrjYL0i{|Kg4R+w{{L-T&eJ@PE%8dsCACi#PsHebf=nqi)~7 zm3sL-H@Wwt@qcRO@#Fv0Tt5C!&GpCssrfzLqJhVS=6Gkt8v{dgyfpu+QK8$kY2*G+ z*9T9xwKgM7&F6RK|LOMiZrdTcc2aR@j;~z#PE}}*AML-ewxNIUf7)MoK<58xf3rRd z{!iV(9su}1HP;var{?+{{rOp;`F$n+Pxp6^&TW1DUp-!q>C!Ix^yy2};=Q5mm7)8z z>*)SZkH4bW+r3je2OemDM4jlakLsd+z&|5MN2Q1AcL{CkQ2Q{#8=f9eYR zy$}9RE&ms9{GXc7Z}>mmej5L$#?#~f)Ot_xfu_3hlpWd&^|EZb3i2qa1wRwQ} zKQ;Fc{x9D6KQ(?3{}*rkpIZJ;E&r#^v-Pj>e`-G8;QvC~{%8JQyzzgbfAD|t#{a3A z56}ER^&ESCOdfZB*gyE$Uv9b}beR)7}56=Pu*-PIra#pJlJl_&@F6+!glwRr7ypJU0GM&F=^Cf9edI z_lp11=W!bUr{?X{b^g5J?*G&U)g#>h zsi)P9cmEe}{GU3%W{mqkby02o`oC)Vzj)*S)V#jo|J2Mk#s8@n+rRhB|5Ml4?=A6v z>I(Cr_&;@-Js$9XYR&&sa>qSSJq63&ffWPXyyUFcIcDPW#%jKe|o*5hmQE7p>2KOEu;Pxo{uG!W8MGh_y_a< z@PF#^$}#r)(tm_5v_5;lztVO5HotsSbj9j#L+6%_jDGU7??TVA?f5^PzHsgs_kZdc zd4p}9?0>@f&&n7c)h&rKbosM0M@w+pPG49lP_8kPCsYdIQM@yHXZ05Fnz*U_kZfliRQ=5|EckQ_&@dZ3FF-Vsrf#? z>4EiOJAZ$}Z%zoEGk&7`Kb?O1xD@w)q3!(ee`+qT$E1@&r%sye{!iP}r`SB3r%wvE z2hVcbUp6N-{!gc8|FZtCn*EFa)Beda--iEFb9?ZAYWySqPtEni|EW1W{_n59>F55B z+mHWK%m1nIe)vB%`~L%*|EK2s@P9i0V)HKeKXr-u0{ovEzk~l%<2&(xYVLphpBmqT z|5LO7R{Z1iaQXPhic`-B&362st{?Lu@qcRk4*pNg`qKD6HC_q-7jOKZx;)L+Uoiit zuFjt6^Z(TNGW=h>@qcQ3*-bmn35_pf{-3tf%>PqY&z$M=|I`bAnE$7){$c)~TK+HI z_&@bx^IrHrb#3l+_kZdVe3z~N8*lty=$v~0r!JjQ@Bh^JJm&wYxjn4^tDbM`ZQ}pb z^K5_N|I~Ox{GXchTlZ{3^Y;tN_lNDw1I<*0#QJ>YB^KcJ7ao?=BCIpAx(NV}Eo- zQn%}TWoWMNXV*0}_t(8CSBK{#jsMg0lk0ch^sB?)bN%ptdc0OGibG=9k4^Ukg%`=kGP%-q_zY?gI0WN$2-Jn)Sisr=MrH=fCy;y8igt_}@3~#@>$S zZ~XL)w=>T)zP+&rY~1+r_~{#WQ<8JKz zI6f9XJ-#L0(Gg9Ox~Z)P8sC0I>tt^j4IdRX|7=xa<+#`DZoTTsj2?3eqgkUHdU4TQ z_kYh%e8YX<%8F|Df9is&D))ctxivNJ|J3Ui&2#^!-mr9`&;L`eSXtx#PrY%|@$Ub| zPkYn--rWf04oZ z-1xu$On=+`ACH%}`z%T9U-yptJ>DNM|4-Yejv49xPd#Q(fA@dter;R0|I^=hvE9%5 zziK=D>;6yO)#lOR|J0p3caEO_#?}Mg@UDBm_U+q8SC3klsNM2cU(a`Bx6V=S?wZ7+ zo8Ncumpx)=^y0gV6JLM(k^8>Mqs#*x+tB!a=KpE?c=L|T|BE;N@BD$Exc{4I>to~p z)RU%6aQ~+sWAiofe`@!Fmn=wpHS|;We)Jz+U643$?q}}(=r?;UObp!hxqH7MX({gi z;*I}Pj~F%7=l`i$zqkLF)rq=Wzwq^Z@oi`KYiQ>C^yY)?)i@D(kVLS<^7?X z9^E>6dwN6j`{x_(xFpeZ)L{309gb)kH9NMUS?>n_r|m7w@8SQ{9G}MjHSIRY{U440 zQ**o<|EI+Ep)QAf6jveq^<*XOjqoE5gWZgzzGKb>FG7WMv5-L|70|2F@p z?$oK1`@eWI|4-eutKC1g{;#@w_wLbaZ|n=*yL%6x|EK+VT-Rm*8f$rUUS6-r-a+fe1ZKMwsyZ=)k-S$ZLf9gK= z`px`5HQEXPr{?v8`G0!6A7}F)@qg;p<`40I>Zrp}?*G&SZN4o2Pt82QVXaRJ&HRK< z-`^OT*Q5J>u^}|~AO25&Kj64t?*G)xbHx9tnfHkQQ+Mgo#r>a}??3Q=>b`BeMnjrT zPLypr!k!NwWX#Q+6>T_fVxs)vX72Z@ODdz@(^5juFRhB6ubL3LDm~lge~b@(Y?J2h z|Md5fJ>Kzuq3!vK|NE>%z5i=v>pS1lrlDIzM?}A`7?C*p=S>oC?RY1niT(W%+lD7K z^Zy34s`r0UhaS=E9}P|nD2m(?-%z z^l$fprXw~{hxaGspq)=Q=hu;eD{Cq-KU@D{!hK@v~%76sWHaU? z_`ic=57)29YsVk)f9iP~v)%t4+WLt5KaLOM|I|xtzSPaN&xWqF?>ByT+%uv1{;9>Q zzX;8IzKQ#vPU;nQ;)UpQ}BQ4i8j9r|EIgnc1 z@qeEWIpqE?ccmSFHUAfH{NE#o57qlW`~D37r!F+_i2qabeKh`0&sQ4%r^Y|x|I}qR z4-fyR*8IPCnU{qy1Tue{H_AM@t$e`k{6F;ydpzR*)N{=bGXF2$_&;4gE+7A==JJ{Ur=Dvb5&su&{GYno z{2u;KU2dl@qg+}ThAT;ryjbcGU@%}`a@SI^}|m* zmekL_{8CbXc<)_FeZ%Tyc)dq%{O&sUduvA?$$Y*;>N$3J&HP?y#{JppLw9M<@wX__ z>8JhR|J0N0^9lY>J+$eO?*GrP^Z(+F z|BE;N@8wHxNb-Mco8RdE55LF!KQ%rO|EK2o2lM~b9ACiyO}X+$_ki+$YWY94{GXcj zf$@K8`9C%D0P%lnd|gh(q|kUk{GYB5$6N4!x_vbMFW&e+HOFh1|EK-Kyg%mu#T);p z{m=1Q{9nBBf1%CW;s4Z}AO0`i=Vtskba(r`U+R$;rRn}Zwrl&Su5^EBykN$)SB9Qo z^Zx$6@v5{x?77;#-^`xf-2bVg>64=i%Wh2j<55?+=j(ss@~GGDTSM>Mx;eV@wmU*! zfAy8_|8)AtF2B_MpZe-eC%XSrmux6^|EJgItlAmw|MdLk_Z|2@^(V9fv1`EhypKlNPmLq}cOF?6x{p^4vh4$b>f{Gav@jsH{g`2+tKZ~R}p z@qcROljHx?)$6j{|EbH(PcZ*aU0~~X;{VjSH6z{ssqs7bKQ;5~@qg-So1caMQ{!n0 zCr=8^`yc$D{{5!$e`*12n1vbAqV^CS>DjpB#SA=H$)to=h3)g49eSY~QXF*bzuUeF@ z_e1#2?|)Ytn$PodM=ej+`zbz8ub90$UGLw@ZQkN<@=r()?;mYGR$-%4EKL(=KJCQ)Xa~>|EW1Xf&Ys){!cx}p8xniU0&fyGon`?yDIb&n@`XB zzq;0Y)%~9uZ;Ss^uV0UEr^A?Zy`G4vn^PTuVHLqXzzj)*S)Rp#nhyRN= z{!h*PK>VM&)YeDF|EYQWGyhM``po!0H69TEr!H7L(fyyAd42dlb(wic=KraSZT=zt zPhC_~@Bh?u7mjoP7jOJuLywI{eD`TmAD_yKBVMLvwkD{&8YxzF!}D_ondoQ&T6o{|mRr<`3cj z)XYO%{`HoIws|_t|I>En)#3lt*;B{5|5HyHJH-8;x@hz;_kZfraU4 zxBqM7W8;@snwormjpq^muX%sfwjO-^{2H$x+}PVS?#A=?{#Q3%zxe;_?QiT2d3}rD z9$uf~JtsZc3pVzC|JQEp0Xd!)zdZa%yqh=jfsq}c#Q%MA@1NcO^%^?B{h#{SOq<8K zYgOWs2ma#zZ-~wJ`TUWUq4UZr-T!I(?70>0|I{ny7Pcyd1Z#VneMWH8VO!4`D`g_*v z#s8^!f5QB~c;o-#{i6B5$1nKU{U4Wy|6B0TC+`1-P8sL^@9(dF>i%z-t;fvzzv_PD zhWq?K^^m^DMu#4opE&=>&)xeSXU9A7e`@CY;s4Yezuh@+f8wdOgWU6Vwd0?Ee&*7o z&Y0TJ9G}Mj>GU-IFW&e+HOJ3SZgElKmTv~Q_oMND@y7qf8~+#YNw5AmvG1M!?)$jD z+wzke|EKNDx5EFayL9UA{!iV#L&s=Wmvh5*=EEh@%6ilw}o!iw3+)qJsyptMIV2?H9S7M9NR7W`72vOGY|Bnhc<_9-MK?F>57v= zcR9MF`@b5SZ+>WY=gjWyy14&SckFqL`#*K3KA4jlE)6=*ZTi#s4jR_uqASN57Rp(r7^1SH4JAK3Du|Dt0l7R``zKTVQqE8>_7p{Ma z%{%=5cYQ;z-?c9)9o#2e|Gm3Ui{9VSE3t8S(Z#_5e>cj?ETT|LC1vcmz{ZO()*A7`z}f9i_bVWsV~`gUQ%Cm${9(0 z<=)ey_aFUp-5oE~xv$!~zTW?R*tO36UuEGG_kZfb`J-*aAMdtshIbM$cyYu5i?*I6`e5aAm*L^hpkbA#*_I&~K|3aGw z#Q((`|EHG!Q{xBmf9gec{2BkJuCe3U_&>G$U%c^uYUW|!|8#wsM~44X^L-8ePtE#L z_&+tbmt#Zm=D*{8^=$`}`n)9%hvxk8f7*Zen6c*`2+j8+Z_RixwESPVKkV=Ee`@wO z{!h*I!~dySKL`J(X1yZ(pL&+fi^Kng$Hx!;Pp$cXYWyDlPmRaJ|HT{sr{?%Q{!foj zd>sBy&Hl&#sk3apAO26BW9v=rGykV%egXbZU9>*a{hu0tiT_jMEAfA7_7DC~&GB;l z-@>~Rb?<-slMMV3{!i`em74zxr?>ON|HT{sr)K>o{GYnm)?35>X@3--IMvtxRWmPd z`(@|Uy|MWr_j)DAr?~&?bNGP!zs2S~@PFz>Tl3uispqaqcmJp6_T&F_ete&U|5I~& z@qg;sHs25bcm1e`-5)al5&x$yKgquTGykW?L*f6_%=>Jbu_N@`UWU1jqNZT?4S=KtCHV0FWH9<29**0;X7HZ*>1--6>qv!3e8 zS5`Lkmh>pMbb08~&1uo#UoQ#G>08cPoYe0>zA$vLc^~|rF2Crc>F)p3xpw>Uf9gE* zUHCsWJ`4Y+#%B$?xiEB|tuNZTcYacTaK-G<_`N1uXNLVT$JQHt^Ka8bIz%$7yqYbz8v%a;%z?cu$eyheWm6FkG=C?XuKW%PuuZ( z_&;^!o_zCdcZS9XKC$n%&}F;w&AZ(gy29r7b^Gd?&{e0*i5?qvMd%tkzcsa&gvKv+ zx%~Xl%n!u>>H5?7KV6@)9dq3O#oO2a{o(ep|9t)5AG*>!tFQn2L-Y9e^?!e8)@Szh ze}8ECKb`+vdp_g;)T|$j|5Gz>5dRl%{GXcngO3gC5qkd48SekIoyPyEXW9LW|5N9k zJj4B;nt6lxKXtafzQ>Pujonz7)F=<%(aGOzE@k9S??es5wM=2b_Ln$K&teVV$d&1W|s7P@8g zcJBYQoo4=@n$M5;KV3e@H}HRIw&VZejsH`(KC)Sa|4Z3>z5BmbEt>lLzc!y;@BWX^ zKls0R#slL2 zbba`IkN?x{qw#-gydVBA-uOT5A5M?|i#PsH`=9OjKQ;3J@qeMs2jc(K91p_(soQjH z9pV4tjsJV>gKOQFvi<`8Pu=?H=I;O0%{w)ZezNY0H2c50rR{%|F*s##)NJ^*X`7o| z>E3U4S(*Dk^~PPh-2bWXKJ6^`f9kr6E_eT@zU9)h-2bUJE~#+;r)GUddwovR>r;vO zBj*39dH;+5Q?p(!{!h*O57z%xm)h?So-h3@P0!~An`cG?dVUqU!u*cC9)!l{{pM%i zCw0fvCh7Y7Y@4t3_PA#0H=gnHx}0;a&X{iA?}AI4hvxSk)Bbs6Xnue3UUlox_@9dp zA04{D{GWN{aQ^aty8Z=gGu{8G`TfnJrQOowZT>l_?;qPUbe?@a!T;&sKi)6k|J1x+ z!2hZJ^H0^F(7eCJ|7rUSn>UC5Q_r@~Pt5;Q^Y{2aHJ_jGe`^1Ijrl)yxqUvw|Ecj| zTW^>Wn$J%+v`!5@&E6m3|Mc&Bx_LbOpPJvJ;s4@||I_*Nc)|av`8-Su=&0CKXv(*>E>ChLi76+{GYDhT>E{+r9ZC;z1ZdlruD2%>YJx8 zOV|6S`F8*1-?JigrF|YaY2CVXy+35W z=Go!@^m(A_#Odz;)YThj`1-$Up1-$$eqQ+dLi2$5KV9ESdp*GashKZ+&VUQU{#mrG z-v4QT&9lE}{-2u9>t7UK680~j&zoLwX=rX=rx*5z#^>Sx^!GeIAN}hUp}GI@f4V+3 z=Kt0-yC$^e|LOLzKWds^ANB{${6B4H{Q&%*&X40C_&+trWAJ}!=Fj8*LYwcy|Hb>{ zlG~HI&BZ?nE&r#}GanTHr)EAV{!h0*-;S5z|I~Od{GU42{1pCAJ*j%M`#(LNhgA)7 z|EC^PGs69!n)PRy|EEqhZ^isS^(^y(FHAfTx@6@P_ka5Q&*K;Wr!FzShyPPEe-8hr z#*g9ubpA!Q|L}k667z-lKQ-%nGyhLrZO4=Fe`@B}G5=4!Xtn)b&HSIbe0f@Q)$pf7 zm(k;s4b5Mf{%{PmKRlvp*&-eKA}g<^|^7 z_)_Si#iQK+>H4$&FaA$mVE%2#qTh#}Ry!^_=h|07XWIU~`pO9-d{6F=giU~gdFW&e+oqtJLy8AzMM)nBz ze`@Bt#XoN~Zv0n#JI(yR+=G4H12VsE$!kk82Hnyp@ywRCnRM2vOEONmvA4}PXp@Qm ztKGjeG``{=KUo?6p6&QQoge3)n6)aLAAMcT>ZHd1>GZ7khyPR0oSN$XPhBy|eh>ZN zy72d9DK;P3{GYBb^X2e=@y7qf8~>;CfB&A)MJcu(;)=bY3nxsD@PGPy z<^|&a)ZBl}|5G!+5dWv1Gc_$bVE#}0XYQ0V_kU{EL%yuyw6MLx{NI^xCim90r-$wM z8~mUC9&d#IQ{(xV|EFet8U9b5m!9eK|Kg4RQ_KIw8~>-)`oC(e|En&~PILdKu9%+g z{x9?o{!cCcr^cf(|1aM7KXq|-{rbOZd>;N!jW@*qsmn4mef?iGei8qt#xLUk)Oa=K z|EUXXJy-mny39P?>)$stw-5iP?OZ<)Lb9@pBg`i|BLsCuNxXq$NWD%K1*igy8lzN9x?t;U19TPo*#ZyXs+MS4m31= z5C5mrbA9lC>QeKF_&+sXHU9col%4GB8hgJY<}t?BkIgk-8SfmsKjYolw>9>0jXhlB zZtU9{d%ni=`2Me5Ve6H~uW#dSe145Dzwtc3#?9+%{QMhtW6#*Q8+*gX-FW?B=9R`T zudxSg+#D~8pT47cmH*a_PyfICUrU>J7C%2byqDBRnP>RrzgH)!C;ZucpG_0<^?%io z&5OeSsR!BXJN{2yTu|ixPra~uf%`x8)_L>Y|EW(~zS8}ly2j@Fz5dP8aDFQ{ul4zV znJIs9|F?JZdiQ_oohPn#|EJ!!yvqHbdU=k`Z#Mroc;f5s|I(&TbpNNWnP2JtukEBa z-2c^9&U62F+k!XU|7F_0hxk7=>wB{PuTDRt|8egB)G6)Tx&PDYhuZN_{GXcNb2mTT z=Ibqd%e~)hn}2rE!J5S8nz!Bi_370=`mT-5?>qfnpYJ!Y|B&dmg|&&zKYg#>`wbq< z_j!pszW%_y-;&&1_kZdU1=HRCsfW$Ua{s5EFgwfrpL*2vY3~2jle4C||5K-=Pj>&O z&am~c@qh8g|6TZx58eL_%b4W;Z`g4kyZ`Guag_VNr?NkB|JP?kfA@dtw#RgE|EC_< zt)u(DnpK~=|6{$>1KTc3ob}lN_kBm$dbY=Wus?Lv@(A~T+Rpkq_`i7L|I|GG@qh9D zWB-d2v;Ne-em&o2O`~C#UKF}Ri{|eCw4L>K@PF#=Ha`>pr^ajkedYOyR?qZv@5ekm z{Ga;R&RwF{=AW1N(%Bc_kU{nKQ$f_ z|EFd?9{x|w>kIx*x4&iAHtzq_t-H7L`G0EWx3T_jyqW)}=KeANPtCkI{9nBBe`@B# z;r~MS?Ckze-8ZGH`#*Ju-ksh5sT;RB!u_8b|JSMaIpO}{8S@@IE9^hk2i`Kcp^vcN z&(E50X4u}fU3>R`+CR**JFx$ZaCv?D^l|^E>q|>ZbN{DK@88G$pL)#Te(wL&y#L1k zsb>ry=>AVVU{I?2KQ;3Ong6HfEB+Dx7jOJu=t2G6|EYTq9^n2@otl~&eRs-n;q=^} zx&>Q8v;Ex6V?%TQX7$<}dQ{*3?*ICA9_W5BJ+-gT|5M}r@PBH2ApTE1tWOX3f9gIR zZT{sa6YIv_-PpZfTDRUl|4+Sg;WGDs>eH62jGASR52rtF?jrYp`@d@B9L)!_(_7DsALGuxIz)(bU-^ z5_;tc!|GaH6S)uU-nCaW`~AUnTlf4}`%UE^bK17<5FOoiP~B<6e{c`T{9We%jr!=j zdJlL+bN7Ft?ezu!7urt0@asY0_B68jr7gNNbmQhnM30Ug7`8`te*B;AUu2ixWmEr# zZq?2GpKfo9ZvEZ=z3|CTwahn+(lg!v>GrqC%y<8%9#S&L{hvB-^)c@M)YG?J!zeH{PFefM{vi|zO%>;H!B zD@R6mp7WbpjN9LCyEUiU)~~|VMYc?0-AHU5M7e`@Ag;Q!S5c6=HCr`tQjz8}ElHn3{!cx1?Kt;; z@#a{Ox^(T>i2qjOx$u8#j$faV@p7=jC-$&v9)cC&RzrHmz z-{0MO?=7M6J-=W5i-xxEM_cy(d1&V6;s5rYcgTG!o(=yOZ|480<^R;PZT&F(pPI)5 z{}=BG4_y};k2mz_YeUc8km2+Hbb4+-{!h*AANRu*;r8MqS0C6Nn&mu-T5#H7D8pHJkqz zPH%q?%>Prfe%EDhYzxizMfg8mU$K3EhyPO-+4nbpzv1lA%s<2bmHzeN`gw%rnecz= zDW?{>|5FcJXY*Ig|EY(p9^w8^J$&6LzP}6GD{Z}D{NF3LJmMa3p?%+s|5G!s4ga@y z;-l{W3hegc|I~c{i2sW>{!hKYZa@A{J>S-I#s4*Qz5i1)?_@y7#o_uZw&X=e>{<|- z*Q1YH%?q8gWm5F?1#?2rI5{W!MYGD#l_%##=bl>@dX9M={GYCGs(GJjTW5#u(@xKi z`hJ@qy42=9;{UWi@PPO~b)_}_PhDjm@Q)+2!~SLc;JkY?6Z)p~NukS6wDsi7|LO6m zI4RftpSr}n;wj&a3eSf!^GEo<@O&}h35PIYsx#<9{Az`_kKm2 zZM|Xhf1&O59{)FX>;vxq@T&Mf^=$Kd_`i7L{~kDPe}eyu_oWXuuKo10``!ETeJlP? z&3r`spL(tNGv@!PSKIfo%>PrDoIX2xFYhmh){MU2Js-Vu)1N})?ZB1 z!qE6VU;p>;{bjqa{~K%kpU#h$^!0xaZ>N3zU+phD|AQwiJXBP5ulpF*_ipy*^3eDR zU;p>;>6!oN>;J~i@9Y1@8vhrr-#j<|PtCkg{GS>>$oxMweh~ks=I_nd|2=&9w6FiG z+heEq^?wgH^Pu9#yG9>BJE7<8*^B z^9J{S`}bb!{!e}SrUiJt$M>zf!TsOhp3Ut1QKXIrHf4LJx@&eXd|2ov+feO~;ZdQg|{Jiej%y(9il z+gb0o)uoq*ZrR;@;Cokv&X_hXYMs6(^w^qe_kS~2UgQ3+>g3BB^dlcOf3`$Olhu8J-{{-MzG%@^SR z^m@Gbm~8idYTp0h|Kg4RQ}cP?qzk^t(%(D21^=gJUK##RJ;N>!|EK2n8{OXiK1;7( zv)7N0CcGMDtH;^v0sc>&VSXO}rY4U=3;!4I?9{fQ3+?w{=)z1{%0ONF~a|;v&_%Edrj}q-2Wq^w9w;gM%aAWexWC? z7~%8(^zUn~y`SEmF*t0WZhqyyy+cFu`xX43PLEH-|EckZ_&+tikNJP3RQy|5F#)?-THUYJT5<|5G!+82_i{{m;Q=3q$ky;*%E^hhAxo z|I_=O6?Xbh&tDO`#NLnN|MdQ9+S>6^>5uEP_5O|Zm#_VFQ?}keGJmmC!SUI8|A|jy z{-56e()RfyTkl_K`+ZXAV)JA6`6V>J2eZ#Np$qNvwEg}mG@pO*f4Y2n)y><&_L&>T zMGt;>Ug-Q|#=HO1>G}MJ|5Nk#{-0qNhGxCy9mnhp&F9%}_g)m5+lT+t`T0DH|5I1m z^KtUWmxk-Fu;(lOPxqhKk5^v1EbK2{KR#%`J2cNv{9o9g_W2e6r{?zK|J2<6{%x)a z&GskE|LOW@{GVC^{-ri=6aS~?{^9@B z9G}4dsqtO-zj)*S)a>8$zqq~O_S^pb{m?r@7uxp08}14{%RC+aPxluehyPPEPqcdL zJq`P3>F8+f!Fxj&E=qU*r~R30$Ju2lp ze!-e7_kU{5|5M|i@qcRhKXv)4`uTsle0((iPtEZn{GS@HhW}Huzwv+Z#{a1~J^oM4 z`o;J^b*cHkyVpP4(B}K_f7-t#%O<%0Q&-sUlktD*s#Rm%|An^e!~ew_|EFeNA^tDk z_&?nqJShH8UA%m>`#*Jw9UsO2sq+^OasQ_txisDVpL)DKU+{lw){EZP>#c;YTljWp z<`=$t-8%{W;UC@&U1qlr|EJ62`H25hbAJ3^yzzhPxiuL+|4;XyX8m8a=Krb77mkY7 zz4oVY{``fbqf^^|9=c#r{rta%(~orj7w>&9|0SHB^VhciYiQ1o{|l!#|M$}Ae-B-1 z^Zp9%{b%_5t+IK2S3U5r@On`>cX%}5-~SF>R+S#znEp++j`z|Vw|pDAqB1?odg!~* zbF0U=|I_i=nkAXhds#n*?MoNi<7NI&mseCd(fyx#a^67qf9mp#Q3;=iDkqFd=n9+f z7ymp~X+8q~x8rB2?*C}~U;d?i-2c(|zh#&7cK?U3!2hW$C!3E+SshNlz`Wl3W7dS8 zXMPR;r^~~8;Q!)%#_{Vz=Vnfc7GJm_^t5dALN^^9da13iiT~62mt36PiXv~_77eJ{}*rkpSsl6(`Ef%b%}XQ*8f$P zjvp0Waq!gG<&Tbzf9Hy!h}6xd(rgF=+P$|x*%_2bVu>tuszwc zC3o`tzT}>olX$#~^-bfix5?g*`JwUc{Js2NI@tpzd%OSE$zHC))(eeaf0?Z}8t?yh zdH(M~%tIz$e)4*||4%2~|K$6Ze0jWn{cpD~+5hqS8b5tHN9ztFZGedYJ7!}*7mR=EGu z_SK7)y8lxjx9({7f9hj4t#$vWKH;Rz?*C@)f5-jbg{N$e_HAETxAFdW-SeGs%*v?z z=@p^RT~;1_)u^G1hxK&-r_+xdkm~+Vy{x*z{ohshz32XK{oJ`x;kPw)>fGVOef?iG zo(2D>9-P+K{hu1Y!u-EczkA>PV8<5iqO^jgb=AN9z`b8u^LEkTn``R2|NEobF-N|b zGqQ8<=#AHF>hk{eNB4g1`V5YKn6aX6Z|0wTJ>Sm#M?@c7v!ZU|($C!cWsV#jjsDe& zx+P0KcW+mfUl?8e&GOJwi}T$7>GU~;+3x?;Q)cA2|5M}rSpQd@om=n!)H&vrng6Gr zku}c!pPG5Y_&?nq=Kr1Y<>I<4Z~3!(zn;VTyZ=)UOX=hOPd(7qx2?ErQQgSr|Ki@S zug#ld{-3&cyO!?%ieK&L{tv%~|5Mv|H}`+)=1m$!AHQ-%-Ct_^y640DW#l#VQAae1 zw(s8^wsU&?pH9zq{GYl_3-dTO|4+^Dwef#yyxW0)U0SzuUz&SAycqsZjc>#Msad}T z|2K4Rs{6lg=KJt}@y7qDyLM>h{!h*RxN-2#u$^Z9pDw?1o3=jxPuorXx;1pqo;{-pS8olM-=jwl_kX%QgHqGn|Ebdl4R-&ho;awV`@eYKRCQX| zKf{Oi^YwqVe})cDbN{FA+dswqpSoA?`uTrq{4n$X)Pn{Lb^oX4^$P!|=JgE!r^W-~ z|Kg4RQ}g%B`oEw3v%mYlp}p$Y|5f)%>*4-Sjc3IFsfP~e6BRx`sqSabHFEFA{6GAk z8b8STzv>MuSGoUFpSNL?`#<%Gi)x}1sx!jrrxnbOK0a<-=#JfcMwPq9hHlX_C3^Di zF`?U~^>hDM)1lrE;sNo0YCPblEfV{R!RZOx+pZs8w{T*VBc{4k4P)c7#`pPJ*t_&+u4q2mA4n*SGX{9nBBe`?kT#{a2V-v<8|Z~UK{^^@>_y8V0~ zh5u7C-vR%p#slL2)KgatcmJoJX}$^nr^c6YEJAj(+nZIgz(>Fe%L*r{GXcJdt0A1;q>(Oy(<%XP50%Yncp?@s->aXANW6AKmHN_ zr{?=g{GXcng!n&ov3WZDpBle||BE;NPq&x(Z}>lLFEc-d|5KNn&%*zyOKlz*{!h(3 zvTgU}hW$*=nw%kJM_zrL^ied7PrWi}78e?f=Z)bH+h?}z8a|EXEO?x^3ls(pX@{qFl%KYQ8w z7NMC3i2u`e=HX0CJEFG31NXW2!*}8T)O;U4Wam$ZUi<#u`gwddPw$OKz75TMy>mbP zSLkYcyhnHXduV(g{!izp&3_zfy5U~;eXLJwJ|r~r?eKrvzS#U6{!hKYPH*1p(9;L* zaqou*!~ew_|EK2h!vCpxeDQy3yczyaU1dJi*Z)0y`BhtI)vx~>YhV92^i21E;r!+m z@qcRWFaA%>d_nx58c&G-Q?ozue`;<&{x9CX{_o-I$Nx=u^{hkx>3fg+J^G2xCx^!S zb=bKvp;tt!LNl)u|EKfgaq)kl?fFq%lOLMDcVGYa@bz=~zW#5lef{6VU22}&*Z)1- zcw78mxIcD%zW(pw?aUMP^?why{GU!Q|EK2h^!0xapMI9jpBZ7Cmqt82d&tIchwDt{a=&lo^$t2Q8Q2Q)^}?Y`i2RwCN%!9^vN6C3vzn=U$3eg-T!es=G3nm zXT=-;r)K^j^Z(SX?DIV9|El>tAM^jz{N4}$r{;JE^Z(+F|I_Wk590sSctPg>>Hc-K z%ftVveLV^Df7(A??D9K3vo=eQhqw7ZHS_iHe`@C0u%WN{!gdB@r={l|EZ5ZeUcpPJv_nBUFP-!JdK@qcRGe|OmV*DSsM(Cfe6Rbo-fq zhyPQ{|EcrMXW8pt*q&pjKl;+1361~L{^I`O|I~S_M!Ek}XRR7-9%w+rcKf`8|I>DS z4E|5e=YhAIjA&@vzfCuc42}OA`P%5veEyg}XvrS@wByU-Ld-rSfO zI@jKx;{Wt~$unP$|5M}r=Kf-8I6Zw<%Ne1oY##MpTV{pk_dfVP-5)+5;Q!R~?Dud( zZZ8Qv+ujdVwk;1`X8&GoJ+U%$mHl4fws+?w^lQ`Sgz9YdH(vVBRoQw!RkCJ6^snCQvi1Ip-_PAYW@EPA|MB^GP1SMP`aHwu zWt%Uat@pF|Jp7-U?f5^nAAd0ar{;JA{!fiZ!~dz7N7rfDxuKcohyT-dp5ORCHU6_% z-}6Ird#ac3NND_@-oIDa@6qsoYJR_m|5Lk1HUFpP^DO>P%{)Z>pRS+A|Ec+XApTFE z=h%+_Q*(R<|EFgC0sNm@{x9D6KehjToBz}G;f>o3+7p`Bn`LYEhUWKi_&?qLDto=! zx&6k3?)ltJp%jdTB}&R>)1{x9D6KXs+e$HV`r z=d7{y+HL-yx^S({TQ~owzXv>^&GHL9eT~g`wE2J9PUHX7_%Y`H#hdwm;qvYC8vai` z+n&!yjj9W$$Md~)%o7QH*ImC1&HmZ?`IDiUXNUjOy+&`|yA9 z-dXlV=#s^wqP>^?IW+58hg+#?*G&a7LIiPr{l4U7msuQr|pXtjdlO0o?V^k z{!cwFx4-*8HQxuHJ+N_(E^qpjM8AR0+O?rc*p4?j_nBomYftIz-f!OF`G4xU8Drf4 z<(-;RKmTv?825i_Ur*8epH4r=JRts0U1js)@PBHq5C5me1LFVG_!#`3n)y%oKlR+q zO!t5BX8xZVpMw8W<3;d)YJ3a+PmR~Z|HT{sr^dhF|6aJTkNZe&FaA%>{lWjKxjy`# z8h`TOt*3;`tFrC*KV3e)691=`|5NjL;s11boFD(E=KT0SHRs3wsagLR|EK2i@PF~f z|LOX;Jp7*;FN*(Dv%WI^FW&gSc;o-n+#dX&8t;VvQ%{>T-sk_RC)wkN|5In$eEeU$@qh8g|HT{s7jNeO zsac;E|EI?9;{VimKK!40fvr!B|5Nk$;Q!RTe&GMqJRbNzHJ6Y7i#PsH{oj0B^7dqp zHr3WQjeD--{(roi%@2*AewMwy{%@Up{^a#+ll@+DC*R)Wo;fLTer$3ld%)zLJ2~~w>dnVRQzxwmm$z=?YM=jCJo0V#fH~7`eKYfa2Zq1n z9&r5lA@2Xw0|s=9#%3<7)9DKb4~ZT+r6zQht#|+aV>RLYS)(%C|D_Cl*F9jL4qe^< zsqruPKQ;5OuDWkY=)rvkL{r+-)TI@?@7`}{+MsC1%$m9#Ge7Y8ej|qti;8QP*9|=X zkG`I7=J*Lw&%ZCPyJXwPKHqPkdD7)eSJjPp=1=bX=ocU+Lj5_+0>>L%$8Jv)DT zw0_y*ustt(a@79dlDZW~e&OCPnqa^8GXEF4{gLkf)T3J*<^E4SrezDC|EK17>)a!+ zscV0KU-y3PZFwB#|Ec*sI{r`H$~-FT|EeR~j{m##<}~+z(GgAE|Eb$FKhpi5n&ZXz zKQ(?1|EFd>Tl}9I|Aqfk_wL=>{a>5QQ{DgJsqlaCzU#A#>vo>g$GsnZ4gaTZ)2*}n zKXsbTL&N{YoB4n7#{a41|8#ww+S==ft^cd$?;roCZq%Zw`#*In`+Yh7PmO28|LOkG zSM_XYd?Wr(+tYgV^!0z$sW!i_W#x|WcnnDG;r>sL55DV_vFC^FtS5{A3+K1_bFBXx z@4mNg3oZYr?NN*7?*DZA{dm0jKXoTt?+E{={l(+Y{696G6aS~iXW{?U9eSj=|5Nk* z3jQx#zV&0LogSKbc~fdm3q8o@b+Z1iZtrmOfXx4kH|zg~KJ5RrzvTba1I+_6|4+?) zK<59cdH&)5)ObJE|5cCZlji;7)vK4!|5J1M_`iLx^>hEn<2mKL zO`-et?d$$8Z13OS{hxYVT1vF?>4|miMnyiaZ&0UpQHPHvgs$k_*Zp7nPa^k$*RERU z{!e}4hGX6TsaM;4K>VM2L`9|hKXqgt6aS}f*R7}fKXv!C{?X{?M~ChBzneZ8mC$V) zH*~kue$kn|M~3b6w3#Eq?dSY|UokwPZ#sKeLYLk+G@zx-ub3Fd@YoBlE%{e~*Pv@@vl|H2zPg zXWk$FPt80){GS>hi2u|5DYW?%_&@a``~5fmPd(r65B^Wh{bT)KHOKGqe`@(Zwfvu& z?fiGVH~s#h(AD<)-J0DGCN%y}j~D(D{}*rkpPKmz_`i7L|I|}#y(RpgI>(OJu6sAO26Lr}2MkzF)!rsrh~d|EK2r zRs5ft?_=?QYQBGLJoBn>eVYHL+sppJ|7m}*zAFCjp1u#c|I0K_#{54!#_#@boLwLO z@2(~X66XKiS@MAUzcn`R4gaUctKt9DcsBf>&M*HL?a@@UmW_7*ch4~ox(}>ek?#Iaz1a2_^Z(TBzut$ogf20k zg8$S0;rWFBQy1C#!+#oZbZGAXb3a>`(D*-{o_ToqKlPlG@}dJ1mxb$NJ=l(qEJH?*G)QPAQBod9W&+f2Dn2`sKKa(D)zxpH5$8-|w!7NSFUs_&;@t`OE&Jr-jSMd*T1IKdbHf@PBH)&u#qGU{6GuJ#4{!cx_o)7pxJ^%9T`)B;0dddm8(eCsCweKF< z@7`~?eLs)?Qx~ru<^E4yd9?IZWQ_rw2vJibS5+mr8i@0Vxa=i>j=e7`#T z(N49kp1RMy-$MI78~>+XYTu9FKcj7J%QpA9_giAO5C5m0ZTn-#*GJW6Z@t%jAN|2a z%|o;QKD)YU?Ud*4ao>k$tW9qmn#T+Or|omiqv8M5v(3-_y2rl`ZJuzCdp`Q4qQ8a4 z*V+1xq49P2Kb;;AhyPPEPY?g6UU^25`#*J!`9l2PrgQeW|I0dky8A!%l+$dUkoi9~ z{tW*YZ~UJcFNgnAGhYw?r>-);$Nax|KmJe6^8^2<=I;sr zr{?*A|I_U$J8ic6zj)*S8X6DTH=*%=+RpyR|EcTe8#W7FZ2OP-f7&kpr)GcP|J2j% z-*fz*o-cju?>+v0bIPUF?*EEDy2}0Es%y`8|EJz^>lN<*&M3di{ok4Q-|hZSed#X` zy8lzZ@!a!vK;l=AfBf;4?y>&-?t4*Gu`TpZ&p&J3H1tcC@8S(`q|OmbM zd|u}H_w23reSMoTUodpWH2ZvM{!iPRWoNkmQ#YD4%Ke|ZXZk?*f9fN9c69%z&M+Ux z{J*(5*Sr5qx8r^IKXq60f%rdlH~T%&4d(yU_(A;N|J-%G`#&20cWBBD_5QC(Q}=)I z#{b0||EF$oL^Jn)YJSg$|BE;NPtE6h{GXcjj`4rGJ&kN0I{r`H#C{*O;n}j#ovrbI zx<6fP{yOvjw0}k&)yDnbmw9{LZ)SGt9H1IIyusK1)!)PBlNR~< zzv_j{XSx5=>p!1&@PGPy@PF#r_I?=ur`Mag z8}r=%sjH68iCWD3PuA~h?sl)o`ohbbe;=Cn#1p`8@oen)lBKXSGUb{GVF)c8B*|EZa;jQ>+-+3m&usi)ZIhpu0x zgf6hp15eIN4L#H5z1iz&==ynJ1G2Th>8G|23fp=Au<6f3LgS(Ee>y$$*6@Gv#{a43 znGeDL#T);p=JCV-sf!Q$KXrlq{s;f3=S#kMIQ*ZQ`P2A6ou1FX_&+s14gVK!{GXc7 zOZY$a5}U7x|5H!5-)rIj)CDKnJQ4GMYCbO?|5H`iKZWMs`mC%DJ-{Ugmzy`^l!V6r>HY8$nC^ z`8577-uOT5A6}2}f9i$S_`i7L|I|GHng6F|em?$B&FABc;%gHc|EKF`JN_@;`)|8G zG=Gmf&Hw514fh}ar{?#U_`i7L|I{-!*02Ao=6J@;N{LPtCkU z{GYmNrFl4;|EI28G1mQ`8lTAezv|M3L*4(WD;EuN|EFGH$4l^k>M4i)pE`Tx1owaH zTzmZSf9gDY{PBNk)+tEUWi_@y7qD=a{F%|EcHNde-mR=KrZVeeXm62t9Y+ z=xEaq{|t@)TR-OC;q{@Yd{Fe@#ILi%@#e}Q?*DZBcTU9!_kZenwtjG%Z@;LNbEd51xl%t+jH6_~eVM7m^nCkvd=g%24G`jfKMmg%)*@>P4{}TWFl|0{Sfz4lw zZ!Z~D@Bh+P_j3Q2WAB%l|EI=-G5_y^6)ElqtHx!x|5MM&81Md1&HA(WKlQBflidHQ zvoj~S|BE;NPmLF0{$ITDe`PexwefYnY$MtqEh)2Qy>GGI2i2qYF&kz5nX8$n%FW%#R+}hBS z>iwTC9}k27Q{(IKfAPlusX0CVFW&e+T_5ZF;{W1}|5I~*{GS?Mi2qZUWQ_Frf9i7E zpZGtu{GXcjiCO*x$W)Rd_z}e8>N3 zdzI}!{GXcriT{f?{!d*!#n$&W{}*rkpBgWS|5KM|PImvNo;+oO`#<%h%<=C3)I2`; zzj)*S)c?=C)bWWPE_r@x+1NzCmy!x8zQqrNqH;bgCu?CbEu@!ON!$$pR5=lJRISn%qsj&$4;0 z@#gvUzjg9F#wn8$_jj`YOYY?Pfd8$N=LdFXU|P%vwj*PW@5BGyb>HvZ|Izrr(Dr*? z{GU2%+{FD~X!BV3KXnsZuMq#&_`x^b|3&?VyZ=*XFW(TI{@BWJ`kK|t-T&$Q3u+d* z|5GnpQ04xw>h3?d|I4@ebtBBvsYj0N;cCrs$&{!h*PJp5n0@qgdn_Llp>%=EGD z|8DvD+wT7cnxAMhp{7nfre{C*f9i>8L)`zV@qYNfFKXX)|2KND&BI=`yzY(HKk)f} z<3^5(Hov{H?%{SH`+UEg$(hl^?HU??hyVL-*r)FQm{*JcQ|ISSaQ~;CQ#{@MpE|c> zmis?-#Y8QY{8Q}p{H5JBp_%uG|I_J5+I-bL=Ks_a3JTo+sf!C|MlDWUQg`+2 zKl%E;fXuypL%eQ&hG!z!&18W`oHQS=8HBj*cHw{xNDCH|M%CmW@eVR%kAB@oBKaC z^8=axr)K>g{9nBBf9k&NJNf)SHS5VR|8LicecT^*w)JfBe`@wW{;#2%x&KqA_3GyS zPd&6(SNDIqKioh3pIZJ;E&r$Pn9{@N|EW9o>E-MHs_|p2|EtEQ;s4b5TKu1y`EvL_ zHS+?G>)OzGX6FCt_H+E6`G0EGYsUX+e=#o*|EF$h>zU*K)T|GS|5G#njro6S=DFej zbonVgQ{Dfmx&8P*_2_;B-2dtJ59>d`{hxaHfco`+)g$fnt1?av&-YRN2m1U!J^xu> z82_gp+`GH`KQ(?2|EI>|;s4a~e`@w`o%ugCo)7=0=J8_wpBk@;|2x)v?&AfWa^?Tj zspdCX|5wdCLFWIdhuV6&_&?TzUD58d92){W0$U)LYio&;L`e zUcAEnpSrZN%Ke|Z@4!Ls|I{6O_ICfLmj6?yr3`WZr|#Q(XoUY$b9($=yzzg!{cOko z#T)+@Z~UJcKZyTRGrtl47jOKZx?AtT?*HPA{|jxGhyRN={!h*Ad*-5kp}GEpZ>QD$ zwfYD5fT?K%q6@xF4c((>pXk+3Qp4$6bnhDtoY*I9KeB6T^e^*(I)Bu+Wys=Lt4#7G2i1M_uS92E1eMKcYr}z=q#1L{Yu}`$x_rhdp4u|5K-!C&mA% zC(Z2U{!d+D>yfbjubSgY_&;XO;s2(t&2;~VLBsz|xAmg%fAK#1>)+Jw>;I5@zjE_# z_&;@-{eB<+r)K?~YnQ!L`X#AhH z^L+^ZFWz@v`gG_b`#z#)@ly$n|I_W`_x|5(|7B=A;*e=igq~;Lcg_E)HgvUpe}ezh z{^0&Se$v6Po&NLK$3ydbc-Df@_0jw`RL$u*mZZz$`!N1nJ$LnZ_kU{E^C&Ml5Vq&o z?}71udi?U%Opfq>>KSXZ-2bU(t$Bbe>G{F;Yxuu-i!v_XP-9R{a^g@@qcQ( zVgD^zVgGY~@PB%IX#Ag==gaAN8R7ZB-y{A{&kxr7!~d!Am#_92QQNh{e)p(_HXjiG zr_ML;_sA`SY75V~zka@-y?*2W)Du^abN{E#Ts<*razmfm9WUQk@BKFBMi<`EtM>8i z``r7@IC^Sy?X}%&zq#;U_kDRb?_$f4uAy0v8~>;6RW>hj-UIDxC%k!&dq4au{x9BR zR<^2LKkFX%ems9BuRp5x_TBs3_woE`->7+LJQw~?+bhh!;r|-i=IcHD~r6T zSL^fnH=*%u_&;r@@qg-hHV+T~7jOKZnt6ZtKQ-&)o-pE_LuTyU_buL9Y~RPf8G6B~ zh3@~fUGx9cv&|>s|J2O4!~dz7FNgnA%m1n6|J3+8{GS@XX#X9W?f5@!XaC^;)P=U5 zFaA$ma9aKRKXsA)J>mb<{5@u;UV5nTiMzr)zdtRwF!X%$i1@9UthpLvKYqEBLtSNu)rnfCgM|I_nn!1{FaF8e~~Z7+2H_t~3Q zy8m0h>kRjQ>a%aVGTQmVtb^)Hf3es7UyuAN-2?8u{|@(m>VpRly8pA8Z0`Tww0VH| zKlM*N$YJ@n*BBcqDl$4%LFaudq?gJo!zgO?eD#zM|WxK z>;LNX{9f{;Wp!aY$7fjoSKH~XKYTQ0>459q`*C~*|EI(R-s?3l>$7Y3xVLQ6vUAj7 zU`>{-vFqNidxwth|I{4+!2jjkaGm?VAw!0^|5FdQ^+PiLa8}qpD1Ag!cF|c`dcO2X zOJzP}=&0jS?*FuXwjVctj{847KW^H74$qw|_0>DJyZ=*PxAOw`f9gB0 zy2RK2)#YEa?R0xS-x4l=`{`TU|7rVa$F6bzr|18g6BoPxQ&+7hWc~Fl{e9tQ@PBGP z-`MMSmj0gQ|J3~c$o_t_^!JSSd;FQtLl>EkoA=b0SzAZl<-QM(a{sn}gy#D2e_^}5 zU&a5a%kAHD{GWP(T_65Wz0mv%{!h*A!~dzL+dL=ypL+C)aqj=r6U|Soy}eD?&gYLW z&S{^m`!jQ0c68Mz9YasskmLSO_kZTbsqX(m+vhL*U%c^uYJNY0|BE;NPtE)FZhZ$N zH2zQ9@lyD|c-!l9XnfGq2htOIbNA7q@qaze7@N@eKRw>^fAMDipPI+F@f%qQJv=Kn zH1p>0e>y#l|5Nk%2mhz$_jC9^_58#BPtE69{GXc7FZe$-@4sKTt|HtY9)J9w_76T4 z|EHd7>)+!4bp9na4;%ldE;nz7|BLsjA1(`BX7d1lk-suD>p$<@v?g2cuNIn5`rw82 z*?PaW$UYzM7=KLY8uK~$KfRw_YR^ynpBi6gpHD(F|Ia?Zgf8A<9&YJbp-Yd?;`2}F z3iFrt`>4?PKbxN(n%_tDUvyq*PM@)7duTq7;{WvioZ}7nKlNPmm-s(*g*~6~f9gE@ zJq-R&J{|EK*i*S6#T)c7_0pPG4R_&;^^rm61#)aCa3 zQ2d{o;}!V7c+b4(y3ow)#{cQ|@OvKopPIkF#-H5~8gEuP_@>Z!&R?v(Idrw1|Et@7 z7Mj<)8K3_=q49sZeC{9qFW&e+HS53P|J3u3$#MUu=Jgf-r{?;Y|EFeu;s131tL*a( z{!d-Ba+1&gQ{(kc`R=~3eda1#57+#kw&MZqzeD5Y%+6)&^B0Z(Q_KIU<^R+ipZiDd zBiZ_VMxVR&(a`w6&W}Bo(6|5l@z6XTlg1uO=tgfG%GT#M{NEMr>q6uI1{6OLn)Q9p z9`Iy1KkNH;SpHP#V)JOX-0*bh*)_I4{oBukp0;R2^wbB>hWlG!9_@L|5LNRE$jcPix!M_|EDfnlHvYO&HiEjpSr|6AM^jzJb&VT0@<~yP!JmbmvutAY&Z^HtS1z{u zYyMBShxLW=e`@?7{x9CI7X43X)*r_I>F=#-$yoP)p=}-@{!d+8Il}#)j;G|=d_Vl3 zjt|eQ9v00w?VHfWHb0Q{e|0>zq`Kb!smtb#_4$A5^7%He(boS}=T%N}|EJ@#!?Ww> z|7rWQ@#*gW)XaxEA-{2sI@$lRerWu7e|1(~l(unMPNRyR?){3!)UW@m&KPCK^UeRM zC!6oX|J_mC%l#j|gZY2)X8xagx_LMJU%Z+Br{?_3|5M{b@PBH&3I0!wN5TJv9zWUr zpKf27HU3Y{<>UY2jsMg6xqSSen)Pq-e`>rU{!d*vX-b6uQ7vK}z=|Md9N_&+uC?eKqUyczyajinE$7)u=~gSKQ;Rc|EI?D;{Vjio-NtW z;dkS&m#n`X@8o%P$(`)ok~{hOliMHv*!Q!^elOX-;Z@_eugKO*k2ins@t!d;@!x}j zDR~LoD>HKvx@=_e=JD|7~7iuU4%SuD`SWzBYdQSPvEdckIYF-T%?}KXns3euw{yH}n70c)_-R zTUB>{#vAqC&n_MR7rJ>X_kZfP=Iii(I=>Aca{m{)QwR5d>K21~y8l}+cI$~@z>UT>+XN?`@{%`-dcijIKPs@!i*|xIow#6U%e80TH z>F)ogpZ1aazrxC5_kZeD6(#QfUby^Y_kYVu?E4M#f9lfW8Sek$&HBIUk)`$iPd#Xs ztq*AaPtE$j_&;^_tUULB>fZVF{!iT{car-*b;l7y-2bhspSn}0PVWEW&HO)gzs~L4|EULb?cn}T-KSf3_kU`R|MvNOS2%xq&#vzOw0%gI z4!-_x$A!J!=W+b_H~vq}dcDm5Q@3l^&i$V*uUo6; z?*G)xQ^fzpoArOyL(Pvd|4%*H?ho_-bo(cmSH%CRS;I}-ckSfz{rEp!K93*s|I~xJbocdtb^C_d z{6OaasaYSG`G0EsBlG{%L;LlQUf+FkXtodTa!Ppq%m3-`VQ6ao{696%NBo}}uZRDO zH|zh#8~>-~_Tm53TtEIVbiWk$f8%$hx&Iq%&HO(#^Iq|P>W(Qrqj8^Ztb1)=-?|S< zJLfV_694yyH@MT26^yyV^)G}iZ@5k?jng6He_xR;gep~zA2M65y(fB_# z#}Dy;YK{jF{l&|*i_;Id_v833{!d-S_fzKo)EsZc|EU*l%5(pxUSRVR@PF~f|Ec-D z1OKPy_&WYijUU4Q#T);p+spSa_&+t?4gaU+_&WYiU9n+Gbm8NNLi77}{GYbt&G3Km z#{a1~J^nAWT_65W`Z+*!rgU zzgA!FcmFqL(|GrP_8oxxzl<%DeE#2&JMMSy$NtCvsppu#V*cOu*Y9(GRbn2F`G4vn z`@Ze+i_Z(qd=31c&QIh2)U1EX{6AekjsH^@+I&3xpE}>pkN;ES7x91Uakkzx{!cyH z_P>2U7dpe%OYT%~d}!8p`^O8%hR(M8i~rO9;rq?EA3r8EUT$*chS02^d(C5O6B_@g z^RGN5-~FGO^~mslYP=5qPtANU{GU4K@PBH&6#g&X_&+sX4F9KQ{u%!7 z(iX`O0U+_cZV zAM^k4e`=o3Z@to{_Nw;#-22fhf7`OQ)6%=$`!T-_{}=Cxmo=-M@#y@{AETO+Gd@wXV@@MDW7nZ2m$)b6XQ5}<-^29H*N2{cc1iT* zo!2zUEr@u2uWb%A+M=KsYT{}*rkpSsZ2|Hc2Q*+1VFW`ySNzwn7+p-ap^?#bvI zy3}s(mv?px&HBhTPb+k}oge=fF8{FqQ!_si|EK2l5&x$yu=OC#cOKN^J=Hw9S&q>79s(?_-n-NAkzG~pke5_b?*OqjTq_vZ$yvl-2V+2KFs}} zy6=#|Q72pfSKTMAhp+#u?%26abk0jBXX*LC@fiG{n$=zKf9j}X^Jv%cJF@hA*tqRv zpZ}-6@yg4ioqaD0r{8ngCGP*U{oIS{{hxa4_OpEbUtRuLXP@N$PksCe8=^b^`ircy z*Y39W&*$eHf8x4ma+^CsZ{D)X{hyxi)u+_^KXuW@3SNJ+^!LU5FnfIt&HGvWpSI`Q z`!(kOsb|{zU;JPAdp+#`)ckvj|I_Oqz6}4TX8m0JpPJvd;Q!){|5MLdJ=Xo7x?;sB z_kRsN+Wnupv?ksCpPJ7b%>PqQFh7C+Q)jNP_kX(m{QHjoQ}g?yy!+feNg;gyzzhW z#{b3J)_V_)Pds+k#L&zK$N%a50lo{GYnePLKan7un_E z|J2McWB#9->%;$rw*Aq2d|9}Ce169N>HhHf4*wT#{GYnU&j0J@=7(No&*u|HEDDY9 zOTBza=yLON_&;5L(ebm~|EZ_h^W)`vSBLFO?ep1z->=Ko`?KZd1Mz=)Keyie75-1} zXIHPC?EX)Uf5ZQ&tL^hU{!d+Ce_!}Nb)orM{GXc7OZdNd}PtE$x_&+uC3#)&VK?ABg``^L%0c zpY{*U{6969S5@>;!v6eZ#~(v8&+w#YK2GQsjXw>|{=xt0@@V{@x_XIuxu1U#dcOJ2 zGd}!tXl_qgpD#m~+WOS^Ki&Syl{wLeJO38CWGTms{vNt=iOugd|EIslVw(q8oAs~I zvlmT>zCG?g**e}*T4TSreemnhIW?1`-yQlkTgQhp7mbfrMc;=mTRh(VpN`j7ES>27 zPtE+l+T~G>Iz4BQ&;L`GXN+?Hr)HiN{x5XWd?x0-#r*;6rzUsaIm>fC%<56U{x9pB zn*US#dZgz6UYO9+{U6>3|EI>M;Q!S4FZ`bxAA|o><6ZE7@y7qf8~+z?{GXb6Q_TO< z?PI-M{GS?sg8x(Fd+>icf5DV-?*G)&CyaFe7ux0>;{Vk69sHk~`GWXAHS@smf9lN9 z>F)p3cm@2Qx_o4Y`@eYO|J0RZ$3-1G*?Pc-_c!wvzv*P_{~m6x@ADfI8~=Clv|jE7 z+27ASXzK$XK7H=^u@U}H&HOF=pPKnd_&@EhoGBCC|EXDj5dWv<`B0X&Euoj))zJ8> zV>8YR+wrJp*EKZHzsm}?hwXE09vuEpw}ST3vE6V{!d+CjsH_KuMq#IE}fbi9s5Q@xg>07 zePibT>Hgpc@qcRfXXgLZi)>ye{!d++H_iQ@x_sJcI7?P#;1 zuIAP^+}Aa;-ygRsULP9YhyR;!&+B16ApS3OqbBbET0itV_kWF|#_s>rc4hAW;{E1* zE9yeq`mOJOvm#s`>$$T2uP(n?yVmaibo)~6cqH@x)EU_mef{4HZ+O!^U;2d6?*FuX z?5KMGr|!|Uqx(Ode)N$Y-Txi9>i6#dGCQP1w=G&$SHAxb?)^q~PjUaJo}NC&{hvB> z?9eE`WL4d`7v6X8S5cT3J@f49x=oEf^7VJiOQuDwzh4!4$-=Uz(tM=0Z&+9oUAJ;& z=rz@a(FfP82tBu=AR6@2^3bzq+4sSX8hY9c`@S?|S=dg0zpf^9=FG|N|E~V#qx$)R z`BU8gsRz!=^7()2_G1RS|5M|=nE#j2`D6EgM<&f{;_;3@pPDu~A{vl&V%^h|eyTm@ zPk+v7)-2JRCa+(e{Cvl={?BPw)ty|>+r3}U);7=0{GU3tLu>bc>JFV+yZ=*n>DJ!; zU%Z+B7jOKZ8sEkIKQ;H4^?%iDXZ>GwkB*((|HYg6e`@9pKKbiQL-Y5F|GO$D#XTUN z@X^|f8@flQ=(|ygjsM%9VQXrd59I#f|I{s8H*^1|%k%wd^Z(+F|5NvBc7)IWQ>S<9 z>i$oy`G30o%sa&Yso5X+KQ$f@|EKO_xBtRT4c)tYNB4i)KBQ+C_kU_GAOEMG)U}KI zKlOypoqYbEnt6@*KehayZa+Nwe^bde`@v@{!iVeO&j-r>JA+`xc^h* z{qTQko)7rHc;_FrHQYY-5B^WLSN>0p_rw3Gng56XQ>XXs@BVL5Wgqvj~GpL+h>dG7zzqwM<|*8f#A&+*B-$Ap&u)Aj* z|EKHk)qjxtztDY$x&KqA*t}l+-=N=qs{~vZr=R0`#+aQ{c+|I{20ee}~;YG3^G{^0%a ze`-7x{!d+M-&f)P)OfM|nJ?7-xOl&Nm}*4e&$i>? z_&+t@PvQU6g?4-%|EDgp#{a2{?fWbIpPJ+CzuA6AXudBh_~iER{KEI)|GF)ID9i)I z|EckT_&+uC#qfV>{3rfT%{&YIpPK8(|Ec+Y?9JP62-nYiu)<~6C-lMYdqd~j^B@1G z^Rs{Oe`@>@{!d+G_wU^At_tVJAAa?~l?jdi)8E&8^HcagJw8=7FN5`e^?c7Z4|r<9 zMYZD#?{n{$Yo~wf%nNJ3y5?T@efYxsX%~cM{vG~L+e?{0Vg65DY~Ls0|J1B!^;6ll z(0DEUpRSL_|JipE?hiRV{!d+O^V9Hu>RI;pg#T0LoA<;2#T);p#tY;B;*I}Pvz{yd zPtAM?{NKU5?{^=`_t*G8^*rXang3I>9xnb*jpxJvsh8M%Kj#0b7u)WZMpY|vB=gEna!{be-9-0uE`6c*2Js;-S_m%iRb*ats!~f~| zMC1R|<@S9k{!fi}!2b6VzI|7i_lN&GbLd^}|JYy4 zzdo||zP)$4_v874|5LNxEdEc8hr|D=t8IPgSMT}Z(564%;l6L)>BX$a8X6yn|I>CF z|EHdRdZGJ2HNFr3r^e^u|J2Om!~dySe;EH4Z(slS@a?Ix=kGlOUOIHc;yc{)ar)|- z=R$M;e!A|d(9A!?|LOERfAN26{$B8ZYP>A|PtD(>&4N1g>MOU`uRm$$@4xBR(9G}q z^}d@!Gym?mzw8Y?=d7}*$FOTcSDOd?<+|OW=h*y1{GTp={TcQCPrc%#eDf>kh3!SQ zUON6y+iCoty39Nr{!h0bAB+D}bN}#v@y7qDr`vki_&@bb^OpEOb^ZRz2+jV)|Ap=5 z`S5>g=KJCQ)c8;QpL(vHAOEMuSDN=Z819exzuR&@4qajXd3xq=LYJEl#sBH~!hBc! zpSr>x|I02r@8IbpuBd(LUpsQO&9j!wZIf^5A|BiA7((aJl=ym+t(z`@g(@U*`UA z&&kKS|2uB&W$yp3S%0GYKXrDyUhe-Qw%<$Q|GNFS z%l+Soe%+#vj@%u3c;BwkxTQZ2J!nYZ=)mX)rX1S6%iiywmos2cYV^s>*QRXRw#PkR zTCXnA%P;;hbZXDe(L)vg3eD$b{GU$G@ksoix^3g;?*HPA|5G2;qe_+|EhZrO>_Tu`{rxi|D_J^=j;Ef zqhTr0+pE`Qg-+{;7tPY+A9ZRKtvF|MmLBh@Ra5tWp&K`H|EE5xO>6gm>W-7gx&PDi zVfh8;y8lz(dYO4t^M5-1^*b(%Y*t_Bi*}wJ-Eqvdq0cezH);3vp-(;i1YiGGmv_QR zo8A9iUvs(pzY|Zk^?uF&sW%)`GO8fV6@qKTEt~fr& zUQgZ*U1XnkT4jEa(DwJ6rN8G{o9z35#-ArN{!iQay%7FSE&mt#=m}BnkKblp();$> zg)8^u%(C@Edp!PA=u-0xk7YK_*7n)<{XO&lbpE21_5M#?x@MgFKQ+G}!~d!I{TTjF zjqhXrpY{*i@qcRkKmIS?_&+uCf$@LpT$|U0|5J1S@qh8g|EYO@FzcHBp-aq9{qx&_ zq51vT4U2~)H2zPohkX9P|HT{sr{?o3{!d-CaSHQZL-TnG|EKMI-opRs{R6)z!vCrH zJp=wvjlb&kR$e$i{cQI1(0rcU^7EOYE6q>g|8)K;o7ac`Q}cQExZf0q)ARWl|EJqW z-XsR^eq+A`by zpKjmu_0!z{sqtCgbXgZ}|9ta%@8unxt@m$>?Ed2a^nRE1Y?=S3mj8=4{x9D6KlMD@ zKlnd2?`QFUYR&&syLsSB6ee5Jzs zvi13Diuo(EQVEU!({_9p{!d+Meh~ksW?tY+&pw!~&tJ@c!~dzv%%|c1)aB;S9{JNF z+4?+&PsIPJ3vIqS{!fj+#{a2VKLY=!=J~<=KXsKIufqSSXRpg~|EJDdYR6-qellzy zWAosc|EJrRvBK70u=#)L={Bzp{}*rkpBlgR<*w&LGY=5|r~NZ$#boz?>MEO8hyPR0 zv*T%ZSH2ROd3X3fJzlKejQ>-!KkVMY{k13iPYFHZw9i5_4-o&S{asZv!Tq0_?f5_SJbS#;7XLN$lI2s} z|7m|LSiiDh}xd<@6dQY{GX1$6fLp$L;v|Eq49q@ zUR-Xz@LyAZNa$_n{TRAruD!o9|EJ@(6LZtt|EVh`j&%R0u9}>{9nBBe`@Ag;s4akkHY_{nIDD!Q?q_1 z{x9D6ztD&MpKc%i1plX=XZ{WU7jOKZ&R>yf-qz;-sf%nqTju|%b0(y_|5H!P9OM2k z-uORtu00<3KQ-%XemMA)aQ%3_Mz&tCZcjmay8Az!p7lQQe`-7<{!fi}#Q&*Tj~D-^ zo;e}I{(U(+H2WL>r|mv}Y}47{`kBYq{+q2;{SAe<^R;o)5HI%=h%9R_&=S$dTPD@Q_r`?|Ea6(^vwTL z&#~>y|5ML1zrp-J_55k|{x9D6KXt`)`~9lF)p3b8LM_{GYliH`o22y39P_ zWnWwpwsZgRf4YBF*>?QV{GXcne)zwJp6>on&F#hisqujLzj!nMPhCAd$NgWtFShxA zYWcr-MMx z&kN-5DZc%`^*r;l@zW=F^1mnl*G~TTiTSJX>+|*IV~-E7Z}IKP^Awry7~h_J`s7ab zdC8sZ{gONR^vRv0$r(!|>m^|D*ALYJ4E` z|1KZ@Tlar7^Z(SG{>sfOLpN#ED8m0~dmCHt5C5mjGUl-*ZV)6KC^9?=#Qz(>)x{Yg3R|TP8%Gx zvH5+)qu#dT`!D89Odl5YJY?(j4t&Sg^Tii8?zXzFZv1=h{bm;BMStA9x^8jV`##^V zsA87;zwg(5;Qnt#d7=A1_1d|m?*G(F=aswvQ!koR;{H!vY4iQ?f9k2(~ ze`@^SpI_fy*R6jq_jR3Y{hAT^4bA+#jgMU(w$t|xZ)kkm-)^`pY)|RZH5%Q%q49V4 zKV4tD4lUjPshf2;%IE*7n|EyC{_p>z>^`8Rs_*~*Uy6YA-h1zLmj$->-uo_f>Ai#W zs;G2Ckt#)cFDeSmswfr|L9u|EXc7%E8Y|JLN&fHGdw9L~&Yb`G=KQ|r`4zIQTzzhwNKpU8_kWXHkQ)E?>Q>`akaPRFTJ1 z{2#k~)yg{mkKO8i@A|*&ZVl?H|6}8PJ?8)Mc+v2GY^-Mt|HsC9$MAn_%oBwFV|S7D zgFpW4A#1EBjP-xHy}RrW|HlrI`GB=@SK9Fp5FeTG+6wEY4Qe@?29~vaonGhv@%TH7 z7lQv|_qxBD`ad>2Cj6hf;s4letKYBwkKL(GP4$0lyk6k{*qCPr|HsDT0sqJQ!})(~ z`ad@PAG^1BKlnd3)(^(~zt#aQ)&C{PcKAPbY^yfv|Jaxh2>-|KF7r);#Q(AB|J)7# z=Wh5vHjWST|ExQ-QvX+)+DiRjS84b^Hf|sOkKLt}%uf~n_vE&=>i>F)|JrgZsPuB} zU(}Ng&&qK|{nFpMq;Qz?(trDxKA!q7^?{Q{j(4WFDC_u=@#_D!9{*K+VD!+@I{%M7 zB-iWz*aLd^Q~$?q(Xy@jKQ`98?ej*TQg-_`-PHfF;Q`_Q*q8^1^?%uITX%5a|JbdY zcUJ$$A3JAsgwyTRM;@#h zt3GUekorH&kkj>krCTq(>4_*jquvkayKYT<*Asg9wAc5^`K`n*H>`0!3;vJWvA)bm z=bC3q^V912;O*Y?yk(8g7orzkwZ`W!@PFJtQ|4d5|FMTnk5d2V?klHX^-P>}N_|k~ zv?yox^jECYW&Oy{f4pp$PZlqjdFEy71UVo6Xw{ePcyay`{*U(;_Xqxujq|_oe{8I8 z4FAVY6<-Jc$4--Z8t{MYjL`w=|JXQR2>-{%`B(Tqcf>n!m!4F;XGhOer0_qb30eDatz&hNwj@%4hwtKk3G zcz)sk+ztQ7*BkuWg`Ed|x_jOMYpg%DtLA>|#2Fz@?br5M!+S1Yvez1~ub+bUSmX1u z(ce8~ohhCV{*SjGC!bfs|FPrc^9lGrHlAPjzoaJ5s87t5&jaB9*okucb)uiN{gcF_ z!vFE|@N)2fY57A=-pN67QB z#k0hEz=Qzj$EZct86*41?<4bl`b6>r*6^qBfASfK`odWG`GEg(H~b$P9`kz2RBNm+ zcKq5T>*2Fy-lzCKK7R09@PBOjKQ`C@bvOJUyFfm#!~8#XzRdH${69AQ4%Yu=!|%ZV zu}92Jl+OdQ?f8bxj+f65GOcla^}k579xU^|j`T~l%fsiu|MB|ZIpP1<$>O&j{W``j zj~+KAs;tE)-QPRh9&bDzqtAs{<9Ol!`23>b|H?W+{U00iSsK;tYp;(&nWqQ;$JY-U z{*Mih_et}vp3UzZSMLW82>-{1|4Uuf-m|gQarJ&!-wpnc4gU=P_wuG=-g$rW@5_t# zH}`n{bX2_`=9j?#v4_a*!~b3Ad(`Xy#HYglu`}fU!~e1Ic&rVn>G|8;!|MIux#0iU z@PY7u&Bq_M^?Tv}*y-ZcJi9A+nmm6qo=? zu`}iV!~ePavp~XaAG<*O9{eA> zQ2ZYJ9~<*a;s4kp3k%f$v6mlQ;S?4n*!D+`>~`+n?P$IJ)B*K>p7Wd32c9{$PrTr37ue@c z>{tKyZMRM80na^iO#L7G+2>B+go%^$@<#Q4FFt?PY4byc;PV9=)nmPX?RD{hD}q~m zyFoqRt=C>t|Cd&>K|SEx7cQv(W1l#AO#L5w$(&3| z%CS`5xhbUa`t|DjGNp(9b+0wP-U;+3^s{iBlJ+RR0|M+@ayudsEk3DU2v2(S@@lbZ$v?S-Nd2faC=PPE4 zdRuGEW8U%m`_>8a`_AB70@VMp1I0(c|FH*(?}GnhM^27X|HqD*ChuqB z|JVi7qSgPgb0&rB{699nUj+Zh#^VeB$Hw2aJxIY^HkB#He^?&dEzLPvB!MpzNz0O#Ws{W7rPkA6! z{U3YWjCl2b>>_#mF#pfp@PF*&nQ_jX;*r*g(_`fO52LN&x880)&KmRJ+Af}G_Xpq4 zg8$>+4@vTUF!(=qmi)bi`G0K8XM_J^7m2Ttzi-0$`){HAJtKerSi_gX|8f8Hd+YzQ z@%X_1u~Q#NQvb&uH78#EAA7`1um5A?@qzzi7fkog|6{`+KKj8L+m7DeV4Y9H|8al( z{tf@fhL3~)W2=V~|Hp=(g#Tm1Ps0DPvEDM~|FMV4;}8GG#`6&<{*Rp}zt6+}v2ng2 zrPp?QJkc#D?6 zd|+KH|Gtf>_>uK^@$B$_e7%evAM8|JdfT>Vjtf`+$K%6#zVLr+_(1qSHqOVu|FQA< zf&b&42Kk+AP_&)eQJD)Nn&>8Oe**ZkLAp9TCF9*x|!bb=EW*smjK>Z)jZ}-ga>A?T7 z2d4E^|Ht#UUBla{|6^y%`oGIMmJjFozk=X?@*DMwOZY#3kKyk}{O4H>5$^^6x2Hj4 z^?>kO@PF*gVDTm5|Eg7QqW%v)4E~QDFY^N7|Jd*`@PBN082CRnK0k;5W5aX6|FPlu z;Q!nW|HsDt`}p&z)|gKP|HtDUAsz(&k3CGTAO4S*hcATxW7Ge!`^kJo%>QE#7!;`f zkB#Gn|8qC|A3LjmAN7B{eavTs|6>pC7v!|fTwpysC|La;FF!0KT>T%rBs@y}A3G*8 zRQ(@2EI3I0ADjMY`lKp|Jd+=@PBN~PlNws7lh0F zJMn+)Y?&{J`G0KOKKvgWx4-ATvc~J@^pI7y9exb{kM{?D3+w-~F~1D+|9E|v9|!-( zE|U3$@PF*QP+4zR{2#k8Lf(JH|5=Ma!}`B$_$T;3Hf|sOkB!^M{6BVq+#dX&yD|Td zjmHcAkB#|!duFY-hJS=##OVA#c6MBh&i`{a{2x0hK3e@BJ1*Kg|BsE=$Mm^R*zw{1Ei1Rh8js(`)xN!_ z!IQQf^XK6IczuO({P2J5qDZg*V;4t7tN&xeC&K@+%P2y!%Moi`_Civzy0hGS&!ZIexEVW_x&Hf*S+2U{`mVv|MtH>{*RCU z?fEy}f84k4-~RqDH2~tN?BB1HK7Ibr_Fr!}Q+%}h^8P;1|Mva;lYiH(;XAMI|F!+E z&wu`3jVcw@|4rHbp8CJ4asmwgkB#+!G5_!K(RbDVVLl-IAKQ`dx5EE5e(r{M{a-oX z2LH#V|8qC|pS$7zczy7J@PF2F{%!vQCDt{o)lmP(M zT_KA`SmXQ14_z8j`pP5k>%70fdUe(RmF)RI{a-@I4$ePUjxH^~<+ggifPP(^i=U4v zP2Ts3dcX9v7-vWD*wVkh@Tq#g-1IQ@f9zp}3F`kIdG`UssCe7%F9;&#~zyR z^?&TbtQ7Ts>>;UM|Hn>~d54()$Hu?6@PF)(fr0A(*xhBlM6CZC@Y)~M|F!AURsA2k zRjXF&|Jd-M6?zV}{p*U~bHAQzN?kfNr}RJ3zj{ia`bxemRn7@)H@EbmJ-?~!~d~s%6z~3rq8nW_pIpK+0*U%8`i4rY`FVa>Fn}Nbsiqpi+pKZSz~?O??2vT z+cBT7U3ytJXwU%X+HE^L*UG@M#(KZc9NJ*pJ2tMT{%?DgX6gx>H>%^zSh1m$-KcJL z=iJ@(*41iPQU6z3v$=Z3`c3NS`oG*Cz7X^O*qDcg`G4%*O&h8IWA|#((1HJBH)+yD z{U00i>q=Lxw(aG_yTSi)d&TNC)&H^K-*&(DXeo~mxBtTcSKsr0w*8*}V`F|F{GYqw z|Jaxx2>-{1?}PtibNyd-hnB6>|FQeDZm#~1$J?!`%nK0z$Hw~1@PF*Oa>5?#|FS#D z{89Knc2J#q>i^jI`G@~w|C< z|K@%9i~7HW;Um@mvFZQVgZc)l|6@1m*+cywyH4j$>i^i7ceneC-lgo8?R%*IW5ct- z|G69fj}0G(`F}iKG}ixhckqU8wm+^9{*RYO!~d~y`|yA4j_tds|6{`gV*Vc+mxupz zH~gQw;s4k;KCJ)C<7?Q?JO7VezfBkQe{A|ccf4ML5DpYg&eD{g^zwl z0RQ*t?UU;NaQ+tl&)x8UY@DAxKjRHg)9xqL^I`tq*uJk@7fy|G8vSs^x?oDA%)@%s z8tWOs|MBveSJ1xCWuLzJ-AmRvMe8hC&uZd>rPlbo>*FYob&8x1 zOO{W>dHK-MeboQ)@rsbox8VQSY4`je8`lT_$HsQ}KX=3b@%hI2J@`L%+K682|JaEo zJ=FiP)5i8y|HsDXbMSv`%y)$UV<*Ub5cofL!~e121Mf^YYMnZ1fcihap6LJFy*%QO zz22}L{_ll0XVtHw;s4n1f$)E9te*@2$HwOs@PBN4-T?o{#`?JMe{38t{2v?h2jKtM z(c``TkB!%Fk9W7(cKE-i9^Gn<g0F^>iQ@4EP?_fq$Ur_1NPnE&T)_&;{G%!B*n$yJ_mn~$lt%9t(Z?}t2O zojxnXIp5|%>rA=64qvXYPM6P*;s1Djn2++whs&&!Wd0uf-(%N~s|UpTV(@?LIC;F_ z|JX5Oy#CMK@PF2F{=C}t+16N(8vajaB&Y`*Fgi%*|FJ{l{5Sj`8~zmjk3B@Z7yKU| zKdi3_|L1PZ|6>oG8?W>K+ztQ7hG&BRV`Kgo{2v?ZAH)B#lg0DQAC^~kJTl({{*T8u zcy_G%KX#sYJ@`L1JQ(~RuMa*5{*R5@KQa$1OLa%r_GglA>#ko@NDpZe7x!Z z*zkq$e{9U3ga2a>m&Ye$b$~tpL*@A4|M>dI6<-Gb$Ig+*AO4S>HbY)N;{W)1OqnL< z>woL$3H#!xdO!TUFD%#IGqv!j`aY~r_QAR~*7*Du{*T+^1`0 zPR8$zJ%9b}uzJ5Dc|F7bvEjM89jxbRJngW~_e-4jzx@PE90ynf*S+}-o+IqM>sU-!ZHC#?(b&Hv;6@PP8) zwjGW6f83rg`@{dS;nm>(*m!<1|Bsy}ei8nUjh`R*KQ{a|{2v>>68?{kd7ha6$A%X! zxIEb!KTiiEMp;M8?cKdpWE~-%FeW(Dy2q>m@_5Eu2P}~F1OvmYarvHS1FYla^#T9K z=Lhd!SC6-`?dYc68e8M>6i;KFFOScitrahgcyYgaAUt2-ImP z{*S%&)E;Nr_xIWU=Z@`F|5tosqk6#SPVUG0!WY=bP9KIBv_Ac;*Z+y>QXlyIxl>pl zIQZ1_8`J|{d*fC0f4}^7z1RO;d)paR{Aw`!#uaR@5W@c8@~i6qx(;5iKJe8u=hXkP zpV_`i{U3YrsABbhsXwk$|5uV;sQz!pqwCcFg?I0-{*T>WPXECFvElXL|9E+LK=?my zm(z9X|E%TmHHv>K+b(@Nt9+(DI(qYauyx7sWW0Zd^5?0q z_y+ht_8|DQ;2YNX{u2Bjw+|NI0{_QOpB}9KkDVdkw}Ag+qSXJfG2aaH|J;rFf9x2U_XYpQ zjuQ_B|HsDnVc`GR@PP1t>|x@);Q!b|#b3eyvGIKf_&;}x_x9=i$Ahd3#4o}B@%IJz zEcib*{=S($JKP%IM}z<4cKp2x|HpoNoCpx6s@!;>L zqKDJ1Gi2VR_;%~uImynM)Ew)4@qR;2fGj(9BiKQ_KkC*O~<#`n!+e!6w4{CscxV5N214Ea7u{fDgaeU-qh zRX&aRfBgNua7L8+KX+sP9~<)q;s4n9J`wyMd+_Wyo&U!!o)xS9k3CpkZ}5Na#{54v zUVrd^Y|O`l|Ff3g$Kn6jgT+^VG^_ifA~K(&NsmSvGI7o|FN+h z{*OIsa=7|G_Aq&Wl>fHvINt;R$L*M}Dznb)c!FiUS@=I5Ux>_8!~8!syw;Jlv-WyT z9M)Ii^g{e+d7_4jU}zV`TmxJF2*w`agD(_&fMN zHhdra9~<-T;Q!dz-tix=ThssX{$qVz_&;~U|FJXW`3YEY&8Ol2`1s@bga2dW`_S-z zY`j0i|G69fkB#pa!~d}{Uljh2J#1ox`aixthRD1{_&;vP^<(}YJ9D)7s1~2t@#6c% z)r&s0PLuPKyPo)iHT@s&Z>p>pQm*JTd%Q3Yar5J!Tf^(Y|MBrf!~eM({*OIG=JUe; zv5UpO!vC@JW-H2lG*;s5w}rVj4qba?o#PxpWApVqm>y_{43`6Z0!U$P3itN-Kq>5QCy>i>AY zH$J(m`agF6K~2^F@%-(eu$IohR+J0p`9AnH_&;`zcqaGf#r~ed-Y<|7@iGFL8i({a<<3x5o9s|MBu@%>QG<&%pn&V`cqMtpCf# z`oZvj?uP$k!^2?yA8#M?2I2qMSdSV0kDV{x4)gzb`CRD{^A_25%pY66cCj_q-`%rk zi8ahz8mRt{9f#M0_&+voAO4T6^C89mvEhT@|Jd+L z@PF)_5U>AZXATTi|HsDT3;*YC_&+v$6a1gM;s1DlupR!7jo1Hsw_F`QNc|r#pA|Yl z{U1A7<~hOtu`{BB)&H@vel7eTJ3}rH|HsY>3sV2b&WVtD3gZ9R@PP1tY|NK~|6}9v z+9>{yjd_6Ze{5VH{*U($^Z(%gxV<o{*PT0 z7w5Ej^)b8r;Mh2)Px@x-;+R-n|CjrxC(8Vbk&oNjC4!eD_ZY_x<-GHNtm(9)4cj*YDr)gZlbxj~##sWo3RZZlJHjP`l@?AgJf4hIzuI8QpH><_F>i?<< z@Pq$j*A&kO|My7O8|we6%lSU|KQ{f}j-cy4{*PUuLIs`w=Wh5vcfWCk19>Ba8o^B|5`Pj|3;6rh8KHzX^AyFP^&LWO8?&Yef53= z8#I&8XZ?{erQbBa?RoCUx5K;i?XLdsqgo%U|4YhFbp{L@SK27} zQ}untIjPR#$HrQZFDX|4$L+I=^VR>cXB6b9|6^xorR)4ZcD(%jVf|lrR(yoc|6?bG zd;K3fBGfzo&)t~+$F4lEr~1DNJ^!HoBk{U5uxtdF|=*P*5Cp7Qv+U+)cMzM8x1 zi?@RR8#4bF^?!K2zP>u!8tbh#|LZL4%J)}vQp%Tg1MzkXTFkWV@K{F%%&>;Pg8$?7 zcb4^^-M8OG=Ci^7eR!v_dO)n#3jfEhSFfJ>KX&zo_0<2dYc_76{*Mjs2mi;02mEWZ zvZnuQ@l6x;fS5-I|HrP?tgdr+Y+2W7QD6NZw`09u_&+v09Q+?USiCCc|FMI_o5BCF zYl{!W{6BWZn$^_*vGMZ@|Hp1zua^2hHoW7CKRi;ly>Vlm|HtjkS~PSjUVhlNqcQ)l z>3;vJYzJ=HSu{*T%&i`Y#Z_(0OGwngU{;Kq|+qPE!$EN>d!{1^3UpCg;h5vK+19RqD_vzGD z{okRx&C~<-?&$S@Y^=u%|Htm!&O85)jmIDUj}3na|Hp>+!~8!s)Def3Z3|7MJyp#G0NdHfXhe;Kdb zRsT1pWUTr>cJjzEPOIR+Qa1eGwSoZag4}#((VTwPK>_`pZkzjBSLo5rxqZ5iwbQk; z^YA;pt>OQIzUgHRfA?k8vZnvbYxT4GL+lU#$HsQ}KOP?%{?FZ*|L1P_KlkO2-R^AL zar?!;bh7TzzN=HUVOe);+u3=(Uq{ij=8JRs)( zvFo<=&i`{a{2#k(^R5o&|MB@m!~e1GZ`DctAKR&1OZ^|aRh6ph|6sV_|2ovHt^SWa zpjmnKf9%N_LF)h5IDb>I%`Fc*U%o#I|Hr2P+kNAt`ai5^JO0Fbo)+z8Mx1y*%x8lC zV`F_<_&;ko|Ndj-JD$|7C)E34z90M_8@>zvj}1?C|JgS^Z~pzbdO!F;_&+x00mA>W z3*`IQ@PF=x|6}9(hTs}Z73>&YHFV60_#_eyJ{IoUwU-#Rm)eFLR!vC@1JK_J>Sf3dF z&)x8U?Ci1feP!`~>^zxAg86@Je19GOkB#-S;Q!c|Uk3lj#`;2wa|Cf!=!{Gne@GbCvQwxr&|I>LT;{Vv# zAO4S>IWtuK9~+-H!~gO6@c6_3u|tRVaFVt!wT>U#Tm9e58;+?5OdQ`={U1AIbT6I% z#||6Y$ASN2(qEAW5pA#!~1f9&z%VOD2Mu!d(D z|L$0yj?WowJyg6*hYw1uF%Pgp!EkH%zt3+CvBu+DT3l=mkG12|0&Dmo_&**GydL}? z8<+1tGSeFK#o+(A9S#4-=RZ^C16{w9Xxq{7f7~Db3I5OB@PBOhCip)-zBoS2|6{{9 z!T+&yWj)nl6@%>gEnb|Z{*TW;)@OtNvld?k|HsDbt=#7B_WHu-xA1>_eI?50ZSa48 z7r*ya$35YAy~F=CZ+%4l9~%CTjrF1L%xme{GUKp%znFXekDW0-K>c6+R}ZQGE0+0q z@PF)RSuY&^FJ{mo^?#8vPYM2yojM~}{ohM#4yyl4pB1Y9@B4BG)&FJ4^}+wK;i1Og zSIILu=YV>@B=Laof9yn=?+5?K#`>&{KmPsF&Nueo^M3K_|H|6y|JViM*ZFixW_tdo~$1ozr#9Wf%-FRc($LfZSv_Ib=O(LW5WOO{^ZEx3IE5&{6Y9X zcJ}f#^?&Tb$H8`b{}d2*7>qfWTUUa)(Eb9Hhj z>qk#MrT&lGPaWPX^8#PLP_Oz%^@7ixg7D*+4 z`oEK>j;sHxetNz7Kg{!M^TUeZ?-JJQJiwD@PO1O9`Pn-4fM=gQr~Z%q!V51r@6Bl+ z!oGU-s_Y+Y{o&QO)&Jd>w@!WFAK!al{okE$)~f&e;ElI+{a^N5rI*$Jz4hQ)^?=t- zKdb(aeetQM)&Ft-l}|n8bSt?T!XCYJsk7+(U#znqS)=}smmj-xxB5T!*29OLC!(u` z^7sxv|GfG?_LgVQsQ+URTRdO=AA82UdFubza~Cgm;Q#n|PI+{l`akx9E!)-qu^-uY zz{%;F7Rtwa%jt8@?D2Wl=g(eH|Hu6=K3A&#kNw7>GwT2Ne7?Nrs8ibH0lWRvI}SM0 zdM&j+wO!{!hI0S)J9er6V=q~=PW>Ny)7n+)|JchH%~k)$UbuLM`aizD7RkK73f*>v zvggRWzt_+2vD=%yV5*bA-AU|CFAAg=Y7dKP?$L>0$h5A2s!H^E> z|JeD1+pGU$s|FI)veMO`Qo$W{V$A<54^>d)lIGO_fCw=|KtAf8}NT@tiK5V z$A*7=pk{l!e6;-i(tc`3>sXoR2miai8_yXKX$=qh-)+&>xct$7$68~aoUBK0t?Sob zPO{FNF7rji|M7S*zYzY<-SB^G+#mQqHm(o;kB!@h|8uv@%eBV*OZY!-PZkeXJ$SfJ zpWj(xog|MB{2%wn-!t%k>}2tP7hWB24bL^E^CX{^dA`=g^7n-2n`u4`|Ht2F2g`bz z(=IKx&X@1k!T<61bUnkMUI z%ltq7K9BjuhpVkF+b+-N{KPdroxEzT_0U;yPRm!?gig(wa%BHC-^^Z$LkaRkB!$i z{2v?M3I2~=B!54`|FQFAy#x3^_TbUI)&H?edmo(<#QW4&d4V)#FHUwMCp|6{}V!T-4%{*QmZ;r$i< z&)u&yxMZC-roZ|>ULHOE(NfzE4|wsF7p;?J{#vd7zGR&%9uV{Yc==+v|L}iooWF$s zW5cV#|G69fkBxbDnE%Je1MAbm|FH{41v>D5Y}`NiKQ=t|mC|>tb^VXuuUlu!`6Bo~ zK0ok%3unJ)+tD@8-1O<)|ByHId*^qs9sbXK`Jkvtp@Dvd$OZ*Kx+*t?_z*|KsuI$a=l-f9z~o&v)yW-&!Zi{_uZ%d}0fF zI%9Kww2seer~Z#WuOab`WnSz*?dLT!zMlF&o{ve1s_B#u|22#q8(!ZDp8tCo&tJ!c z)l>h+^S>d3TB!fy`P=Z&*6ROwzBD7q*H`3jn;7crTav>geYV4w!2gZ-rh(1- zga2czKNJ7Q&Vttv|CjPvL-l`HpBD4~*hMlQ?d5mJ*#4OR_4$`$t>FR7{Wi`T^X1yq zn&8t>?Iv0$g$C;UKVCn43H%=$>+S9tHpTXbZ-M{g@#6U5|J)7#=Wh5vULW>{|6{`^ z!vDD&{?Fa;f9{6=V`E+x{2y-*J`w(pjq8X1b2t1SFOTi;f7}iq1OLY!6xd(=pS$7z z?DBp4Ip6sKllEa|HqC9_WD0|QHadH6aU99fDaY_$EN>d)BmwCzYO#L z*m(Xi|BoFb>y^U)vEdKl|Jd+`@PBN~--G|-{mT*G2mi;;4jZWckDU+^r2dbWPl}Sq zU*`X@(_$jk|FJX0i(&qsbxf4{KX=3bvEkt`|BqcHz7775jrC{ue77ci&ad@L?>|;O zB0Va?xiN38HP)kr|Kt8>_&+xGKm8xyhX3RC?AUnqf9#yN1PA_)JtRKa`M%>O>!O$h zr`+kXhM%hw{FrSYoRFaYkCz{j6s!J^4UZRjYqRZ-`btl`*`ushhe`CFM z_x=(6eLZA#nTO`y?%)4^^U>VR)u^KL{}yb!uKusF zEU*dx$F6p7{$Kjxchvt?6&?ov$Axl|I4l+`@{dSae4SZ z_w~X5u`7x1h42 zrCa8HsNN6r$a>EnS2}9pE%ki?J$gE`kB+tO-qSn(kK2<{;?@7{-}kZlzr5U7^?&RU z!!y+Xv8N99&i`YN$xc-N$IgolR{zJ&jvAo;kB#>OtpCf-jFEZeGXIYqF8gEtAG>d0 zH=X~-?%cJV6SZrYZLd|Qs`|ehn?F$xh}ReV9~({UE40>~eZO1%7%>NtsP9yb$?ZtP&|FJvNZ>0W@-L_7B zo&WdLjmGN#us{4C8?Pt$KenzHdwZQV{U5jE^#=dPhChY>V+Yl1qW+JK`}0)i)pmT< zs#SBYZ-3NU-!E#FH6D+?%OA1r4I0%}|HtcV(yYGvKQ??E{2v?MFD|gGG2ajV@4lN& z)B~d7|Jc|c^Z(fGTQzZ#|MQ?-ALik~|MB`8HEN{(kB!IoM!-;}%$Gk(# z|6^CGR7w3GyZe1!|Hlq*+{hU}ak*U|jtBma$A{yE|6}9%hW}&Zc;Nroc>FQ{kB#RW z^Z(fJi&+1cjd^;Q|Hr2PV`Cm3{GYY>J@`L&!~e12{jmP;qz{^!|MLXT_Srt74Yrq1gx z3@F|D#t-WKB6|6|V`JyHE1d*awh>i>@a_eUT9$4(tNQT-n~rl>^yA3HxMPyHV| zuy26+KX&adUDW@vYj*0S{*T?UT@Uqt?uP$k!_RH*+|wF9FFLM=b;C~H`G4HMLC4PO z|Jd+&@PF?9_r)$g4gbgO^nYxuM-2bR#(Kr@e{A}{fP%Z~6VdR0?tXPmJD>gG|9E-M z|6{`g!vC?c9qa$PJ8Djg(%RF%m(K^k2*>)z8Ba8~Zr94Y{x6^3TCLlv|6@Bfy#9~f zu0~bot)fpoH`bm|pVw1-_U{cpvF;sE&*|~rZR@POKxgRsTh?hqdOPcqKeEn~^E0KD zKeWdAzkhvq)3f$-Sp!zQAHLuFbfxz^p8VtL`S5-B`mf%w&J&NbV#Rf9crN%q?vFmw z?`_Y#qsP?u!50<&c-0#7#^C?B9p9%eJ^Z>y&Z(*gLLZy(nl;Y9Ztr%*ryu?L6`!7W z{IWIX8;qOsvNh)0<@b8YI&Om3|M7US9%=7hFWT|L2g3jH@xbRz@PF*+qAu$H*xifT zssH2i6D&Ro^Z(fNe{8JR0{_QOl=U_+|Igj%jl9asD3ukDVju$Kn6jnEwI)$BvcfAO5fC z%adOJC;P+yxf}kEjn@nO9~;M)&}pA_j+|fr*JpdIvt<30quX{{!`BVYdCI42*4$+c zpIG|Z4(k-m*I2gQ)gkKtc5XW5olhvo3;)N)=K~L(*y6K)|8Y-PsfkErj%=VeoFK5U&O{tf<* z+q35;==?u6KA(jDW8?EZ%>QHO$@2~W$J>LSg#Tm5%KS+9KWjN&`FzYeTIONM=V#Xa z>TlS@PF(~@q&vs zX4w71JjUA%(yTM*h<6;5V*96Jo}TzWULFnq$Al9;`M;|>JX`Lhu|HsESReaT< ze+Jw0gZXGH77es663+$y$LF_bak~0HcHaDC^?&RfnWqQ;=Wh5vzMkMq;s4mF^8CX8 zJt_0};Q!!{;s4(F@{sz!WbwDPzH04RDP9lr{lewnANW6Zn7se~GQOE7eBD9yev#sL zG5?R9FlCT)vu;Drw2BAS`z6Tdr|^I5c$r`G-2U30?gaiv@B zcrpKvjrC#cO{n5&+;+crzMsrzga2d0pTYmR8~%??{}=z{)9U}wnE%Jl7SDBh`d`)nE&VQ z+h1O}6i~8Hy;*x+gR@gw1R8;3f7Ih<%cZ_9G^e<|ZOs1MwD za+~@;_VI(e)c<|wY*7FA?5Tt5|2A)3um11plivA%>;vKf@qe$>TJQCLr;lKL;9&Og zlZV6ut_+qLkoP>`0jJO3Uk$DvxlTRc0l7U{FF1s~```ife6k8N6Y$$nE%IaQ`AHK zAAcS@4DF--kKMnxkNQ7$Kw&TSf9$}b-s=C@*dO!%*iGg7;Q!byM#y@1;{Vu~4+a0n zj-8_OMXlq-2f_bwdz`FK3jfE3|A+r$!)L+&u|wtiCJpYd6UO@+GEL@tjjv}7zcBgD z2G;Nw@PFJN^NryD+&%N_=4CDWw@PhgohklLJhe5xUjYBd%g13oPw{_jtnYgLoz6Zj zKHEBZa;(#3V-M?;DRDCIwpUq;Us{pX*BbNRWZr98%j5HLy&!9Re`3|Ff!6eY{CxpF z3jU8hQoJ7gpS$7z*z|vF`ad?dmlyx%Zumbo=F`Fdxf}kEjlU1!|Je9@68_KK@PBOV z5C6x;@AvS3Y|KxG|6}LN{Al<;cfZwmj%#^VM5$Hwau{?Fa;e{4Lz@PF()nLiKz$Hsho_&;{O_$c^4c9yKC z0RP9%ka_;_f7bH-pcDVuW6xKnoZo@})-Q(t<|CP#=kf4e{8H@4gbf+_tgr;|GE3C0q{-*>vU``)%k<#tp5$Df~=?4HiRO+VSs)1X9|*Kqx=b!22KC%)1z zVLaaw8rn?#AJ0z@3UBUYE%_~sJs`BHv$ynj>wu8{+=Txx|HmFKo)rGi?q7I>`agGL z{vR9b(PI5yULFnq$4-roRsY9M6K@9p$IcMnh53K%OzfY#I=sQ1dg}S$=OX@4*2VGh z&h)WsY&+)B!T)jpY+1h-{*R5{U1AD<^{t4v2lCwf9&E|@sBe9k3Bq5?!V0cV;4n-ssCeRJzw}gc1o0Y{vUg& zcsR`eV-F6CQ2)pKpC`{B{GYqw|G0mitZxke$1aXdRR724H$5Ry{U19;<`u&KvD3xt z!2h`$^Z(e1k-qco;6>fFU+d%J(bKfAa4xBvUIfBVnd^Y8!V_x_jv!_S}l z`20I-kj$TS`8NNC*L83A@BiihF#ptjd3bVn`_BVR!TeI!@kI5L_p|?_qXT^XpZ`2S zfA9Cdx@uM5`F`*~?%Vgj{QvTQn6H-9a#HC(DqWZJi?4-ukk8}c|CTj+M?GMzs+FAe ztH)boePH;%`kk+-2gLfo*}spmu2Rvv{_mjyZ>tBaUCHbJ*ww`kE_`8>?O#sT?|}c~ z^`YVa*zkRr|L1P^{cR`fd)yr}u5|7%H$8o;ycHfO^W=VgYOFQZ@BHsaW2~FB6Q2_{ zzV!P$AFB7m`k3&4>>eFEssCel?b=o6|FQeXdeE5v*RT3*^?!Zi!`1(>L$i|9|FKh2 zlXU(cJ5t`Cvc*TT3&ewO8#T(hFnW;sKW!AeU7JdgT_9Md2aB34W4PB9uV{S;Q!e0TkwDGE)FZ}Hnri>8=)oWH(|Hsz(pyL17nEwa=$F9++zWP62e=S*G_;SW0c6+#e_&;vP zd_MR;cF$&woK*)`S@)3jdEx&KKik;m16E!0kZp&rga6~@>$Pa=e6?<+9Z$6eb)9DA z%erBe`*rQG@HEpW?kH?4gYvKRcZQHj{ z|Hp18^9ter*bVDcQ~$^ADDxKK|Jay63IE5&^9BFMhVO*`W4CVI+F5&TzBT6Q!T)hP zJRtlZyI1Ef4*VaxuXr-}zuwO^@%q2^9Ub^TZXeL0vjhLf4rtR}*Z<}I_qFuS|6{|$ zVg4T*mxupj2e$Rj|6})V>z)6{hWESn>15l#tE~5o`F}TFZ>k;L$EF>J&*o&U#7yggkvSSzZf9w|Wc)|a%;o~s>kKMR~eBL4R|Jd++@PBN0 zK=?m*!~e1A|Jb-a_&;{@_MO!Kv2lH4GdtLJbi=9beH#9c`{VlI|JaS%ch~uUY|j64 zcgF#(?D@lX_`hzazg7QNvqLxaf9(5PcXWn6+sw9Cme>El`OWS29PzVvwluTu+Ng&5 zzw$}P)>bX{G*;9U9zN{U5t9KS2E-J4ntK!vC>DWqpZ9`hDQ}_pW2={bIyp1SH(_ z^k{fYy&u*`{U+dDPv?n8)$e7=`JNp=UAN8=UzU9C9cz3Z@Y~F5);RzF!~mfa`->)kB0waU#4#pgfpf9w=FpS}AVk2U-l{2w2$Sou5(>;JMbAMnE5i}v`!cftSh@y7SLG5^oq z@PF=x|6}9(;P8KJ%p=77KQ`98f&XLU_~8HCjkPG)I3J1crm_p<`NFv=m_PVH`ad>4 zkAVMU)(?gMtG4@u`oCnEHvs>~j+5tSXPy1FKc1g;Z|$>& z_k{oB{y4u1|L1P_KQ_+K!vC=`{}KMrT0Ree|6^y12ZjG*!{=fCU#;Ym>i=?OJ_!6D z8}t9*|G0m=_(AwTHvONw|MUDNd%Q7k@%5P-?Ddo&o(cZ1>4d{x|2Mv;^H}m~Ptxay z)cZxv30D8dPLcU^@PF=x|6^nQQmp^WPLcT>@PBN4{sRBU&Xx69A3L(#8lQi_|M7Sd zaei0)9~<-g;Q!cBGJgU7kKJZuFRZU+-AUd*?#r5Mog+UVnExlAp{NfWF0U{6KQ=xO zef6VhJ`MlJpVwlUrw9MXhUbI-V`Kgm{2x14d<^^_dyIHC_&@fj2NKo)v9Z1;{2#kO z{0saa8{P^2kDVj)-!4C#YsZWAUE9>iw$73Hg7AO5e_66#FZ`do;s1DjSbueM%S79b z{(f(qb*jwQf&b&>u^ue^A3J7Bp!z>|!~gO5$&k<6;s4k<;@#l?*wG7;)&H^M7N@EI zV<(7T>rkziy;W>*1O9JP{sHxW0i$|2ixxNb>=3`#=+>_Az|lR`|FL7n_HsU}SF#&YcV*Sf9{6=V<(7@ga2bE$vi#r zXO~ir>`{-FE{|8+>`gum|Hu7v#m~Y2vEc#lY+Y%cy;$byiT^9xj(K@=tdnFu-^n*7 zStp8*{WW8xb;i;}^?$rP8vf7S@PF=x|6}9$;s4wX|Hr2PV`s?m!~a=}*Mt9acg?O9 z?eWNx?MG+ay~xKaLtYOd8~;JL~7OB^?&X_Idi)H;^ZV#39<$wET z;>8b=H+ZIpJ{q38Hdp=Mz%SOT2b{HOfwQ?r=Zow|4sLLwr&qE*ym!0I3w-^;cv*iJ z>jz^V;Kq#)UU>WNI`x3tP8`ztf4$eQQxCY~)Dby<;W%up4-Ee|ywW=LfG5t14;24* z`Kh()|IQshC|>P~_2Ioc)cJ>bc+=fvAR7Q#L)ey`ex`>ao%KkpO{JZF98!Ugqz-2c)=kNQ7$ zspm!Yf9xw4OV$6eufFt(`akyd%P*<_bN8ba>xc4qORv1>oD6Ml{ha4KyrcEiGiTKQ zasM|@pH~0Je&*OQ^?&TMN96IB^?&*J9^AW6{U0B{-P?Dl|6_07`lR#Zp`oGd)f?73 zFZ^|k^|CdqoZUC4+V#y{zDWHauYcV`kE;J;AKiCQ{U4w2*S73b|HpoA)mrs`>`7}@ zIk6<|6?zjJ<8dbv)3*^Z~Abj<>CX@V;?BO`(r47 z9)?ZJ!uzLnlFa{=_g8EDz9v6!*4cBC@&0U`IScP6x2%I@z8>cP@%jf%iB|u|juwxH z^?%thQ{&YCu_LC*zc(`fj~z85LH!>)WO{;ArQ5Hee1AZX`tyIR;rTv$yIdHz$4m`( z!I@Z>A;_( ztl`5j|Bt_);QKz9|Hm$xK1lr^d#Jp>!~d~MX2+=iV-J&gfAD{7{QUs`$Ih8LNc|rh zf4{;1u~Wwes{dn$j_#xWj~y(3FTnq?@%;Y!#}Rga@cfFuw}$6}|Kt97a{KUqY%xk$KwifA;&Y{QU?2$KS6*#QVYjvHOe+ zQ2)oq_n+YZ*b(ykF#I1oRy-*D9~(Xp{?Fa;e{6jJ4*rh~uLu9fhR=ilV;6}xga2a} z%j*ID&)x8UY+OJ5pS$7z*!cVZx80B1;{ji~_R}Y0{faHJ?Kpn||Hth(9|r$tEq`Cb|FM(h{LN2K zp0wkEPk!kAQ`VS&-l*;w>&P*|>i>BB;iCpRQ~z}~jDLS&eb;h<&sbx9SNK0}4;}0E zf9&w_UjN6Y|Ks0pIG+Un$Hw_T_&;~U|FP-+*qCnz|Hsah^@id9*eNp45A*-nxg&b3 z|8w`bnXlOP%#z;f|9HIFqx$OnKQ`C@bvOJUJ6qNhP8xmH8vg8)-EUdr-yirtKE9Z5 z2mi;0&x8MSH~b&FQ0_1MpSzPP-7LF)+5Tzd`#wE&(FfL;FIevR53TWdKlal{)&=4# zJNCY9ohR=v=O=z_4L_fB@Dpoz#!vqAsde6{U}tK}KU(WNMe%=pd@%11{?Fa;e{A|c zcK+BP^?&S~F=6We*zlh4e{A?e%>QGjkC6K(^Z(fNe{A@_=Z}AF+p`M$I7xr|#yY!5 z=0&#u);hVUr}{rW{!y77oJ+%gu;(Ksvy=Ki{`{q8byok!PE75j{*UKlViMXq1+o7M zV~5AKQvb*E;e#T){*T=~tc6qj@Bf7H{Bgh7_Rj29PB=Ru#MeJ0h57mje@_BWRK93< zc$-)2srU0=pA!BG^Z&R#Pu4$$|6^x{1Ubu(jIs_M5TO2V?Ya8u0pZC?6UK$Ju|6gI zA1{yfTH*h!#pl8Qu`%BY{?Fa;e{6Uu_&+wh9M=Ek?O}ct{2#Z&$H4!wasS}|*tq}j ze|C9!eBl4sLu6he=KrxV|8Du$v+eS@{k_gyYk0Sp>px(P`B<3$$J@jD$C&@e#{QW9 z$IcT^1pmjz;{pH2&I}%;^Z(emefU2%=6`)&wA6a2+&~hxvbO+#dWN8(s(gkDV>^39Wt@$&-z=Wh7FXWp-? z{tw;_{*R68hyP=%=M(?O#`>-Be{9U_g#Y997lh06DgKX*>xchyH~b$P^X1_G*qASe z`G4%8vOYKF|FMe##NUelV`l^gs{dnSz9;-2yC5h){U1BKZ!h(K?CAbI)&H^KkLUcl z+3p|w?SU1KTjS>!^Z$7NalG(`<8>>Gn(^GC$JY{vOVM9vyxj-23}C-Vfc|!-9Q%8-D)W+x;7U*uCAq{rC5u zujhZf{_Ef3`FCIc|7-jEKL7T=J^$mudhG7oFOYel?)LY8X@1A+@A>@a1Nv|GfBgKt z-v4X=ula!f{;x(|Uq9Hgb~T;iy90e{8HTiuHeQA9zc>AJzwk|6{}Z!T-7Y z*i@dj zS55sN8}lLI|Je7JbDVCcWqr`^zfm9J$n!PuhO7^IudCOrss3+4iyzhh)voEC|Hp3I zx`X;Zb|3M874MEKZL#j}o_}TkIlNP|7S6bs@ug=-sfns{i}<_6F($@$))w_PSDbjT$wa zqj%O?WBuumi_5xYqsHq0_HS#bUa)`tdQNE68rwghZXNZ1ygvFrc9p6X)c>*XuO=&E zi~nOcl=Y0^|JXH~)=~e*+pFEYp87v_tETnU|G69fj}0FP|L5-4o0N5vCQTgpKW@kT z!xx%8Xt$4fe@Vwz*yD%CYeJi{u35Q?lQMgS?O*-AO3vat%dPLb?>^^5aaq@{UEBHN zwPm&)-m`X8S>xv!>;Lk2upTb_U-H&Q>J`zL|Hlq&-&*}2ySsQt%>QGzu3JO>AG^7% zw+{cuE+>y4{2#k|2e1EQw{F`^{U00iIA5vpfF0jJ@n!Kp%<*aXKknaKykE1zIo3VJ zwKAG=rcR!+roGp*}OANuojYxptvzaO_WR! z^Z&SiTUqZJ{*R6Mk()e|tm7hs<@-kiOUKUnPW|u5)J$j8D+8<-j2`dQ{Zo+jkWmwK z{vY=*8sT04mz`EJLH!>)EUU=bIkTU=-^8coIFmN@weH+2&>1A_{qp^&d$*p>{nvY2 zcj??s{U5Kdb!V^tW4GzjP5mDmo)7c?+ztQ7hNpx7b2t1S8@>+ykKLqWPxXIncslq$ zcKtS8bp2m;J$e4&|Jax>i1~kP_(k|XHvA&|9~;LH|L1P_KX*S^?&^;9aI08 z+OwnjKXzzTD`&uOw>*;vA63tnT@dITKL3$*qV`cr{R~~uav-9Q=^?sPY z6gK-k&qrO4sQ1G>xBeq$SrFxf}kE4gUuJ=kArKUbOp*^Ly}rd^|AU z4*rjg^;~KnyJVdr^Ujt|xM+>@vllO2u*VnQ*Y3991?x~b9}EA-=PO+1FT($^J;s4l0ay;;VZ1^qsKX!^d9`Jwc963J@|Hm$r=L`N1#?S5l*qr~z z#^+1$f9{6=V`KgY{2v?ZpI+R4&>Ei~9M3yojr0HTf7~CRpTYmJF&}cts=d}&-wFQj zV&QT1g!p^_{*R5%pWy%4nEwd>$Hway{?Fa;e{5X7ZSXdqzWLLW)>w}g{*U{k|910n zJH8~DpLcuxW}k-tts^^E}++kb1u;IX~NB)f&(F{Rh?i4H(-){U1AFu6O<) zdzkny_&;~AskO@U<8KGlTjj{-iv!<((5K=5xIgAU!2h`${*R5%Pvm@)H9kL?+Ha{f z=3~PD@%TfBc2oby?p)Mf{U3YaM6ds2W44DrG|HsC9p>2jt zu`ZsU;w=7rqEEyB@#ncLe`Il|KsD2`I_*5Z1`UIKQ{bZ$m#&=a;($Dcf$X1dyaT2 znZI;NjGOvC%vTei;nVPc+zzh?|HsZ2ZwLR!hG&KUb2t1S8(t6okDV!A6aJ5#C>{^~ zkDatIPW>M{U0&btf9y1QzTyAanCA!o$4-}@U-&P#XPx7feUx5-^2X6 zjRE_uu|BVCvrb={>fE}#-8w_or-uLIRb4$Hwi! z|FLsryi?$tp z8uS0Sf4cZ(_&@F+ARgkx+mkNdcV)e2<%^Go$32|woE?~SF(7QcdcdjcW;+ue>}}m0U_gy&h)mrs{JI{Fi z-`gwKss}tJ>jlIA{r>wJ^?zs19EA_FK6wIO?MiU#Eo;;R9y+)W>jj6fcR#(~SvsbJ zPs9I3_gSMpaQFVF)&GsXx?26;ful!c{ooZL>|;j{I*(S|Y<>LLA@OxjTOW{a_P2A^ zhff~Gdc@Xe&zy9Qz5TxRxwEI__P(_CoH_1ib*X8of0 zNccZ)hku0sV?QIF68?`}D)SXF|BvmF?U?_^K6U6Rr`EC1P(B{Vp56{0X}xRbR`q|} z{`lq%>i^h}ZCbDXkG*c~qw4?IE7v@%{*TYc;)j;2|6@P&@CNmN?43_}{U4w26HjbY z|HpoE=}Pr~?AZ@4R{zJ>%e1BQ)c>&;-}8U$nKLIjpX}Hb%GcY}nZup&Z|t?6Fs0bJ zd-p(D&&^c-$DfDMGh{s@@qg@$IWjLx{2x10-XG!r*tv5f)&H@x<==1kKX%g05cPlV zmY?5H{ybv-^OnTFTEmn5Sng||&UoQFpO*InS4XPn{G}=WBJX zlgEcU?RzxvY4Ok2DdM*l|E-C2lK7@$@y)IA_rtCIEv+-;@sfF})`R8um4K3V)`fC^ zN4(g*Q$z@cwL_IC+5cx7*#V@qL1Z1AAGA%RJ(kEq$z`<@*`(es2xm zwKKcFH6HJ)rw3RMo}Z!q&whUpzX|`xhF^pKW5avF|FKhN1Up~m$6BY!>uJ;ZcVw@PF*AS>fvc+>QBvY^(|g^8KhV{yv;r5}^K%zi)?#zxr>+O4}YbD#+Qi z_CagRuZI8Q{+M44|Hr2Pb2t1SJ41e7h5ut?-ZuOn8@>+yj}0FP|HtP1KX=3bvGMmk z{GYqWkJ@aJfHA??q2=iQ`Ycx&0pSajqeA-|8aku?|}bfXUO-9;Q!nW|Hu1_zkh%J?tpE_ z`WCXUHO?=IE%IrZJ!Xyb5wbR^HO?noZ*|-n{&>XT6V_Ny1OAW4gP#}pKX!u5FNObO z$BdPEg);w-9WCdZ;Q#pd7tSZa|FQAi^jAU+{nI3|WsG z^Z$7KdE$#P|Ib?1m&N=)cfyngsV_&;~U|FPjE;s4wX|HmFWF--j*dkE$?ivMH755oVs z8~%@t`GD|$>@0ad#{56_U^$-&|Hm$t^^xKK*zlIGclfhCALwSo|6+~xO{Q%7!W!o@ zU%L6FHN0W{T6e5<{buohy#A~afja+>ohj>A!~e1Ki+ZX5b2t1SJ41Zn)ZyP*CuVh3 z|HtQ({*OQJY1v)W|FPpUd#L~8`JSkh&g%cz@rg~<|MC2IOk5+K|Htkd+f4l*&ld+K zv{e7cj*swN4>2y>*Z=u@2Y(L;pX2`g8D0tguiWXn>H~*FhN}N#7s-4$_&;|1puWyt z&uE{<{6B8b7}!t!ADjMKpSz2de*bUmpICjrm^if9{6= zb2t1SJ3-dhh5uux$hFf2^{pS$7z*qCPs|HqDy z`vd>S=KMc4{T~~?68_Ixo?rMsc546L>i^i7&jtU-hW~;8vzGf0|Hn>^l=WZ5|FMV3 zd^`9*c2QV_`agEQ++X-Vdwy{Le|y;WhyQ~AZ9Q~ zm+PqaL&N{E;YZ>B*zkhze{AfJ`G4$e@w4!MW$pEUyuF-Indd0}kB#Gl|8qC|9~(cf z@PF*Qh;a3P>>}}=@PF(AS&tR|kB#RO^Z(op|HsZ5&`|6@l-gsA^x z!~eqnxf}kE?eFLO8}C={_eXf<|Cf%1w{^{@^Y?lF>)rbML4UvYzkHkj{{HRn@%}&3 z?m9ZkJN^IvjXObt6A11>0wEB0cSRBc!5s<|cXx;4u5GC<6`0g_>swbUyDinNY-PLM zcK3I^uJF2Y&wRe;^pD@?oIRgD&pmR_J;G$>G1ohB*g&uS!|Sm8+lzHJc|4Jv7WEH z;g#GCkL1-&>Z||T(ewrNf32H0a(au8JJId=%K3gW?+X5p?Z`Yo_&;{z8kPQ!-Kcss z2mX(Zd2#T6Y^?W-`G0J9KKK6AlkM)tdb93sC4LD0Z_E3ys0YOHf&XLU_QC&I%k6{z zb9a3B( z8rZj=^Y_^kt%HO5JH5|MupS^D82&Hg#+&K|ho&Z}|6|99?}Pti$7jW<|6>o$h|&3f zY`<=8)c>)Ei2uU;zwl?@QvVlJQx2Ew`QE94_v4|5+@FX3KC7Z2_cPg_kD^*NY3d}^ zt!m6e{Gsnm+YVp!>c*KBmsfr6Np1MIsLp=PoH2LKux?wYhV#|S)2;pG?p%{HqvGnT zU#QoE|NHB->DIOC)Nul~PqVJs(9fBA&s6JLvi|GUSEpDvXx~BoA1|+AKu7g|jjDg8 z{trHG|AfgEY|O{Q{J(?inyUv4kjoEzbw|a^8=L9-r`~PEdnQ#id{y+d?Y6zItXG*c zu&Vvqv~tFt+h*JAH1%_CG~RBPkM)iJyLy{fcl_5@Yg~Wyw5smkp_9|_<*gN^tNqmv zVtrWnKQ`_U%>QFIZ(LvJ|FJQT6YKx7t2dPAhxk8s!j z;s4mpYSwnP>|1T^U%RgQKc2ruoqEm-%U0QTtS|fZ_baVib?Tu0kEd_bCD4g^aHZ`} zw;qAc{_3l2e|z-m?7TH^rFE?M-a#*|u#S@XeDHtYE@`P=uxI;dBr|KstC7rzDn$BypQ-Ff!S`PTG*ygocW;s4md z0iD$Uu?MveRR71uJVN+CHlE*U&&;;Q`QiV#eQ<})>i^imf$i1*U0v8py$~mz7Uf|HmFNcD(vOc5zv`Q!Qjj z#jMr;P;Wf4Y^w9u{K3}AnZ@e=xV>*$rT=3$>Rajm*u(k`RR6~w+PlB=<~RNA^5Fl@ zHmYj)zuWo-+4g2KKQK0}pLJ822Mhnl{q5bWulhfB&mO&X{vR9uZ^<*g?ELU}sh{?= z#{9fiHLKc@^}la+?qS=TwGD6{i0N+KQ7(T?SvTt;J^MM?E4o?_yygFR{qTwKf9#Ik zf}Csbb+Xf=H~kuD9oW6UQ{1MigJl2U|9JfRcIl=5j}4y)|HsDbGyET~uepC~^?&SU z&0DGeV-Ic9Q2pPyCoZY~%L(r8{3YT&&j)QTsrL&_3{d~a&KNaF{U3Yym>?(r`8Pd{ z_FSx-?8m0b^9V7E7;Qy+}UQqv+CcX^*kDV%?hr<7{@p&iw zpSv;tk6kS5rNIBO@q2yvKQ{ab{2v>i2gCod@%bv||FPk_F#nH@`2p~M?uP$kWBnNT zKX=3b@%G~PvhaUAK6!F{;Q!cIKL-Afog}~4hW}&Z_uBA(Jl?6|)!_fw3DaYpBcTsl zr^)v_@PE8NV`rzS|6|9`%~1cx9yvWy{U5t{YPkA8HvJ!){*OIU_8!T)jpu>L6g9~QGjiGPCsW2eh}D)>J(ydC@>8y@Zb2~)fp^Z)q#hS!7tW5efR{-3*Ri2q~b z^zeV~uD^1mT|PV?{2#BsME1Aweff6#CW+VTwj;-m$M{9b^8G=Ub%A)O(}@{&`a`csm zoE>8Omn8G@X8k+ZI(df76Ieaa8uJ6;|M+;wk@fr{KkZ|WAAJ7~|HsE)iaeg+|Nc7s ztogr?kzG6~yU(ci!~71c|I1FCHdy`NlV6;!T<>>cf2Z4*Z9PB8`n2$Vm@gFkaVyWv zM^35t%bXdi{*N6auU`%JHS-*md3r(j9gT{W=QI2t8?R4OgBy8TZ#k*nFK1qi`agE2 zJb%J|spCl$uNS}NNEFuBhW}&3!@>W}Uv@(M9~%CT4L>I9D_;NZ_2cUO@?{2%vc^ez9#hM$E0W5c__|FQ9W`=Q!&yF7IG zu5s4+;`!DFj_~Riu4GxmANofndUeT5;ntW>c(x?itN-zJFY8>He>h}mpmn~^KWt@9 z|Hs>(zb?la@<@&A8Gk;e{$})=T<51#KVD;xTAkypc;#bjtnd87m6xya{3F(6JNtsJ z+4d2ubDhAFi`JMo*?9WCYd;@2>Pa7ZM^w?WZ1sQTSGTMG8@;+f{ok$u+tvRqSUW}i zAA9$Sb?X1vr;hBF(?9np`~1lRG9PgLqw}8MrXFz11rQyJ@G-r%s0T#D|HVGFSv?@m5C7+G_&@f2cU@Hf$G%rQAp9TuwD>{zKlX_W z@P;?7FP%H1{*T+wpFXMnkA3d!N%ep1lP8X-|6`vzc0~Oj`^drl>i^g$#P7lXu}{nS zznMNHg17g?siW%u*oTfBQ2)n1ad4mdKlagmyVd`(_e*2_Umj0*z?C~DS?}7pRoDOJ z{jp{9di8%i{obvW{*Qh7@Nu30$I~y}vs?Wid-96qj#$13J|5<*U9A3(J#G0s=ZU!e z5qvx?Tr$_mntjN6_H9$02O1xbI1|53{pqZErB3~KPe<_aIB9yJ%(J{;J#}`RgZY1a zy_h1N1^$nnbz7wRKX$hKdkg=^#=kc`C%+!S=O5<7tqpv~Iz{}}M{nP-PMasce|hEO z2tJ>2`8U?xw8rHR8~&9w{(V32&9~N=XC|))UY%3)Z)=?Xo(BK5&XV7k)Gn(Q$?H?k z_(%)wx#d1?$R9iXX~`3S?d3I{?sLz>i^go^7|0@KX&Gl4E2BPq9y6-|Jb<;FpsvIoj&dM z1oeO1o-FgI;s4n1NbrB`RCpKhf9wG>2CM&L2hW!I;^P0?Ha73I30rERQ$%KQ*{#XV-~^)}zPvc4qpoiRAm~^fAHe|Ja%0S>XTJ3FAZ6|MBk!cp3OV zHhv$5`G4+)|6}9x6Zk*&C|N%N{*R5nkKzB=m?sJU$Hx3f%>QHK@4>{ccG>>n{BQNx zV~zU*{*U{QzmL21+!x9B|M)!Sq4ND+oqGI$HBSHjy9ceY9`?+ZhpaPXK47)n!`66w z@7Z?5tGhjW)Ec+{p_<37@%a(_ANLR2;s4l0GM^v*kB!ei;Q!dg@_Ehp2hMu6Y_lFE zpD&3WvW7Q=|Ks`b`zH85Ha;(a|6}9$!2hwaUIY9ed!%?)_&+v2uYvz#WBxw;A3I@k zgmdHieRlil|9F3di?@RRV~5G(>-DP-M)L15{2sOYKmX*_@PFKn^*`YM*a`A`J@`L1 z=l`*>{s;UY8=p_X|G69fj}6}q|HqCl9jyM3om1Ld{U1AbOds`s?7Xsm>i>BAiskbO z_&;mR#}og@*7_WLb_&;{JczpOj_858m!2hvFhzErK@nd{ z4*VY*z6Sn}4POWU$A%xn{697>AM^j%qs8mM|FK7iM}z-krwxx#|Hn=p7Owt}P5;Nv z4GmZS$Hx3F_&;~U|FPlU;Q!e0Z}5L?c%ZRw&+}@`|KoPd_k;g)_e-l6ME!726ZK;7 zg+cpn_iFe*o<2RS(*LouB4eEF7Z%&;F@Nx$50+SC{$SJZms-RB&8e~6t1ueqcQ)Fmj@3C|Hp>E zga2d0`@#RQa}tu&|FLru;?)1K(`0>V%>QF!{m@tDY_u*2mG!2@|8YC!ufhMZ;l<$p z*jQg0{*MiB2mi+|ll5)k|9F3v%I$&wW5fHw|G69fkB#%g|FK8Q;|2bYT`1lU^Z$5# zBcjD~ivMHd^5Os74gbe3ka>vkf9%nT@_Tcc|HmGan56!X4POWU$A({o|6^l5=7VqS zw*ABW$xlo7SY!TVi_fbXkEa}2|Ci^-^Ly++TrKndu>LQ%)BmxtJ}~?r8;@`JKlVuR zqws(1{C<6$$9vsj9X2q?dFB49#`6{P|L9GyfAD{7cry4uce`I7eZ3j{qkB8n({{J- ze84|yUw`Ji{;h9kg?f9sbRT~g9pb%zF*2{wy??&z!~1$aUmxhZf4<(%cmCe65bym9 zALf00d@s+}lBKuiKyLvtF=oH>u}6kI%R3$@-S= z(7FQU4b@{B`wzef#!R|Htm%ztaD)2Z&FH|9d~- z4fTIf$+7DHtkc5P|FI)ei^jOb!w^qt3TjP^?%K3)zJBW z?7;e1LHV&2{9jjD&lLXe?!%v||MT~2p#F~yzXbos9@M3cGp+6Piv2S`@!anDFshr( z7YvD>X5G9&b?28u)9myO#UC#GVOqsgf4Qk%&=DV6tCg#3)pT|bpK9AN->pOG6l>hS z@P9e2K36}8d2g8i$8Ie112O+^a{L$S|8W1o|FP@Vt?OL)eM&{c$G%cOgv(pdzN#_L zF(GWSZSU8!v$J*8 zze&qx>i^j7JG4^&$L9P$_Mo0!)c>&u_UNqsk4^u_>qEo;u_HTG`agD92l28p|Bu~A zJQn<)yWbf&%l5Zl$4<`ZmNUKj#;?<@@q8%zaGEvdY5sOwc*Wge->CPC=@6v;kG&wT zT>T%PPX#5D)c>(Zj;r*4RXsudpS$7z`1~C)W{Ubhc6#n;^?%kG#XA3w-MdeS&i`X~ z>s9Ih*zE&*s{dp6>QL$b*!?;OssCfczrp{p`*p4Kf81X*=Krzb<1qh^jrn=-e>^`L z{*Mh02>-`+8v3jMv#!-x{U5twvv%tL*w|nAKX#wMzD~zuU92&m?;qDXTf_Ik|MB$j zkMMu&jy-y*|6}9!!T+&wJTU){-9~&k{2#lae=GHWy!~jb|I2RByruK`6E{5gePV3c z*{Bfz`cCo6_pJ+pd#V59_TZ$}>i^iuqx-4%Q{9nkW^XmUn zY?`3_))%#9IWy|NY@PF(q`Tha^j}1Qt|HsDXpYVTdeE$Le$HwQW z@PBOjKX=3bvFZQV^ndJp@qO@r>;hST6#kEm&oANs*!aCH{GZ)kSk zl_JLr{*N6$K3M%9d-#N*&UZZ@we3;z`5pWpk3YO5{2x16K2L1;^VO=B-(O?>-#yDO zs_#se#{54ve!q+Pf9!1eJPz~!*fH{b6z2c22fUs@u#(%Tv|Jd|@Y|Jl!|8qC|A3Ig%8NmOsGZsXv|6^l4EBHTlo_zie|Hp<; z&3)*YSI6CU)EfS8NYD|l?)JqYYdn5ip1H#skGDEw4qC(W{nF-ub;_Iw=Sa*xujBRN z?|Zy@#Dlx+@qptG|0mx$sQ*in&uiiT_5__(|A%>-@PF(y@q6%p85_>1|HFI^_&;`u zd|wIw$HwcgM|H)|iJkZ^jI3oIdBr zsn(dE*Kf&WSBuZ8KG7P!=hKbl*7*MSalf(FBbH@4$M%<6!v`%27;TO77oHhm4SzVO zPm%S=Woh#He!ksa%o~IMew-AVO+sq%auQ{Ku`*Ew0aey_ZKh5Y7kohUv6{*T+yEe`s5o+v({-VgIt z;Q!c|zw_D1`kwDzJ+9sl^OVZh*YR}BIIg}AzTs-OTCR?B9to@NdFSjg^?i6ewte(} z*V!fFzu^De4gbe3TT$u%*khJwtN&x?%66IWbiGdCG4*rs3o`%7I(1Q{|KsT~e^C60 zZHK=TUt$gaC*I2%^EGGx>p5%8*YuBi#v1EaKeYaFYj{JM4`+?_jjOek`G2?e4}G>o z=KtMl91r+EcfN1Z;g3=@P9mguB`71|HsC9zwm$VhW}$@9wGdnyW#(= zZ}~rW!~e0fZ}~rVj`-0_TUuTpdg!S7zJfLB@HEy%>oV2Hi+Tuuc76-lA0Xf8TcA zrv9&R^?3Dv?D;3xsQ+UhzUBYeCr=$z|F_$-RsG+-GbdyoV68_V58bLB>(Irs@_CHo zl)t`3J>dC^XVm}Ip1nmq;H5jyORo#FzUNM7%X5GBYVm^M+!tA})e-aOP>6B$J zeUEs+fnPmsjd_Cer@U!>=HdnMhBvJ*Upnvncf!A{FI_x`^@}5T{pT;7bK(Xzv_2(1 zaKdbV>yyWiI~%UFw?1_6Al5s!-go$b^L)R4)`xESKVJTklPA>wvG*T7r0f6kc-(Qz z|8e`l1AEo~vG?uWrT&kn-??L}lQ?v81ds2oo!iv^v3Kv5x{cfXUpb*1(0 zU3+l z=S^}}o;x1F$KT8arOwBhXCnCcET5K#*S`opA4iE_lGjITtbZx5pVlez?}xm;dbPa% zTI2T_@PE8K%qM$#^4k%7e&YRar+^#Q=`tS>{*T-7elGBdPb2tzMX#9qr8VCF!T<5} zX!t)it{?u--SB^GyuXD1bGP_n>(txj-$(I(+@7{DPW>Mn^Kvo&j}89~|Hm#8Pygf3 zev!QW`1c0>kDVvKuYmt!V|{Y?KX&f24CnGBng4g|^&GzNohRE_uVQz4MBlJ-k|8pRMuxq;@GX|L@l6Q|0}0%Gn_6 zQ1P1!s>%GnTie6r^2B>vHec_T%=UJzg2dV$#{egL8@PBN~EA#w!v32_Rf$IPGej5${$Akm)6w#Bw*%JcvCU$(kB27g~#<9K(PyTf{< z^!<15w8nf#_&@F+=KI0_xf}kEoijUD{U6`|XNdQL|6}9tZ}>lUhI~E*|Hp>sg#TmX z^$Y&b-SB^GoF4vC@%!75G1Q!~e1Ic>(+%8`ls2#~v;BAN(JCl=wyXKQ?}U2mi;$d_ed= zHa-u6|KsgX#C(34|7R_aFZe%peECrIfBbt4>rcS{v7==^EBqfD^V;D5*eR34)&H?^ z{h0s9hJS?rV~-Rc5C6w5nh~w@|JZp`V%7h#lS_xH|6`|&8KnM?omv*G{*Mh$Tj%bl z?ecTv`7`qKXRNV4?VX+f;?@5f{j4?pACC_j^Z(fJfbf58{QejIkB!d@;s4n9JQ4nn zJ!x zdiXzg?>N8E8rS#j!;7qO|C9tTiYkAgam9sa8bssx{5Ni~SHu7D@^F0M|J?m*ixpno z#($-Cj`+CLqg5R_Y`C+y`zqTW6CR=dkCz9}wRZd}yMFk-H@>cF_|IOP(yjj)oZSa3Qo@mVfW9$4kng7RzM}z-k)Bm{}{*R603;)N4$Atf5 zWB=j**zj-ge{9TCg#Y95z`RQMKQ=B8{*SHRQT!hpr-%PzWBwxi9~<-R;Qx4iSRWVu zkFB>~{2v?h{ow!D#gVb<|Jb8q64d{(%OVq;uETfP^_7IhI{8mlHE!>^^xd`{9uWS| zy?^k3Y^+}l|HsDTA#u)LYdl^s|Bu^oe_{P!HrM}Ue4IQNZkDV>v z3;vG{{|5iZ#`78ek6wiS&)x8U?smWa`TD;)XEb_u%5Bz`42gLlp zzFq#J9uWQs^Z(e*YuD8Ef7zH$2>-{fCcf{P-!E1SiSbu2qw@e~RdpSi2UouBY(<;G zrs}7#|4-jMUD2eZiTXZA=8?TIs;aBWyfXMdZg1P%-}yPAs^J??{^>-;$$5VI{-K5V zqg{Qgx|#T+Ri}>IcBf_yXHIMHhX3ny_!aek?Zscg|FHvQJ{#u$J$>d?^?w09x~l(U z_muU?G5?RvS7=Tna-*4uV;(U7W! zr>*<+TDyJld_9L%HGC)L|MB+Mu3cOG9~<5e{*Mjcc)4Cx4{A_f{U5i-v~8pQkKHY> zt@=OS-tL{+ssCg5?9^HPACD(IApD=Ttk*k8=Krzb2jTzNm>&rL$8HzUQvDxa&pI`i z`%C;Ew`2Wu%>QFI>(D~|AG=e(uDbp&yLi^u0`G0KsKVDz3_^g+X-)7sB#WUut zoogK>uNUxtJpF)xHtPS}4gbf>?<%K<|6_M*+s=XiV`CmQI>pn%DpvOV zO1QcAwt;bp9XPuW?iLf9yVft#$q%yGH|m^?&T{4dwn5|HtlB zr-{!0S2v}rx#mPwNtCE z^U#p)w%w^-+j+X6TUFPn%U&`n~&L<7uw&wglZjY1Cx8VP7PC2Lk4}L7^ z)T^G4o;<7G4-Nmv*5A8||6}9(hj&}Nz+l=%MGW;manBe$E;m zYHx>UtrKSrbDsR@&(=vYZ|eI~&sgL0)xZf)TjTfEnLVEJYWP3yAABJE9~-}~hW~Rn z{2y;W);EFwbNAo-d#n?0&Hv-^i;>T#F#nG|NIV|=A3H>TZ(H`+!`5-)5nn$0kXOV1 z@&3z_&(Glho*I6ka(!p%;s%Hhdub9~<++3TB%;uK^?goTWB)M!&rUD<2mi;$`eg8bY+N7w9~+kk|HsDnJMe$*hW}$@y&(8MHrBI& z|6^l*-}H6+ZU0ha{sR0Tj~5=F@PBMPKH>lPcz}O`|C1R6>i-gC-XHv5wI5Ea{|lKi zz**FQ?R7p&RyJYmM)B9{Fjt zHJ+~%udT9`~dZT?4a`A&aQ8k+VzD@8>Ie^`;X%X|HmFHekyJA0_!ws z_&?tMRQWy{{*R6IQ{n&ESqo#-|FIM0`#|_VcCz>(_&+v0Ap9R29tr-Bjqjh~|JWnM z6T$znG4BihkBxbJ@PBOhyIIQ$?e-LiXM+FZ?af-2p#G1Yvm#0T9~=G%{*RYO|HmFH z^Zeld*k!W6@PBN4zYYJ#hDU_|V;9RjLij&+fqb9-ercHPALiA;|8alN@PF(C@m%nK z>}dHu7XFWo`7)o32(tSh4gbf-2m0BYJ?-(7Am4A7JlD*LWqv07 zU;Cve)&HU4|5E>TLj5035C0dRb3*+ezJG`RyX}SJ>i_WlJNzFT-tV#BntG;pKd#=7 z{*Rq0m$&D7L(id;$JG0w{XVPbdA9vA^?vXd@PBOhi_h<<>3MR&QT2Y<4*$o-`oZvj z>}*+I5B|^Hvi{=r@4i2xp07-m2cP?>;@qs{>1VS*NYaa>oDI(K>ZyrT^ppWy$&B|Jd0w-*0qkjqB;3A6CDYD;@sY z57*eZzQ>w=Y>j!8@P9l%ZqEzi|9JWWdAz{?xf}j3G4^of{6E>g#k1NvQ|2xCcP_Io zouBK}J=*KqwcodTUg^9gYQwQ5&g=KovECy7FLKlKk8=B-GlyjR2J53|j=&2(n%-io zdcqUukIN@yj>A5G?v!}J+F@7j-J)Kwve#RmlJ#$Ue)*TM5BhFVKY0GWJK+h#*_aRb z(@)*QW1iitp77#b7sLxDg`b|VSv}!-@p`|soML?e>j~$s4IjL0lX}31WFBDj`+L0_ z{_jAWO_lQk#Sg;&vG2OG(*Ln9UB00Hk9|?RAN(I1+u{G%*be{4h8KkYV;?(xO7_P; zg8O&u)G_sc+`d!R=Y{`cZ@uOJ*t>4|KlU9mKTzh4+2!p&e24l!UOxO_;A5G#eb<3K zPIRpz>pkNCdVW17;?<8fsju9&eG86f1ds2IU0a=IQ|DOk+OypWy1vMIr+C1wbyr!h zTfau;L9UD7{k3TA3Mas`$$HMx+Z|cE*LuyOnd<*|`jrc&IY+PTkKp}3Yhk7TW6xMH z*(q*)B7%>vN%Kdj|6`Aynu+rk69OqC(AnUv~|kDc;~LP=d9E5e#Cj% z8h&Zg1Fu=bFTwxu^0UNK!T+(d<=+Q+{zlmIQQj}X|G69fkB#|jH#&do)$)2^jrDI2 zt@*_ozaRNE_;>3u3saoF|8ydGd8M}}WC@@pOIOnJZZMQ(lT zYblW?{0E{#MgS-d?;PSu)Vy8tc)Ef40t%{eS1v*4FTHb)(x^ z7s~sGp@#yj3*`3+@_Opkdonv)=gZ$mPh99~jrDQAuinEtf4=;^S<=foN$x-RKkk3B zyuX6~W5a@eTjS9z8!%{U3XztS1fs$1ax712F%O$G=3@8-@R4kD5^F z|E%$QuA6Hj`FTTc@YC>F?WFXjiz>@eGo`GK;ws5O4Cl=|@n>omE&@3+5X zjlcJ26<@Z7Ppr20PHU`(y!Yk1tVhb@3;vJC8|R1rW9P`{P4Iu#;?Lm!czZG@3{n5b zh9_OM>;XGoF|vLt=Kt~j3LQI8{hzzx|Jdm=zYYG6oh?2P^Z(chvfc&!pS$7z*zj@i ze{A?T%>QGjPL}l`Wd0vJLFT{t{qJ$>sIis)kK3bVz8u#7W#^U;RR71u`m^wVY|M*; z|8qC|9~+;qIzv8RJM+r(*4c9T@P9m>x$^vm|6}9&;Q!bK^7$Y9pSActtpDq7 z_&+v2U;J#!>vnyG@^~D6<_&B3Uid%mFXn;5|FMgv$>)>e|Jaxh2>-{%`qA)z?uP$k z!ym%`xf}k^-SB^G%nOA7V~>~^s{W5%EWdY#|6{`o!vC>H%XaubHtrwH|6{`g!vC@1 zJK_JlTGs#N@xylbKXzLW$2vYyY=TlbkK>2(6M|*x1 z6byFWZ}hK7ex99?(bu^ME~SP82&nwuf`uM^zma?(O@0J0&zs{u-*9PlI`T@PGXN9zF^Fj}6ZQ|Hp=Zg8yT~ zx4{3g;alMU+ztQ7hChV=W5dtD|FLm?_&+v$5&R#!RQ4b1|GFFgj}1=)|L1P_KQ`vW z!T+%%!z%qB8|S}M-t-LG+E{%bx>4youZI8QcI+?w9~)i<{*RqAc(4Qi#~wa3Sp6Rx z^RwXpo;ck|{U448{GYqw|9E&sv7qf{2#9m4gbf+ z^A-M&jd_;ve{A?#_&;{8+t{?Aoi6d8)&huC&J-rTQ$xc%<-UGEp`nY*|9 zdOP0^3-zAIhu0hT`F;Jh@4UP}YG04%+kZ4aFmCW5ul@18z7fN`|9vP9^*%nn-Vv_{ z?%OviEW)dO&+mJEzViX2hIsFvZ~LxS{73T*eJ|hF|M|AB_tSY_u759m=lT7={GR)G zw2<|1-QBXOw;%Lv%s+FVzIo%i&Vo&sDz5ZxralS#`_O+bTGy9(So61Ds(7bMbMt=i ze{6W5Hsb%-@MrLUqavHA|ASA2{~M6xr~a=&i)QNo+ztQ7#_fmyV>hkeK>gpUvc~HF zus$dJAG?7JD1`rG!;``PvEh@(Za-$-qG20fnE%J_-K?ehKX$(smFxeq zJGS*#|HsDt2mkkUt&i3J!DoiAndQ}WF3z-uzkKbb8P+%+$A6q|4bOEvXGTS7(BIS# zqSF^lx2`Ai2I2p>9rGaJ|Nd3@cdz+>*5WPU|Jd+>@PBMPKH&e@xIXwlcKsSPou~dX z(YmfQ{NK70pH$8Zl*a@7Ux#NuRsYwvg`acbl}QzU`u?W+n+|Q7tN%*~`&>O>%hpZR z|FIi4spovWaAF0!zN~M2<-i1M;g!1nFCVY;e{8=NP1XOgF@F#KkKNhd&w1Fh&7Lpt zfBzX!)%1USesTTZwL_Y!7sT@o{*R6Mjqrc$HvUc2|FQctZ=(K>-AmSghW}%?^KY#F zkKIaMAK?GkjqB7^|Hp>c`z(8%-5xw&;Qx60@OXm%W5aL4|G69M|FQ$?HBkS@?$@%l z`agE3_AS-_vElQu{x5rQmyS;3iB&zQQ|0_W?l1h`+@34#_Mnr7uCT^@zw-ght^0TB zp#G1?AHER&kKH+-mHI!vesyo%T>T%n2R3V@{*R6O7wiABJITDhry4D^4h#%b|HtiU z_&+xGH|^1R)_uBmQ~$^9QJrPIYVm*UaGA#l|Hu8qd_>IuV`H8l{2x!>Rc;Ub9~+Mc z_&;{rrmfWf@%b<^r^xBEY`8ri78QFS}Fy4(k8dT^a_e|6^CH-&*~jyRrW7jq)$lKh~(%%=utrAG^G2;saMc z*vqcJn#}Km|KsaV4cQL=$F3%ifA~MPBkN(q|5?|lrvA^}@PF3wf&~A^ZV}Md`R2jS z*7dt|QUAyNZy@Vi!~asyei;*oI>jHq=6QMT8TEcxKLY-bogu$RhW}&Z_sMtWz3i#;(dkO>Cw>e5 zkB#pq;Q!e8{1g6+R&ACCw9A3I0Z$AJH1WBwlI|M7U{ObAi`$BvjVQ2ie}YErQJKQ@jp{2v?N z2f+XF{=@Hg;s1X6`JDPcd|nCv$L%@tc_sWGyFmQr3t!!59Vzp+A}-!*9V7k?{?9H? zjwk#d8}|qN9~^?w(dol^gY@8dB4kB#-&YQ49?^XB%G>if|5pImQ^ z?|XL=?Jt=qhV?!RBjL+UbYM`o637EVmv|8mRt{ z`x7;zzw_0i#kPOBxBMS(&zM{Oj}0Hxz4<)5z4@|TKHsy({IVNeXLQBvY+DHRIAQbt;Q!d+;=R}3-`;bj{c-hvk@EVo>A5zZ8wZc6_rv;#@PF=} zHrC(M>c^w%{qXt&|HsBWAI$$_j%q zlEvSQwZ`Sc|MB#N;{D+N*jT?8{*MiB_rmrtJ3rR%^$QwgowYJuyj@T06!D&Wrg!w} zHygCH&R(7lPh*XFgYbXcUwB3MKQ=BO{*Rp}9xyTcCF@Liy@3DYcHBSkf9{6=o7w7+ z`ajHTg#TkF%lGr}f9&D6=Q$T1=zXoh8(Zc1v^8q%vBl2%opr6Z9@^?OX!F9Op*dSU z9oKD%I&k)Y`oB@%Y*8tA7!6CcSJrGSY_ z>%(3=vspdhsf(wbPcA-dec{SQc)@UPzhBl9ett%e@ZSPAs}HCzk)B|3= z>zw*OnK7px@Xou>WBu9inQv`W&vw7~ytc{vtRKAVlCyH++3=n7Hdf9Hlz!~H2d(dv z(_{YMeN8v255#;w%>Q#Y{2v?M5B|^H@PF(xmn!G~v5(7o!0>;({$pp4J7t{$tPdW) zL-wzm_5Py=oD-M(S!4TS-wm-oAnOCe|MBwnA32Emh!MQ~hmRg~zAnhJ-gjWPQ~zX< z_09vkoHG-~M(}uU-nGS9GjVDJkN1up8=XT>&-LniyDqWbzGI#9$>Xc6*R5YFesi7m z;TsY17xWS$X-roxrOmU_~9k9M_(PZbRxreQ%&K{%wkB_Ix zvvbt{vCAf>sQ=^h8SjsKM?Dt7=f`N7hqvk5r>yb%_}TGiy;`1c*5kz=opoNb9wYv% z#=UP@=5H-!IlH~b&F zNIVt%AG`SW6!m}X4DovKf9{6=W9Q!Te{8%zga2dW_X-`B`9<=0;{6BwA3Ix)AN-%Y z;s4l~3u4v(vEjww|Jd+z@PBOlJ_!DgjrZU1f9!1ey%PK%yIB6chW}%akoU*%e{3Az z%&UE@^Th)$Z5m{qC%5PFv;o%m_g%cV^%S}P;Q#pVSGoNCP_3oR|GV{mAyeip_n$l5 zI!op;!~gO9MyC9p4*rjwCi9|J^^Ud1`)~L^ZZDSiU+{ly{JjSM$Icbs2mi;$?T7#4 z`ytFH#QZ-t=7q!mu}8|~!~d}h#7DvZxf}kEoj7f<`ad@QK0L9v)UF@D=Xmj-W!6}4 z8vc*_H&z~x@PF)5SzkE6(PV4PBV0Xgsx^MUaOK(Q)@5>eH+szS>iX;FSdUqd=!AT7 zn{}c5y$Aot>%;o3@PF(w`TbPgJ~IFB*8MkC_J7ERrPh<={oq5L)4e$8= zu$|T;WIp4p`Maz~%KLNY-rZge|Hu8u@5SK%`2HUa|Hp&9w|HsC>N%%h=uN3+F9sZ9USyt))+ztQ74j(gE{U1A4)(eLJW8?EH_&+w* zmxcdhY>Hg>T3KOW!AvHjKmv5Uk*!vC=`uMhr@ohQFH-q-&% zyS!3q_&;7>iM*b`|FLoZ!~d~y|HJ>Wv3@oDpS$7z*tmZ9KX=3bu}6x}ga30k{2v>> z5B|^H@PF)LnXicXf9{6=W8?hrf9{6=W9N?>rv8teGbTj+A3IytPlx|w=Zg1h==sXJ zU~H&U`pehWnIi|P|Kst_$myc~kDZy@RsA13HM6JsKfYdOTKT_7JH7b7kH$DrYW2b}< zcG8B;wbNsN;s1E~@FVblY|Ph!|6{`k!vC?ceklAO8}rQI|JYcs6Z8Mr*gvfQ%f|7< z`oHdm|8qC|9~=7%|Hp>!ga30k{GWAbr20R0W_YanKX&f$NcDf6_B2$Fh=%`T4gbf+>EZv_xWD25*ziOB{$16$KjHs)|DfUj*co9ly8bUaDT%@PE8M`agGHiQR15b0b34|8aZfu)*s8*f`$se{AeO{2v=04*rjg`FfcD z$A<5N|6`Agi&y{0E{=~^|7ZIjRXP8UogXE?HxmEH)8~W_RsY8>5YGz#$1alRKl~q? z{*Mih3IE5&`pEEqY^)~>|HqCW+F$)28>in?XRkdT;1S>5QPuQ+JUx6M{2v?l2mBu! z{uKU?Jt|uKqxe7G{;YVJrzrl<-SB_xV)3W&f9{6=W8?bVz6$%}ZX7>%=lXa)-2d+F zz70?8-u{35wa@wg$iw+=_w{|5LkD_YpRZT+ZQpr+cs#iG7yi=S@SpC^4)NZO_1N9p z|7gD9AI&FB2=VrlzPBH*xBq{x&)56;cEiTr^ZR_;cfMbXCJnvz2kWQ0_YdoHx*I;l z-B=IQ-B>Tw-CbKYRsT1zX;bxo@Okim>>4tU?%y-28uP)1e{{jNW4>2xn{yRMy8Eg3 zYt^9A|FK)vuciJkXJBLXfAB+?|HpP_PwQwdcI%eIuslWQa4;Q_x{tu1$f9xU6 z8mj+e4;G&X|Hp>UIy8QK#o85rRZkeyvbpoz?(r4#$G@WM`F4}_69+z1Zrxq{#DRa0 zvu@ROYZ9BRkcan8YY52b;$39k1h=%`T zH;{(^3;gtN>i-&wCxri7*x(cOe|2StzdJwCx{h4`pT3`1@#?@&)dMz`eyV9z`^o9y z|2|%LQ+;3^@i*{)YjCEfeb%mtm;Ynyyif6eY^-;T`G4$ojq0lZb2t1SyRG;}%>QGzl6i*k zf9z`Fc`^TwT}y5+{2y;mO_|RJ|L1P_KQ^BK@PBN0Lij)S5P5!M{vSKJeS7tP?2et< zs{dnm>DEF0A3Iun6Z{`LLOfE8tpCgX?a{ft`agHW|FQc9wp0Jd?$fcYQ@`di+fM(- z`vZOs>;EpT-AsLRmsSnc|8aXu;nkS`$L=8WHsSx+L9JV;|6{jn*G~N(J0KuH{U5t` zhc@c}*zk#%|Hp=3g#Tmr>(t(PZSovz_`kx8+1Buj6OPWX+Xw&m%$n)e@P9q0PP6XR zq`CS(KK{$Ha@GH_Z!aoU|Hs}iX{P!=cFK$e>i^hjvlgoVV~?9UPyHXeeA;~Ve|&z9 zn><(jAG>t?O!a^4$zvv{|6^ywr>g&B4-D$9{*Ra6ReUJ?A3L{afAxRtvXBV%e{6r5 zSB?39?2d^UI{$C@@z2!%4UWlD|HtivqB7L~@%p2~lhyyZ`}2Sv_IeZ_mg2OC>TVqq zn&`xqb+hgfBJ;skb+zsoG*svR@$za1hp7K!*B?4u{U5u@@M!1vH#*ttU5ls$^?%&o z`eD)P|Jb#M%I}3kI#!)NWSBEV*8An@PEhr z&Z_?lZdd95*x}t8sQ+V+PUz#*+WD^Mg{^1Q`*o7vGh+T9yQ}!W0U>XB623UC-Y<1@ zrT=5+%jY%lf1ZTX>i@952mBv9_1649Hs=4q|Am}7rT!0}H^Kk0@%;+?A3IY#8vGv{ zzo&-(V~>{4W8weU>GFLJ{2x0_JQ(~R8{QB8&)x8UYQF&$a<>qf9x!o4*>ti`xBp! zF1`OxUJd`p?O5Lg{*R6CBjEqo@Ne*cYx z1mO=8WPKUf$IO*!)8?aKX&ph|HsC9*qHxkEuYuJ|8ald z58?mV_&qlKACG^&tfvD1$H!Zm_&)eQnNgtrFMWE5^X4yGJo24|dO!GD%>QGT%J)?x z{5N^l6r51+hwsDS|JeAx4E~P|f0g;sTF-y(J+8hF^IC>qSYutXAW8inw-?L&1o%HT z{H5cpv<@llt^SXfUs%@Dc{gyWUEjFrgVq0We=!d-sn$Z<|54&eF#nIYceJc$3jfC* zu`pHr9~)i|{*Rr%G}(dwV^5Oxd*T1s6Bnnc|6{`+!T+%f;p4>rvFZQZ4gbfc|8qC| zA3J|Vs`@{6;i`1?f9#T#8S;HVj-7s#TtECDw`a@wG5_!G|DII;mm}+eKGZAKw&%*c zuRZrAdG)NY1Z()7)Td&t;d|i!c=`B#9R81ud7SWnY<&L<|L1P_KQ_(}|L5+FFAcE! zGhMs`{2%XcH2fbQ9|>~)wZnVb<0neKPlW&D^|7ATa>i^vR?$h^q zZC~0{=Kt~f)o7tVO~_#cm3!^?`bu*Uktm$vM;PFWf!USyYb+H$Nf zDf9nsT|VXo!vDD&{*PU}NWMQ7|Hm#^AoGdD|FMV5cKE-5op-4Ji(D43{*R60S>xU! z+g`FdO*~zub=m4%@j&s`r7N?YrhguOegD@7EB&1KyX@Hmtutg^=gu}gt>F(}exid{ z!~gO6GvxI!y+uRYj`@RIJk_n!2pWr-y_HQ_XnHR2Od9v z)cHBPPS|@(H&=SVODDtwt`DpC>!wN%c8}+n) z@bWpC7nmI0y2U2-fOm@DyY871{-66cst3Gs&s|u5HvIkUjp_lhp6};x?eprQ56*_y ze`$mIK%9T~ygylEp5IIL|7?9h)+?@m@-44U9QwKS*-IB>J=|Zc&s;n&^9O52d^K%@ z`ofd49&+G;hStZU7qW+J4?C2r&f9xaD_f$mM zHm27m>+m9AUlG`W24Of+tP4E1drDS@qaVwjEms$TqXW*aN@KG9{+9I);q~} z-DbUI%UY+zf2sA-ZEKu|BUW24*su(~(|V!!Ke2t*bC=I|ir(ICy>Rgi=lZ-o5qvx> z5D%Dm`GEDb1>>BTKR#?dZpH}pe?0x+{*OI=afbRo_PB*<>i^i7 zmk0mH&X9R@@PBOhI`}^}*0+cMtLixQf9}ToKQ?|}0{_Rx?@QqS*!VpF=Kr}H{*RqF zFI@c}k8j+ZVe0?bcz+B3$HxA_|5=M)#QZ-t=8wYvvGMOM{2v>CKfwR7aeDYacFw{i z^?z*mGWb6>d>Q;78^0fb|8qC|9~<`{{2x1S>R|PM?2+QX>IKUDzgz!ap@%LWYK^~_ z;s5yWd&cxonZFxuohs`;Ztfjr4gUlG$M+)zV+W}JV`q=<|1OdxX3{hX1pc zzvtlp*q8?g|Hm$x6|4S_T{1se{U7hI2@6uy|FKJE>iqRczCVtY_nX7sSQp9n&;3jK zsQ=^p?Z}bsotdw1jATcR3Q+&Yj+-z*{U19OzhB$1)lQH3Z18{F9zR9Aq4+;G=Ci~9 zxf}kEjmIPWAG=h%+n)>f*#6T0asT1%;Q!cTWj-qWAA5{=KKMU2?tjexb2t2-yW#)X zc>cowv9X>s{2zOa{QX+v*l}z6KW;~hC9>`Ch46pej`fG(|9E@R@PBN~dxigFm&tbc zKQ`9$h5uvY@dy9M&YC0Z7mEL5dV?G}I zpWQz3a`1obOz~A%|JU8{f9$N%f$IO*x#HjQ>OEqQ-R*>!v(B6l z?qoc8-8y4@n9l#><<@`T(hTLE9f9%m^!_@z=N0ttC?j7`v zZOi^h%4*x6~_)c^7G;+*vE>i^hb;sIA|`gbHd zBD0tJKYqTKmD<(WQvLTxc1nB)=V;7-tz%;Y)&FsOTwEvTfJfE`zV&%}e0Z=kc)1hh z?tp-5*1p~Y9s7NG6u)ox^?}*}6Ky-z+l2q)_w_hG{2v>qhyP>4$E;g5DQeE7hBi;{ z=AOyc@L`GPrdY#=oquSmH9S?F=cif2Q^Ei7@-XiW{*R6MUhseJ-t0fy8vf_2?sKf+ zf8hUkddvfZ|6{}F!T+)8|J)7#$Hu%X_&;~U|FLm-@PF=x|6|7ut@MBFc)2|IKQ=rJ z{GYqw|Jb-c)~sJ1wQ_X>^?T@U2Ub+Itnd8yyp>)(`2DKJd`QgyXB<-z~)@-q|Tbp9VZD=FTA|6}LG$EyEhr;6|UaL#7Cz3_MafAwzoKb{_sFZe$; z=JmnlVJ$A%9a*J6jAz92Hn*?p|4as3a3@38%WSFHK8cNb*rwC#D3 z!<@5kRCQupl=E}RF58Yyx>?mJiSqm5nY(Q}`tzTwIx9BX8Mb1NZBLiyAN(I554ipC ze{6WbKCSmzV>|pGZ!eAy{2zO?cu4p^HjWqkAMa0GKl~pX_ZR#hdvt>MPw{{3LOEXW zf7bH&aQiAeUff+E>xa5K*Ju7;;c)NuZi~XaPY+M&KELn0LEpyn(|!6s@^jg~-p{9f z=NIPr+@AmE>$_{dov;7P5%28YKi_$Sm~ZOdK6Fs9SBD0BZ%-fS?G=4HGuZq5zSsXp z`|o>y`uat9H~0Sfwy*bVU_rd?MYu2ly{*R6Mfbf58tjCJ^e{AeO=Kry= z-X-S$xf}kE`-AQ9e{A@`h2I>t#_`!y?rK>d6zl&s`}`&KeV7lHH=wGqeklAOw|8mL zMEzgf^DnFa!{x*Ov2lOA)aS4rPyd#F>i>BB(eQsi9l7D<|JY3$)KdS)ZYJ}lF#nJ3 zSFMK5|6|t?;0OOF@2S=Q)vi`u{T~}%5B|^H@PBNq{|x`f#_8ez+ztQdZumboykE83 z#rxg5e)_*&pMGc_Fz4$D73^B#|GpYEvEq?lAFBt%e8JG=6RhDIJ3Kp~;`NNbsSm{E zrF}Wxt6v>Bq2eEN{;odI5g+(b&iJYpU;2+Z<<@w7!T<62caZg|vHmZ+N6R+Od!x45 z^QBkoO8@u3Pk!oW;cYShj}5AAG-SB^GoFD7|x*PtF zjprBq9~;jv_&;`aY4|@j{U2{1d@lT-yW#)XP3kmK|L1P_KeoTD{|x`fhL^vAc9=t@HnQf587e zvSg{-_p?%csS`PW%?dpdUwaH?OOX&un9wfaBazP4@Ks{dm*ZQ4}*AG^2s=)Mz% z+4Eyw=_qI9`cUg}-xXT|MZFa-J$&|{U5u3x6bPS*ePAQ zssCda4j82VkKIcCUV#5&_e@E5{HFG`9u}YL%-z@9Zck`jj`~0DPfAR#^YCvy?097- zk8t4s`1+HOQmp=u9h+F7{*T=usZjkNyM02wbM#afJAb#hOy{{LJ6m^+%~1cx>kmlG zQvb(ppOEP^_&Lz_x0$@3ZQZh}o6GxM_&=T=zh{E~W9Nt;j9n05-C$6L4NH>^W?H+A;E@}6~3+936RJbl+u!OqGBZ+m{ca7w)& z8vc)+Frv54|6^yB4_5zoSM5{k|KQ)?|JeERdE>HOfAx$Xe^R|4JQVz&yW#)X`1~3E zkBxb1@PF)7`91{xj}4yz|Hsaq6Q}-oN65T2_&+xM2mBv9b7rXe zKX%$U`95UEV^!NH1UZS{RoLy#l+UMz-0Sh`u5+(jW4#dgKOR3c{GYXaKluI3N37xh zP6Rz{jnij+bJZHhJ8Jw@yFU}<`#|`=#xI^$|Cu76*LVE*0ox95x#Rf#*7-7@;J+pJ zS>yYPneFejhPQ}WZjnE%I) z6>o?6e{4LyG5^oqVb310>%+WA_&@Fs8vc)s-)F=B@pu-=^?zG^r#;@HrUg5_g133( zI}7!Gu`?_EA6w^ZW^DEhkojkCpFR>T<26aJ5#Dc?toZN1*}`J!W$-cPCSKMZnMUGnZon4tuasR-a#|1u|97@&oo!3%IC#XtVhW_tjAxUXbtZN z|0iogsjsB}V~<=W9#7`~u`!PZ{*R6IKQaH$-SB^G_(076b2sMyvEiHG|JX$-6 zRsY9^4~G9^XNwnw|6}9(wxGCRJDzCxKi;3&;`>^>(9iB~^yN#v?eUN%^JL)v`1rwk zxd#Kgc}~1_RJ|YlA3H(5?}q<-vEZoszhUxx!2G}U_a9OJ7cM>k{_lZ-N7VnpGq!xD zrDyt%!|MIe@PBMv{+FwpdhTd+SbbmmJXxPO(9asrhigd;o!sGbl0 z@4z?TTEqVh8~&Ab9_BZR|KsV=@PF)d@mjJzq*sd{xn6txLG@~ROJdWhD z_!R3=D^uWCtVfGS72jfABED7pi}gs^KI4Nwd9`2Aeb&X|U*Z3_zi9YBHXh&be{5`r z|6{|`!vC@1ZQ=i{<@pW&$Hwy!{*MhG2mi;$`kU~7)(b2BpS#0fyUq4LYH^JEKOWE6 zTmFxY`Ga}S7hd-~en356;p$ZJUK!R!tJ9rV1LCa<tJ9~+Mk_&;~U|FN^=^zeVYJ!rXqtuen0{*R}}d{+2B zHs(`e{vSI@zVC+rWA~SNIDXUnUVEX{R?nH)+oF;;<~gCW>s|ZzzAc{J|JWL}Y}X2> zpyx}EvUi-`CG!C{KKkr^o7DpzKXCx_0Ga{a2p-S%TQ{ozv);Br{U3YfhE-0-zbuX5{j+r43g_UV)z-JKTnyi7y=2)O zM`rU`FI_&@863I8df}4k&Q@n{1RoFc7fx~f!wyCsKPa^nyn!XXUJtCth|l}i;(u9} z%D<0A-G8%&zj|-76Uoa@m4C0~^~D;$FM*zk4_t&g$o@G3X|7H6GQGC=10CRz^=-va-~^A8f=1OLY! zS~fuaAK%}g;s4l}Zx8>+j+Oc4U$!f-9wyytagjBC{{jEU_glI1Q=PdXqiuWkZOQ8Y zczKu)2mj}8_&+x0)x-a}8~%?CKlSw4DRz7C_u>!Lrd#LBJonC}Gp#XSEBlez)|kJw zyyb1yIQ`|h^R4ms@H;QvZjI*`=Kt~d(f_gO|M>S>w#=`C|Kt1VIPpwd{We$+9@$;} zAK#CMjP9xakB#+EG5?R9Ade^bKQ`7^mA^0T^3Y3XY_~2J5BT!=9oG1Jwe#P0TH|=l zZ@=3b#}odK`-|`|M z|2bzpM$Qla$J3X}?;+v;*jO*&|0C@#fb6W#u>U^&{NGbo-?9D2=Lh&d-rhX<_XYlsT`KP%@PF*`s$uH?*zkPte{Me*{INCs zX2a=!^6QEVpVYRj?~D0=+&`@Ei}`|8pDukDWhqu=+o@;s4l$ z<-@$|r~kt`t6+foKYRUT_w@F?^{u_0vU7UL?@_<6ZSi|^+WZj3<1^_=-MqSa|FRBA z>8AdV$CE?TdU!d%`%e@*C;e9Se>{GknbJr7A3HIzr}{s);s1F4=;$Hp|JX4x!5;h{ z``7#gd>_{T<@fPu%>QF!y-WB%HayzX72~6u7Y3>C!{zs!Il-^t|F|6<5dM#i)5HI{ z4gbf64}!vn(qv9TTgj}2c2|K~RRA3Jw=xcWbKk<5#O|6`{{Myvm0!{5RGv2%tE z)A@gH!~e1Kf=@Y&|HqCVQZxULojGWj&i`X)4GvNN$Ic#Bv;Hp| z^SI#utYtnH{NIPO8>#=pye#-XHXbkdKeyrk*zk!1cCCuOYe&QCl#d(5z(byFx7r#$ zsrkv;hX0%Y^BOxp)(?Gl{aWjykWjB(({ zjrCOF|JazX2LH##{K2jlYr8xyPW>OZm&x~SSpSz@o{*^ikB#|zSpSz@93QX#kM|F} z8vGv{`@3q*R=<9=(Kc(GzWd(VE{Tos=5*X{+e_mjy(iDsHs;sC|MB`Uk8a%M9d>%$ zKKMVoerfnWHXa}NKQ`7MhW}&3X7|6}9+g8yS<|KR`leuM4sf9&Ge81;W_`ad@PA3M<3 z;r?{JRp9o(d3AyF_X53Lpg#-j!0QW~XZLH3d5rGh9mKZO7@WQ!Z6^{a0i4e(;HNk6)+}TV`$J{9{LtuWm8qW%Yj8j`@FVc)+_KI%@Yf8vc*>f17sA)&H?uwQ1@#YkkDF zw`|?S+mbw^`o3r1_3b$LL3E?Wb-npBrdwk^V&(p6*3D(!9oGNd_UTpigF$HVf0G)$ zul}!5otpW7Y|j648~%?CUkCr^HvAtO9uWS|ZTLU8;s4ye`{;PThX0H2_knsqT;2!G zY8&$*;r|L|e5f7}z5Y~{HGCla-@siTsRzXQ7X{U}C%5-Pzj3zRllgzIXO6WFl6hCx z&8)P>^Y4yNw^!fsX%qFaL2X*8|6^mmALjoJf48anzxuKsFZ>_7PUD8^|JYdn8~)GE z-|z|qx+wgyETtEDu+nE2y=Nsln!vDDq z|Htm$sImG#HrDrr|6@1l)>-`@yG76L>i^ii`gBwO$A)M7@a5IEKk$CdT0%?+5?Kh7ZL2KQ`v?Vf|k|9=$u%_&+x0p~C;MyS8Yo{*Uc7t(pJF z4!W_q`agE7&K-3AAG=N0PU`>I@QCn#Yi^iI<}C5x|Jc)JEmr^MHrD@T&z`wJ{U3Yg^m*$4*o($aRR71GH)@>D|FbSB^SZt< z&@OLQL6O)0p98G(lM>Ybb@={I>IHktJkGiO22``_wr;Ebj~&#ZlUFsrubscs&B5yb zczrzwg{%K#M-Gis|Hu2QFr!TUA3Hp!T>T$AbL@2Wf9&DXnE%HP8$V0^AG>7KB=vvn z+~P{_-+%6Ir;jfktNxGslUQD*{*N6|TB-hz9bHl7-95RBoqtqCrFV5pXY1s|H1&Tx z{dI%;s{dnqGT*k+4PK_J;51?@p=r%f06R*z|ww5;~BjNwp@L}+OeEi_o?(XrRb($P6hyUYt_%!%GcA9)&0sqIw`Xcau>i;aQ@rW&dZZt&`;Y zj3*vgWgR82&-Z>@VI3xZ6#kEw7cbrq{*Rp`kLT8V7Foy3_aQsN7y7ur$?|9i8uQk|&K3Ig{(;6hmXu|U`F-$zTi2gd z|Cc7$2mkl*4JXwrmdpv$`G4%3DMQr%v5Te*RR71$pV&|RA3JpF5cPlTn7Oh(mCXNR zV}8xzexbHMBgG%R{?IV%^d(8^|9F2U%k%4zs6qC4<}Z--bjAPi@y(OjX`Yd7*p&3eD`{5$ZMR=)W64y*TrM}Yrh!!Jy_)YLbt{IGgIJpX524)RU9a!9>j zhOE~I|Hn>}`I7K|?Br#cUejA;{@;j0>ibe<`$sQbXPqMRC*l9NJzeIx!T+%{S7xdI zd*b1P>i^(R;s4lJj~V`tjrn!5zT;zG4nL@#FGqZb_z!E$V-p`@4etg2XQ!8j|6^bC zUe=gj2mi@WNudz5%p_&+xM8vLKz@PF*$mFeOk?y@eG^>Af9S?iM3 zx#BI(Sr^NEyuH&-*0%USSu4`IY+bJRX3zoavFi%Fh2^`g$8Ri_^(D7iXRgf^kFwFP zE7I0lSFFvGc~{G=%h%+JkD2q>Uk@Bm&zC6I_r{{h)-kdkulP1=_+I!wo*upz{*R6M zp74KcJU;M$Y+YYh{GZ$Kf9!Pei|~K!6j{$4{*Rp{>w&`mv1>eD9qaV@5$gZAJyHIB zf&XL2PuF>5kMi+~n-;A8k6kc%h_3(3&Yv_`{U6UCGjWjmKXzE12oUf?5%b++jIKs5e$ z@$_c(fk)3D#eBf<*Sl?24|q!E|Gj?i#_*8GH`RE++fIA4etbUs(CAI-0Z(5#g?WJy z>^m-VKh0)gVf3iNZUH|?Ad%Yi<=SA}V*|mFz*JM$d^_D$5)ci^hFHZ1pMv|Ss?$7`;v?<)1iN^|vp>|xRM)&H^k4=fMB5izdqVoMZ(;s5yW>8SaM^6yJm+m6qlPd(k;8o!@`|Kt9{@4)}D^JP6x_&+xO{#n(l zuQh(31^>tGn6C!^=QjKw8@>YmkNXGD0{_Q`ubA-q2*2JxAi_Fq;t=(J{Cp89^UmS_ z*!X=I{2#keyb$~!J6U`a{2x1A*1LuOV<*i|_Dv z(>G5lu*T;h_&=ULabb#=_;#r^eoq4b$L*=&zcBxg4gb}2n9Tp<=PmJH5xd7)M zUshS;@5_U!6Rq+0CHx=HkI#$ne{9T$hyQaM{?BdrKQ`8Lh5uux%kd8QKX!(AH26O@ zd@0udWy70QeX_zDzlVeW{GZ!Vf4Rd>ul}*?UDoiX z@PE8~9N&Qdb9>Xv_gdrl1N@(Dm)AG^A3Jqwoccd@;>0NRf9yh;R|o&cE}j~p{*R9b z*4KsqW2ctgtn>fa8C4^^OKY!0@$b7VnFsjjBahU!%>R4kyGQ-{lfFLdJn@L|f4n?2 z{GZ#MUw^_*kN3mDji0i{^E)BoX}>O6_KbCotj|03^0R&o|HsSE5#I;@$Ichu2mi;8 zni}s78ULbn(p>pHq4+=EUlr41)&H?er$nj$W8?9`{6Dwh|Ja!C*YmMI+T~-u-=ZI0 zw}$_Fe&Cya-DUDy)}!U}XP z{lWY1TbGC*{HD!^eqA@~BWrll_8UI7#_?kKKi+@%_w3#e|LoWBf4u$lf9y2zeDHtl ztnvZ6{;%8cf9&Yee(L|&v2uF&KX#@Z|Azl#XUO`%MHj!e&Xe_hZ~OQg>zv$vay;rg z>oS=S_;A)g?e$xbDDxz?{9xTLskL`t$G@X^{AOTkJN17&zL%8TL;W9*7pJ85RR70L zPU@rn&uy&#%Z`m5s_Xyq_%Isl|FRP!{e1@J1-c#~aD7Pl4fsEPKTrSXHvHc`agEgf z!I#1Rxefp4HvFI4@PBT@|G5qS=QjKw8=esUj}4y(|HsBWDfmBjf~?o(^9xefov4j(vJ{U1AWaImib%g&SeSy=zq zZOs338}t9z1w)6a|8pDuFS4?s`af)k|6}LL{R98U#{4e$KX$?}S-)8P--|07sQ<(L z3;)N4uY~_&m;Gy2QVQXzWF8}pMYa71j;V$cIuV4Hj{2y;m zWbh#Mf9&94gS^`x+F++2A@kRMir#1qj|l(A(~nL{Qvb&unVRZ-`SvC|eUbRU$jZ&N zE%Wzw{Jpk|Wj-I~|MC7QjtW)($A*`J|6{|~!T-4p|HsBWLij(o;s4l}*VnS&4r{DG z4FAXNc>P_--C_49?*Df0)OLY*&y8bt+IIB6|K{IQX6~}>cs{)QLv6!XrLWj++jC;0 zy~pbAvCfK#^ZIZ1?-Q-}+V&E;|C$}E?V`viZ`DovYFXL zN?M{{M~QcIFRwg2(yuEbqWn5=yU)|IHTI2o4J^iowzrgFykoSN0{8*pU?G6DR@YmM& z#rm%9`2#!94>pqdJnrdr{ZMCqV53IoyKj|HsC>KKMUg9{e8s9~<4Ifw{^Z$5yH2fbM>nFqi zxefovhUbI-W5fHw|GE9!Cy)B|_V{DfV?GR0UrGPxHvAvEgX}NX|7G7Ow+H@@jrnBo zf16srqyDc|(+2AQ*sbf=RsY9sA&=Kd@qayszN`KZ>)*ovJ)VEHX8zwb|Hr2Pa~uB8 zT09;6pWE<%*4KOL|J;WEvzGJ2|FJPo5dP2Yvd62e>HjL`zNa1#^ZTX-S5;ff{66@< zukL@}<^#U=*e_l|F`+I57Z07>%#xByUIMrfxE_7k7pWE<%ygd3px8eWX{@r`)?eeg{@PE9#CiQCk9~+53v9~)i|^Z(eK|K~R5|FH-3?5gws+%CVo(zf5)tE+eH*a~Z0{s-%p*S2`N zuG5$KHT)lMKj!aE`)sN8O`Y26{69WEm)kFIl7hk3DhTGVk(pA@=+qJ$H%s$=`=rkD9aC zYaUeF6K5>(BKr-s?bGM2@}_16ThCj#RQ+GCZ$DH|ICIVd^?&RM)90%HV~?LE-^cxC zP&IqQUAwYJaV)b-e!QEzF+f}>i-@Z{IPmKFQ}9HKX$V&1J(cW{C)b? z_&@fo146uQS8ulcA1r^LVg4WQpR}|z^?&T7%zX8K?4pt5)c>&ujh&+Yk3FPnn)*L> zdF52~e{6U__&;{q$cbLBdj6f)r<-k0A2nJ1ANN1EYNq->o`3F`N$UUDdC|%0|9JX# z18e*r+iTTK{a^mgr_}%5*fvQ0AN%HBHS_;EK6gs}UsOm-^?&S&fJxlq#1h09c7p?L8=@lNGuAkM zdj7=I*7*HC=Kpbjus#a>A3H<*68s-KOV)pd|6`|A_SN}+y!~P0`m6tAN6G2o|Jb>5 ze6&^Yqkawl$NM|s+WbFu{I&Ui?3}8B>i^h`agD}_&)eQHs)Wz|E=73M*SZe>;JN` zehvH|J7IE^&i`X`{a?4?|LpR`S7QDj8^6bg|Kt5tI!(S`d2P2nKk~+p!1_zRUcW!C zzH8{DAzt3&+k9JYJEp!bT-G!FWy4nM4Eet4*yEdhk2gG~zAt}%jJIjiCTq+Kga709 z0{K3)#m@DkDVtT4gQY}PXqtQ z&JrI8|Hp=(g8yT~+ra;^i)G#){2#kO*2jbYW2egcsPKPm%;SRpV`IJ;{2x0T>!XVQ zV`IHk_&+w*FNXhP=Zfb!_iDN|*2{zc*5#@?*{kDWJVkorG% z$n;S4f9ztXeN@XGLiY`nj~|9yG;A@zUwz7_tDjqhWRwQTCk-Fi^HpRR8#{*R647yKU^^Y-BX z*oERv;s2Hg9juw}CteT!kDVd&mf-)`nAezF{NrOXvrfGq=1^ zmn=)h`i<84*Zdz(pLfmwvElhHFSz=c%w$uqmLso+{1@KzYxqB&9^3cKd&#!vtw@4T z@oVub)&=6*X3wei>lVMeVh#UxU&jaiI%n2>);RyyPv2=>v|8rfiT~sN6s^lw|Hsak z^>E?;*rnnP;s4y0+iI6rDeGO|_4qF9G2#s~+HAAV5kL6FMd|JXI_@3yg~|Ks+Ig|YBCwmo^?2=#y59yfES`agEm4E0El^8SsG z@7po|kB#?#dAzJKUrM%FW4;sS|MBvM$$F5O|Hr;{Vz~N0c8JVFf&XKVS~u1EXyGf5 ze3re%_w8%jqnDrE;x+zy^CR+q^?(OX?vZY2edO!`IsWE}3EZR}@TANGl=*<+GBZ#; z;Mq$jv3_v4{J+KnUOM4LZGItK%$Rz>)3=?(yub+dMOiNw^Z#U~och1pWj);oMxsOe`5Zw%>z7#^=Bj4_ug?{{U7@tS#Nk>lS{V!j@vJKk6wM)`c9b_c=Kn^MaT?6 z^?`R^x*+rN-m!-N8=CaFo&KEk$kzY0K7Rq%UoVo^cjvj&-iDl}k-WUyWxn6>d)ivV z`(19@)vsTe-lw)t9`gS5;y~+TCk~2N47EOR?2z||xLCWsJ%{$eM_TXQx7&N>LS7{A zzn#0bdvCQWx8AaAoA>us+!xw zK0h0$$nnvR4_dd(YOnr}uaBUDu6Td6?cK!_!T<66;j&&U{2zO`ynf{U*BbNFzU%s$ zHT=80e_O+Y$oso>mi#^l{*RZ3-><;`u~Wnk!vC@Hc^LEm*!X({{*RqKw#NUlbHr0% z{vSJWTFv}FcJhn_^?z*qdkg=^`vd*O|HsDf8>(7&w#MgY_&;vXk?rt*Zo~hvb7g$xk>LN>_&f~%$4;3NtNxFl58!j)|JY%ZBh>%74gbgP zJ1N3@YEzW;K>2$E{*RwOQpH2T|FP5M?`QZwcA9+thW}&Z-xK&hcDBq9hW}&dEQ|ME zyeHebOg^8$|8YAS{*PTKzmI_b>4F1n;_&+v$8vGx-Q1%D@kB#et|6}9!!2hu^9}xb} zZTLTSnLK}#kB!$K{2!bCkB$2S{*QkTV7&qOKX#!U&w&49{5>rHZQF7EVtf1={*R}};{pHYHvAtOj}QDGyI6j&2LH#um(cKk z?soV;c7?n@!T+(#WPc9Ly3M+1c7*r&?YCRQ6T|=U^fsP@4vGIFC_&>Md z|JXRb1OLay^ArA$jq_vvA3Ig%i8ko@8@s>Z?aD?zXk9QlRQ(?x5BOyGKX&%$f!_Y~ z-$wE8In1Ag|6^nRB>W#cMLZq+A3JqoqzC`U#^wJouG+5~9edob&op@=ihnO+{oe%% zPg=vzr!9TTue;p;v^9Jn{2#9mua}iy{LUKd4e#msd+Yp3!@Ua?&s*on`!W0e|<=3+43<|HsQOlE)MNkB#Gdg@td_ z?vFfvlefQVT_O9s?3uUx8vc*Bw@5x8!2hvJ~hTGRjW{Al<;c46@#^?&TVg8u6N*x9n4Z+6l5cKVF;-s=DO{?I?U zllng%@9vk>QT-o}Cr2lD^m^3&ZxlN*v%C5~9zRY_>!<#Yos!<)ga5Nm7^wb_$A@Dg z`l$b7!w-G&c%5iAJeKPdqJ|FE`G5RAK6=;?^?z)f9`pa$i6KLE{$KW>hU)*|x#0iU z@E!1fZo~hvaeDYaHv9|x9~=G!{*RqBLcV_x|HsBWEcicmL1?i0KXzWoVD*1&>_7Y; zJ9^Ln^?&TJ0fW^4u_I)CD)>J(ydV4@JE?D9^?&T-e*JX*9~-BK|6_*_9-#h@4c~_K zf7$R_@PBN~uY&($-{%d^z|(Hck)!$A*uE|8pDukBxbc@PBOhGWb6>=I_D(u`z!S{*OIIP7nXb9wqB> z!~e12C*l8i|G`hbc=G{kJU=_%SKGLK@PB-Mm&y9o&t0i)csuw%Zilaf|6}Kd`};Kb zMfd%#G(FR=D>5?tx>UTV-|181{W?3^-|xY9x~C6p+<)%&Ko9t99UI{Duzs_9d3e74 z-x~8L-R+py=yp-S_P{O-I6b_o-}wXPDHa6GyX%~~{4 z|HsBWy6e6>YulSQZ|;3F$-lAwFE0? z!PE5?|Hp>U8s5RbQ+A%T?bzSj+McRD{kul$@zC&pJU{&(8~Y3Y$HxA^|G5qS$L`dw zg$Mt~?%1}u2mi(RQI&i`{8{*Mj62>-|KAh!qpkB!^+`GD!w4^_SCo4ot|Xk6c$ zMboSswrQ;E|313%ZS{U$P#y2Pelx0XJpPV)zoz2n;Q!c-uk*aocTTUKf92g8Und^$ z^H-+%^`h^lT66tho*xbW$M))6r~c1v_&>Md|J;WEW8?DR|Jd|@wtv_BpWFW`8fW{5 z`G4?#oBnmxJRtlZyMfFLg#TkVY1qKKa!aN4kf26h{fsfz0~^%$3TBM9ZYT5e;Qu1d zHdg zLij&k9$vp2zTaTm@qTb|QfTlwvD=FG!~8#X5Am+>e{6Wyw7b??V|`@I z|Ks+ao!hDZWA_mc2>-{1U&H#p>`qz3t)&H@*dY<|} z-d%x|*E*mD;wQUAvdmigtW!}{Cy`ttjsqQZXGu`_0?|KsVG&0Ok@x^jzM z|Ke$j)c(7 zWu7AZUu`c@|HmFPbFl~i=XQHp|ChIC!u*x$|F}I*?jOwmV|R>}d3bkrvc~TXLSE`< z4UgU+$rivbpGGg4JT{-UsN0Qf9#Tyf!?bRzT>MSUaxe- zx#&S<1HG*$-tsL@J)z!jVCew$f9%ZSe%`lfulv5f{kZzR-10$Q_a=X=?J@n;|8aYn z96x%t`W4@V#>dt7rO5H?p=)2Z#(GTff80KHUXqtK{srIO?Z?zRjgj?xAHL;zYk0rj zUp;3H?+5?K^J9J3>lQw1+cE!cX81GKxPJIQo<2d2x3wJmly#cyFZ>_(KShp*!T+(N zU!#iQm)0|FQ9V+pgmO*f@TR`G0Q1|FJRu4*rjwDaRM#|M>jE@ng*Y zW0%PBYxqAleoqho$HwpNr&ruzjpP0Bf0)6?d4TYLY|Hp>cf&XL2%J*sTf9xdr zeh&VRT{$;F{U00i3SjNn_hKKy#W-5)sq4*$pd3-`|hckilwKFaZ4nZMwZHI3B2rOAA@ zrv`2F-Sz4bpXZ&5&Xf6U_xyW{bq2ma75~TW+2X@~``?Yep20`d_l=yN;{ElR4c6sz zWxka7KW@kT6!<@Ol6+qQ|HsDT1OLZPkk<$N9~<8*8{z-hN#bwd z|JW(A9sbX4_&+v$7W^L@-U|MYohcp*{*R6IHR1o;JOz<@>X=r{k>4WS-vSEzx%Qm~Z!Vn@Hiu$MJzw}gc8=^1 z=Krya-{MN#Vi*cppr)c>(@d*T1s zSu)QP{*Rp_eh~Bj*x9lkG3NiV^TY?j|FI{^yh8ZDu}|(*|5qvVL*f6}xP16OHheJr zA3IYX|MhPVvW6dhVsjtAhX3RBrOWdJ^Z(fNe{A|cHs}Ab@%q91KX$gv)4}?`eEwyM zzlHx}3{Y$z3ts}&b!~b#nF!2`ff9z=a{Dt{{Z1@-WKX$>QV(-N8KRnX) z%4T2Pq8-tz&#&{u0zQ%+zF9rs#?!mi|Mh!slX}3d=l9F;G|wv;xk={(9zTBs^8v%x z$^5>RQ?^B)ym$=j2Zv8sxlujf3GshHH@+CY+uK;PUa+*x3yff6o?e6Fw?xc2y+M88 z#Y^X9USL{8LEHxQX6IynpLn&1l~1i#ABYy4W{vfLlkPa^*HhMCvc4ee3-1{HTkA{r z+$O&8dF$U?x*%Tes`dTi{eJrLbL->hPs=>K|5~3AuL%D)rfR)<#QV>m^NQbYYJK%*syi%-1S`uMTK-lchi{QA+Wq1L;P9`a7T7#qpkzjgl}_(7nJ;i`Fgm zGUl$0kbHcR~i^i27Ef0H$F7<`-aB~aa3r4}GiQ~;Cr9%6 zn4TftRs0`2s-&;_KX#(5mn!dnwtd8y5cPlD9xdJh{*N6j^L*g{+=l;S$I9O`@PF(q z`8@*sAG=~nj`}}#$pXwD{m8as{u=xrw`2Yq{2x0}{ym5PV@J#1SMYyq_!rFoa~uAT z4PS@(e{6hS#QZ-tKHo;Pu4|nkpMT;1xE=p~!~e1I{saGKEuUBZJEf_0jQGgA9&c`q z&o`smw(@Iv|FFjAOWzaitTV;i!2j|63+oHR|G5qS$HqKj_&>Md|JeBb0Q?^t>x07o zu`w?g{*Rp{@89r$?D(bW>i^hDE3(x8v2&MZdyyN4+Ue2ofBd|VxHL!opWE<%Zo~hv zQ&xzl|5J>0k<2UZ9vN>9j|cz9&nx)%X2mzjwmnU5&t2(h*7$u2{2xz`-><;`u_wrU zKlnfP_{C}J|Ja#}QoN$4i)?#}{QhrUw^D2PPWV55-hwy#=jnOgJxV^W!vC=+%I7)wKl{8buRr)dc9Q&i z3jfD0m-PhT|J;WEV{`r=8}mak|BsFJq~ZVAITMGg|6^l*<%#pVqxgBhSYF@Xe6YtF z{u1;5czSp{_&=T=>odUrvGMmi{2v=075N@9uOhFr@Z6o-&)5`4D(j} zbj3P(a*UTh+-$BvctO5p$4 z@#8~0_&+x0`+fWAGky*K$J>YP@PBT@|FN@V`)~KXV2$-X;Qx4kVf|eAKlUi`aqxd^ zczpOjHtv7;KQ??I{2v>?_l5ssm-ab5@@PF*w z%E8`kTR*LBSr7Q9r~hu9C+h{n|MB#B@_TmpKQ`6_hW}&dR@AKj%hy9zX^sD5mloCd zKesXekDXH@$7jX=vGdDAi>9rc*wA>>i^ie!2|q!LE-Qremx?@ zzu~Pg|Bv7ACx;DD|Hn>^sPTVab#CCd{;%8ce{A?3_&>Md|Jd|@Y|L+h|6{|0!T+)0 z$Ke0iSbrAt|JWt6elO<#vEdEj|Jd-|C{6BW;fC1|N*zv)7yi#}_&+w**Mi^jEe{A@$#~Q4PZZNiHN4YZJ8C;IA;jpe2mi;0CxicEgv3u0vbE%ASB_(%9Zc6LmS z|6|ktvC9(T)&H@lO2hxLt7IM`{2#ka=J|bdyMI>>*>Br%d*J{0_@Lqc`23zIj~DzO zd%Vn_ga2d07sCIs3nN1O-roY}*X72=_-!u;@NfA6-tGU@zhVDf&lR}-FJ52n_Q3rM z?7(?{8F7LB&;R!1CdBz&KGwf>udh@*tlN0Lx~PB&8}k4$|IcmsKeyrk*j)eDT6_@vpWE<%pWM?> zy&>*TtpDpa{GZ$Ke{AgEz~`q`&pP}^->NC^MWaWE$791E!T)W){JMHT+*`oCu4-(K4^qk89c@2K~q|6{}3!T+)0@z$nJukI1?u6jCj-F8#` zw(kj>;@4RJm)D2W!~eMr|K~RRpWE<%Ze#sl?hkw+=Kr}3|HsDu!~b!AZ@A$Go&U$i z{7U#gc4K+{!2hwkHms-qkKLs~UG;x#ynf*Ssy7Cy|HJ$|_&+w*%ZC4B*R5a2oAH~i z)qgnJNWCBD|FJp$kB>LJAN(I1?+@^QZo~h%J$}_j>xK;*s{iA5tmg~=$A&M2|6^nQ zZTLSn{4V?-yJN?W>i^g`b!o5ukKIGOAN(KtrcO2M|FU~_?xOyW-LZ39^?z*mKdk@D z`vdd&nod|{m)B3`{lWk7^ql|4?$@Wg`agEx-hI^nvHRbAi?096%ZC@l{699l9sC~~ z*AM^4$FFzS8`b}@yWH4H{T~~zNBBRsC-0B&f4sc?onK$_Gt=8+7u2%oY^Dmq+PyHWz{FKS+|JVtsDPC|=Z@Yhb%kRZj zP3mRcq(=wur7b|7y4tL#T9b2BJ{*RYeHnzt9v8T*grvA@*_6qfX?8$O_;s4lp zd{(D)wVt$mllnhyU$k(sx2C$2U4Nh6H+!#q+|e5IBRkzt+d&=L>ioa^FCJIF7t*eo z&i`ZQ5AEm89{!$>osf8=*Zp7bS{D`fRsYBBLrZJ?-=s#z)&B*T43K#NZ}_@QKc?O< zvZ%lMKX#n_J`(H{R->@cZpMdpu{2m!BfPhlT&+{=`lUR{zJ_gZVY^e{38dh5ut?K3~$;)jr-|!z*uA|HqCIj|2b5 zh8KhXW5esg|FPlA;Q#n|U_1OD8^_1s|Jd|@KP8+{-wA&O|HsDhMEE~8t{?u-ZTLTS zg3RZE|6?c1e3AFxy~i5I*Wv%fT&Oq2{0#U%HXaZ7Keyrk*zjrae=v7C4^Za$!T+%_ z-w*!JZTLTSqWm5n{*Rq39t{4ET`KESVg4VxK)fIPADjMHZj%!~9Yr)=@%{P$4J`n=-Dwg+#v&Rh_!{*T)+ zUlab1jrp4Je{6hT0RP9v`c&|LY^=Wu|HqD#=L`HFJ3-c;ga2d0L&E=Ye+S9;W0?QP z9xC65Vf|k=E+77nw-?{f!2hvF$~?f>qB+);GSBenCo`=x;<~$HwSCtDAf`4^YxCfMom{bRHL#aidd zd_VXkEc_pzKbQvy|F?X_A@zUpvqz}^3;y_^`ad-M-{^4%)&HTV?d<4l z`|JVreo6Dh_lf^wwK9~;lFdSkBhEgig1y&s-m{|Wy2u?r9ERo@5S zb!6?ot+TP-?X{?BdrKQ_LfhyP>e%lgsqe{A?O z_&>KX|Bs!sB17l@v9Z7Ke{9UVg#Tk_$@;eNf9yh;&jAv(w)#KzDDgP(f9y1Q{=@&Vvlqpx z|6{{@!2hwc7iX&fW8?AoC9I2WhyM%vqP2ChJm0YXFZVA=o}ZZi$4-^^19`qZ%1&Pt zul|pX_fPmgK40kmy$J4`~!~e0v#K*w@u|vfZ!T+(bzCHY(+wgzvev1pd zslWTfBOlb+?8|$2M|A0h)n4^0TOL_;Zj*Yzy~lQl2W<4n9lbZH2RwXcpZvw;dF&%+ z4$6AL4Z|0uZB!3<;=)nP1`I#@;s*7A$1fiDo`3tr@Pru~)B~QB`G4?#v%X%h9uVsR z!~Zqkv))-RI4$D-;PvYNE?he8-Tl%uzm{2a))#L(=d}($WDO4(-0L>$J7qoLyk=MY zTGk`BzDw30-ucN@>)XzqlI#1z`qY^->i^#V%{ujmr_Y`he^@V)eb?Dj-q5IK)_2PM zzoa|bSsyub!YgUt&HBKJBbaw+edOq2Z`rqltPdYKBwlfZ^?`%?yvlWPk-R@J?@xSW zZSUFXrQc8x$@_1Y_`i~s71kSfZ1PT)RN3j*Zdr%>)2~;3J>O2hO#I*WsVl5ku9kW8 ze^?vI$7|7&x$6Jeix*B-|L6A38+S+Y@t!IEuhppi)|2OsQ~$^9Rnzmln+D$*$=6$2 zeyI9CK0iZco($&yu_NXCX!t*Nbmb8Be{6i-g#TklkFS~k$A*u9|6^mmHvAuZl>GY( z|HsBWHO&8Gm&)rM{*R4+-{Jq*nKgdgI!F9I{2#Yx$>$aLKX$2n{(}E=8~%@t^?R?1 z|6?b}-(&E9Y<&KJ|8u*|5A~vWf2Pal-)B-AT4&4-^A;Qrs%`muvClV6tW)IoF>fa{ zx6YAyNAQ2V{4DV;@PF(W`F$4rA3H^UPcx%khuRje1OLbOGyGl*{*R6OAO4RGPX_KQ{h8g8yR|EQnG6$1arn7ygfpf1fb_&uz^AW5esi|G7Q=gAi*xzF7a4pD%Ld z-%I#EHvWBw|8pDuk6k8SAO4Sx`NG);6Rist$EyG1b~OAS8}qoYp3kt(U6SB6^0KYR zEza;l%W|#9E=u<%Ue341yhZpweqJh&e~;k**!cV9{$=IXSWgxHkJ~Hc?-lqzcA0pp zm9JLX<>T+uyZcsIWBpn9Kb{_cufYHD_MqYa*b(yg3;Z7&9uWSIoiw$^|FKiV$N%%p zJlmcwe~;eu^8)J>nb(zDyx2N*vK*hfZ>e>*%y+*xXoYp5c*cJWS!G=+pJ(fhS#6E^ z?C^j5{EqdJ;s4mVa(n^)kDW7ah|d3G7s%hkSpS!e;|uVAY|P(-|6^nRUi!3MQT+Q1 z9tr-B4X*_M$HsiJg!cQavA#6?AGePYzXt!urvGE(?@{)j-{to`nZOs33 z8}t9z`1>6GkB#R)=Krzr{BQH(UA8}Yv*W!pxm*3Am5_PY2xg1|>w&*@<%y+E3 z?|y6gKi>Xi`8{az)XP!)dky}r?Cfu>bF0EU_&;vX8y~LzkDVp{4gQaR&*9%c_&;`% z%#VZrW2a4uQvb)!oGQQf75~Sslz$K5|JWnPg{c2y7mOXD{*Rqs8LIw|ojEpC{T~}% z5B`sh^TYqS{cP9YS;IfV|MB*r;s31V`r!ZEe(A**t>Mw&|9JlvR@L}FHhgXU`G2TA zz5ILD@vc{`@%kC?m)ESZen(vA*R3&c5B`tWkNJAPx$h0ze|WvkpT21g&jIsSmze?^S%F?Z0KUxa!1+l!kE!#7XntP~|AqN~{QkZ;B0|;=92Z?Wu%3D|c$EqNs4gbf6e}n&HfBbf_ZAZiZ zaXaV#xefovrvGEZGs6F|;Sb^e_;@6Uf5iMhHhdiB|G5qS*E_$ipZ{|k{*Mi>1pmi| zXM+D@i^4*5{vR8U5B#6o@PF(`IX(OzJ31oNga2dG|GE9y ztc|uE&%g42*EaSK{*R}}^B4ZlZTLSnJQVz&+wgyE^<(1y+{XMrc7^yW%>QF!9wGc6 z8}k9-|Jaxh2>-{1|GONq(;h$gvKyYMZTP6d%w4t}z76yLc>c2ZDD{7A%zuObW5aX7 z|FMf=YS#Z{!<%9LA3Hly=6%cjKlVuRjqrc$(#UA_e{A?X_&+x0|H1#Uar^%G+uAOb z`vd-u&+joZPZ0i(Jvypp{a-fLvxWa-=g9id?)zI>+i(^*Ut^y9@v5N z{sJ5Cm+t-qcHrp)8-CS2Ki*&64)l1X@&5j=Ji&kc;z0jb8s~rcf%5|K`f;!C*E-Pm z1)e@|d*JO0Z1_?4`b)(FyN%bs+kw8auB->@Zm%Q$%I!d(*HGqzx!Wvg#{T>YQh@PBN~KZO5dcbD~7;s4x*|8pDuk4^vQ zHvAtO9ufYp_1*Q=|Doak+=l;S!}r1evEc*Z|JXP`=Krzb`{4iFhX3n%sDa=5zifC) z_&+x0i^2c74ga^{^HM1jGFA%cdVY|*P-Vp z`t{S#P4Mg7FUI>d{2wphlk0>3a~tdby88$J$HqKB%>QH8ty|Z-&~IGzk;Ct(UxJUr z`oC<<)5H3|ZV!KVM|JG9M(X{r9sZAvd3^AH>_)PFaAe%J>LF_ys`rBjg#UBwE20H(b-SUQd9{eBsI`NB`|Hr;QsDb)FHrC&U|6{}3!vC>5 zbm*Y|j}4!8rQ>?rfB3l1cC53;e7}x$Y8&(WGUl(f?YD@3Tk+`{Yxuvr%WJz^kB;j9 zc>iEMU-&;>f8XBS)c>&u_Ufkd|JZ|i*Z4p7z?*uh|6>p8+1sluTxyqx?eKrRzJ9Xa zF8m+6fA>z_z=sz5^`7I4tlRhOsQ!f{+Z|BpR>+$0bFk3GA5wE91{;s4mtg+=QB*mdRpe6y&Z zZO`fxqW+KDrzaJv|6}K*m#P0_XCxP?|6@lMj`IF`Qy;s(qKZbV|Kt6WR54opA3JT# zIQ4(*+-Y;w|FO$u{^9X6H`)HpnZL@r{7rYe{6$MQc-OVA?PZJBssH2tED;Y0|Hm$0 zvR3^cd)%6>-mv4H?eb>MUZnny*WWOxrTRZMK3~B9vD5{NmXAZ~Ka0II7+c^C>X@j~yY$$Kd}m1|C)a7bT7Pf9yC}pX0O8 z*L?ANkEr*9kAnYWM~)q?{*N7AH9-9zJ9di93lsl0qwNv(fACrGe{8Ie3ja5L$zk<> z`29Hi9~*uO{*PTCUJw3{ol`YP{U000zv2IQ`8fU!|Hu6a9Y5S#-Rnu~5pui={*Sj8 z>xaPqvD4-E^bH49TW5^vr~Z%kAFdz%kB$2W{*R6IWa0nVnX>(x%fGeGlI`$+e7uS# zM5+H{=Z_2b{&&}dwmnnU>$-dTZ>)3V`0dF4m#uL;9{z9Y^~coYo4$0`8uK|;ZaHI}B+n1{KbSsvL-Tn0!Czmz5Dj1XZq5-qeX{s0_&=ULP3EV-|FJQT0RGSJ581zd z=l9y<1Mel@uh{c9Zd$PS=A`Yu4V8z~`vp&x`Gcpo`j$O&P`zLH+;H`OY<&L;|K~R5 z|FJQT1pbeW#|!?Cjqf|)|Je9G1pd!$_&;{8+~4qj?Cd#7>i^ie^Tc0oTV~s_e_OjO zvBrEs_&?shY?-%K6}`YZZ(fc6lka@gKTeeM!~e0T%lF&xe{6V{f6kh2ow~5b|MB&Y z^;>V-I?1+Ued9VePN?k#kzU1xan_j&qr3-$E3J#gmoMEx$uAN6nXu^|MB^P@B3%n(8qTv<)C^$cz`a z1FyU9`GE)2`=R0g*q9Fr|M$e+{p$Y`{I`T{@2Sb zeNBJatKKhFyc7JN+wgyE+<)+Yp{w_*|3kz7u`}iSdH6rKhh4eeS9QZ)^?sNy3IE4V zm-T(&|8{QNqy8^Te3|%)$JT$oTfH9|{*RrrJX`%AyLerZ`agEc>U{No?9?>{@E>;m z(W`US|8YAS{*RrrDqH;@J6G1%h5ut`uFX~d$4*_Dss4|hBJ=Lx|JZ5k^VI*b3+4Rq zf9$+fS?d4T>8o;e{a<$Kifr+17azNC#%}d*v&B1fx^I%5 zKULnp;QzS)V`dFi|HmFZGg$o}yKqLR`agDwydPrz9~-YH_&+vYZ5D$+C2Ci+y8>Kg?PR_%G*=4zF7SqJ8Esd`aeEjqt_Lv|6`Z0&Qt%# z)0fEO2mi-Tl6g|_e{RG7vEd8h|JY&T4dDOSLl)($|6BRRM)iN?r(vA9 zzwJ2I3y$bHa=m)M)0fV8AGW?VBI~1d*F4}EnHQL0ec{qsZ_fPb5qGayr#=uZYtLF= zyzPwl)rCWT-Qf6b)^~{S>#_HW_3anWVm)H(3m4CcmwV6p?77o&eP3FimwxG?pCg+0 zTBjcItoXhka_UF2&&hnhy3aQA>(=4zt>OQA-rLQ3pRDH_-0K$WBjW$!jtsUwc<6w5 z#W3qV2M>6In#M=+_HW;_TlPQQde@%q>i@WX$F8mF|JWOLZS=&}&M%GR^D|H8gTw!^Q%ByS{*N6tdVu;r_AObR)&H@3XSdh+ zf9zZHJE{L;=ah6+|HmFVzMuL(cD(#v1pbemD*t}M|FPlS;s4la;`K5A&u#cWHvBLA zAG=cg7W^N3?2=4f|CgP%G)w)T+Ye;biQ@f*%d0wbgLQ(;--}pNFY3K-cKQ0q_dM`T zU;VLxb-sMwf&b(A;d|i!*zh*+f9x{({SEvdufIfoj{^V4F1_ae*hORdsQ+W9RQ6K; z$M-Wd{2#lb@)q@f?6T2))c>(#tNN<{V<$`;p#G1YE9*UD{vSI_{22TnJAC?J^?&S$ z8AEjb9~+;K;Q!e8y#)N9wfsKeSjY(LJo$Y5;*M}@e7=GIy$IcZ$5C6x` znJ<5DivMHh%I9y)|8pDukB!f3@PBT@|FJP|8vc)6F2DDJ|6^kw8vGwWKjHU2@PF)4 z^7;0=C(G>g=m`?`( z$IdP5tNxE2EYENFKX#b-S@=KxeSqH|!vC@1$Ke0i@VW4RZo~hv3&exL|GAC%e{8Iu zEq^;i@$ZKW`TJU|kTvF$$}BN!++JC0)EdW=;Qx4eX!t+3;s4k;9tHo$#_zA-|Jc|c z_&?qs`1=|D&u#cWHasBwpWE<%>>QbI2>-{%dKd72Z1~P6_uOgMk9ni;f7~DZeGmV~ z#_8ez*dyo4-+$u&*rhXL)&H^KQ-gyau=^`XJR1BT@9%u^W$=G&JYMjB?Ba>hUY+8H zqWJe5j!(h=v9rX#!T+&y#lOM-u@fdnsQ+UpPl@(MzVv7m{~nwuzb77iz0Z2=I9XqI zM74E^c=~r|Jnq++|HsRN*Teijc7Z(q;s30!`9F5v7&(3^{*PTC$BT{>J?Gc(f4u!A zGVc)nk6k9m8{z-h@M<63@UnHGc){-@Ua`jUKlneM9>@RS|E$MHsQ+^t{*OIUj#qxX za`AKUf82k}&x8MC!~4SjvGMrA|FQA-!vC?c9sZAzhx0v9~ATk;pb&baTd*0??Jf4o2P#@6^h zHvB65A3I;>FT?+_OJttp)d#<{E*Kr^{o|{ztP4jERsYA=OR@ak9sZAi^)s;Q!e0C=D7+u!e8Ct^Gu6_$K&2ULL$5*8gS0yJ7wx8$JyFj}7ku|Hr2Pa~uB8 zZTLU83+|p}`-AmS|LL1;oh$3t9(ZMrHM|}CAJ315|6^l+;s4ym{69849{iu%@PBOF zKFt4f`&7YFyMFk>xbe%Z;UWJtf4Oyd$Z++4y#J#{)c8L(?%%_8Rz@cz++geb!vC=` zPYd(^+=l;Sr;6u-|6`}fd@uMvHvJzP-Ut4VP5;NH|6|ktxefov9zJ5I`agDfWR3r0 z)Bm{*|HsDu!2hxF{Dl8=8~)F2_&+x0M#r!`u<|AVM9~<+~;Q!e0W|;rSh989gW8?ba z|Jb71Ksyn!#^fms_i`Sc$ojk^V9#i4gY5?`v?EWrvKyX z0S*7h#{JPO?T|hH;qgYjR@)iT{yr=w+TZ`h$N77*%tU{mmyzH1{U00KG5?Q^?eKqW_!js-c3bf@@PBOVAN(J?vv@f8 zKQ=tm?Dn+{zX$(k+hx66_`i@t_0<1i{apAzx8eWToyG6K|FL_uYpMRvZTLSn=7Yii zxefm}epP+-f4$qc()oXETps)%8~X$Q=Qh^=WyAkr{ok;HSJnGr|1kfLjr$k=?=R`E zssHQLw4wUH9*bYEng1vA>M;NBiJfoM%>R>lk??=)`qy8l{?BdrzoKW}^z(n*PXFgN z=Kt~fIRDRW_&@jb@PBT@|GE8n`2@RuTwdsk@z(H&@PFLD`gLm7|78csyt_p~Rn`Bz z`c{qiYj}hDKQ_D`{2v?h@ZkU4?)tB7cK_4=J(bf?Jz%3ojnw~HU-N(aCN)t1hu0(g zpWE<%d_3v@tQ*wK|6{`^!vC>@Zm6sNkBxbL@PBN)AHe^y>o#em{*R6Itl|IIm`4Zy z$L`v_gSY9@dfVUbH+53~$Ni`Oa~uATJ)lQt^?z)5I`}^}E+77n-J@q`^?z)5KKMWG z4;u6T*n|7jtpDrw2kVyGcCP=+?fqpQAp9RYw9if6>BuG4A-%eLpY&R6J)mb-^?%$S zctiL<_K=%y^uAlW(7H>rx?bUw1=gOtpJVz*ZF^ZeW0=aFMHbJ8vn<}`7!^GJ#F!7^?&T*s%h%~*!kt- z)&H@RvrEKk@4=z!|Jc!Kx!y02-eUJh zym-I#4{x?kN-OmaUsu~v`4iOt@%~6Go38$kol~_~{U3Yu+)e8L*yEP2SO3QzE535# zD?RM`#xJPxf80K4@mlqN?D>ngHvJzvG`*{LSEqM3;)MXmwA5hfAs!e7)=1zv6rE z-9zg8qN;{_Gv9m3I(~A5c$OD@En^O;@5`7L;pH8C-WtbW;s3ZD^A+I#*jRrQ{*R4$ zdGLR3WB#Ap@PFJN%)^8K!<@IlSr!|g8AAkLJ zYs}|sviCOYV)2FWfA>Tl^TmxhADu4W_rU+T4gbeZmhJF=Zo~hvF+ULgkDVy<3%^P} zZH?#eC|N6;+vCU9_&?0}gAa_9#{*W6jd?8iZ#LF{#`?cl6Bzz4VOpsAKW@kO1Mq)r ztXBm8$A)i%|Ks&%%6td-KR!N~uL%Fg=WDXOzTp4n+;UL;-w2tv2mg25jsxodqQr+` z{vR9byTSjt4gbf+`dRRQY^FK9*lF{l)&H^6WnK&XpS9dR_&;`{ydO=;s<6g-l}}wQwT_qVT_zV> z!>eKbA0OXnS??C}|Jd-g@PBN0K+OMR!vn(qv2l9%Kfa&g^#T9KhDU?{F@c8d51_`iR>yhr^X=GT1xLo;8G{5|UX(9a%eVvYL){*T*p zWd0fa9~<-i#9_IhC^Hyi7|6>=f%TfQw9N)~hqwOid#$rq<-^zb zHT)k>55ETg=QjKwJ72sa{2x0{JR|%cJ4ew!;&` z|MB*~t9|&t*|r_N1^$ockClIa;s4l$;&ZV6FS~SxtnVfB|Jax}h53JO!~e12%i;gn zI6eFyJ6`+%{2v?pgZY1K%x8rEV`r{RmD^Xx8tW5(_`h!+<@QP9LrcbfXk8&*P(0|P zy#2*8&r#-^S&xzX8}t9T9S#4-hR=lma~uATjrox9f9zCUKe&x`+>#>i@fIIH!q?Np zlS{p01GhfX_00|H0e2l#g{>H{x{-;?!c{rdMU5BoLzpR8G{UJ$2;|8rZ`Bev6H{bBe&Za*XQ z{NVrG-ahpgzkdDR`jNK%+)3}_zRj&qpFJTSvAy-Nv&X%kx_7rec;XP|9a`@{a@cFr zeu(wXeS2kp!>sr2-K+kO*SBNG4)uR*%=>G5q#%;_&(0lNz3v@HT5sDaf4|P15Xt*@ zi^h<(`DZ8+xJGY^X2o2yuVo|%ij~J zeXdv!lkbb~c-d#&JFk!WKR(|(XLnQo$L^BTUHulJndCGe?s9+@_zEBbuXDW z_`{WVt#1)uA+KL+d_K9-@XyxC^7*gReV-#>XjupTR)w_-2;U_DO$ z{W_cVlXa1J_PRg(&$>kZeS!bu{ZlHhZ}>lUzMLQa@A}{GRR32tKSuo@8y*V&kEh4y zANW5uJ|DsVvGMzw&4*fAXUOlxpu`**0U58QQnCu_`8mi5%F zQ^Xfy{vY3e;>3?&{vSI;ya(q0vBTx>Va)$yV?9gwKlcA&?Y^VsD$D-=?+`))X(XhF zkluSgC#UD6o!(1&@4fflNKZ&ePY5aWqJoM*CLoGP?@cM9(nJAKR6zM%@B8q%&z^aH zOV+cV?;kFCuRUc?&73{2x$a>zQk?%&r_CAQ{GWQT{hoyRe`;cee7JAC-Ul~j_~!m?{Ld`k z-2cP!bA6Z3O$?UZmhYSOQSpEJyo9eiT&L7Ge(9Gp%6&6`691>u^Y;w?Pd&;`kN*od z^Z(SNm!>=a7jFEYy2L)u;{ViT_IVEfr)E3;PhDj9AO26x_2d84Tp#{V&G~0{UFL6p zsrmimn^*WAWAnm){hL+3IsaFE*ZSuC_&+_Koc}j7Hu&c!^LMNKWP^V_72D_4H{Rap zyKI@gUzz{Y=lv{OZyf)p*8D#;UdZOpC+qWns{Q@@&p!Knvpxd;Pup2P0RIH>Q`;Q!S5)9v?Y=Ks{Z{>+gwd^S}5%HS-_wf9kT?75-0MG^b+z zpDvHa|EW3Ng#S}>JPQA(W;^~*jUUAS>Hf+$Plx{tH~vq}JWBkZdbAyH!T+i8i`TZg z!(TqfXXcN*(>Kq5{GYC$=Rf{0-1xt6|7+*H{{9$mf8W=7><7Nb*!|b)>mT~YQ{(@1 ze-+sMjsH{Q!SH`-JXp_GKS|c#^UR;a|EWuC{RI4cbCw<17Du z-ABH;f1fD%*f;YkPwxJcZyx{okA31BPm2H3<54iFS8!R!&!W1~_|JV8k261gGfV*-a8mx?VtYjUu5$It0aAutm8K{^Z#@_I@i|!eS5>deP`rX z%>UEz=gibjLBDlDiaH~uWAORuDk(ai%=)TfZ%~*J?P1)!ztDPybk(@YDe?yR9sHk~ z^)-JnW~y)IE#dzf*SXwzK)eY4PmNE(|Ecjy_&;49>owy4)OaTRpIZJ;E&r$H`k4Qx zW`FR1YEF;;Q*(LvKkW~G5C0c#{9m~7e>y*>$Nz;J|EFf2Vzc_o{rTyK+pO@-{X4er zO5dzk{GaqyzDozh1^7Q*fBt|$LH%E?N}1fhs`Gn!{o{i#URmv1^Z#^u&Hqz#d+~od zKaKzMZI_S#Qy0c1y7hm|5Nk$v;MET*d7no|5dX;%>N5F z{!cyByeael)I499|EK2hX8qrA-~0m?VXjK zH#jw@+h>R0o@*ZPrUxn;Z`CVhr{7LL`pe2@K3!4vF29}ihVg&epK|kG_&@ci)I{h1 zwExUw!~caF|EFf29sW;^hr|D=xqSSedURTn^MC3RoB#Ihp8fv%@qGIm9PrINJp7;b z4_}A>Q*-(FKQ+GWl^zFubAK@ZPuGX%!~dyyeDHs2JRlep*#@P9U z1xeBK4r6^_?Bz3mF?@Zor;qK}>-&G+Hh(j`Ke6)-N7=m8@b=i|{Uf|Rwqxh_#dfUs zyW)G+=dEw+@rAGNimPk?*N*jl__y%++c#(&)y(U||IK;1s`G!$vt#~Wxbc5#=HKD} z!j1o%c<1HL|FIqa7jEYNsqt(0zi{LK)Qy_dbN(;f_&;^y#*Ll-Q#Wne)cHR(^Rn=N zYP=2pPtED^f2EtMIseDJGyI>rRnul}{ayJfs_1ouNYIe^H zk>!zhQo1y#7rgZBT;FZYe|^zy-lf$)f6@8Bnpf9w{_o9KUvmDhnhpHJ|Eck&%>Ps4 z0r7vIUHM9d|FiLu&(EIYyNYpD=KtyR%;&@Z>H28a|5ZD`XZ}y8r}2N`J{>>3^73sv z{!iD>=|8)5+NJ#KUUi-i|99Q5r~1bKWqmxwca5r-JO8KC*Dznl{695*FZ}vwVe|3A z-P}B2xH*05?A`wUXT9AC@9e5<^L`tOD!aOQ!<&D#({HEoe|kLefz1E&ZI^d>{Pq6% z#Pv0}XS?rK=5tv8SEuh_?+5rlb)6=Soc~kTYu?oPKXrpvjh+8fGtUnHr*3ca{8;}t z+@0bp8_$<{_h!GnXWQ%C`oB6oz3awJQQPr_GD-p733C!cTd-Mv#A z=l^thJvz5_{!g9It&5xgr;hK^DZu}!J9qBv=Kra?b?fH*pL%GQF3$g{Q`@(9{!fiJ zY*%N6zr223+6Pm=T;@BjbI0J;x0m{E*YKL)!^fBSW`1esdlyIb>?4bO^ZvWK#bSSd zBy{QS{GaZh;jP=c`G4wub*^^)Py5I7XY9_|{`pYb=C|HiC*Hrl`Zn(nl=hADy>aG} zVE%|W|N2_GW^?e(?153u{6D?EX4(lxHCvqjQ%~Bs!}&j*eudp0{GWQs()G^&saG!9 zk$|EXuJ+V1?Hdiu(3&i|<=*!{=)zv_wR0r7w8S<5!M`G4w}OE)&#)#Mjokl#Q8psNByJbGrmXL`W5&; zZO2RD|H6&`Q}cZS{!cy3=C9%Z)W!CF4*oCP_&;@_{r(*Pr~NCjLJs5 zJO6jbp%cyn4x7=}`9C#&kpEWa+4o({|5J1Q_&+uC4)K3#*6X=y)s23CitPFKZoPy4 z@y@aJqU`&Xh;oc~h~v3X(d z?%p2x_P2+euNq_XF=~}<^IdNH7uR~LZ|3t&`P1g8-uL58QT@>RjlQ#(KV|+;*EiYb zG2s8y>2S)Ocr zvED8IPmPzv|Ec-@7XPPaz6<_O?`QO=4~Io<$N%Z{tRIK}Q{(yYe`9|EWi;Om*}B)ETSNoc~j^ez5tFi$U{!&fn4IM|=<8kc}_#J;FTS z3%_{Ucfs1B!Tc6a_|CEQ|7tIL%y;IpWPD3hn}6|LY#t5&r|U1Z`HA>HHR~VZ|H6&` zQ{x};f8oaeso7urpE`4Mh5u6*Y|3^1FWmS)^?aLO$NWF_9GhQ<|5N9f|2vnv+V>E9 z|G@ugd;ZcS=l|3rY(6OdPhD!B1OKNkvF9`XPmMRh|EUL=hsOV@nRkr;Q)inm#{c=Y z_4x3A>f!c%J^oMKVRldF|J3bg^>F@AT{@$i^MC4c+m8QJm)Y|l|EK3u`8>D2sqaY( z2Ri?!?Q>RFtpBU#@x}jz8~>-~{RjW2#;?3uv(dx;^<%#$!2hXd?;q#<-=mkdI{&w0 z-x}xt)F*DP@P9W?-s=3{(Q}8L|9kqwEzbWPzWI>#&II*|^GAYuA3mFK*X}LO1L6a1 zz2L-G>uqr!@Z^P?f_2@xCI&|~I}b?X|9&@Uv-5zrT(}vp=KGG@FF5~K>yb^)12Vr4 z|EI?Dz0=?h-)C<>7kt_1A>Yg!#Q*8^XUrG2ZvK|<)925aH~fq5Q#Ri(x8=7{jsN@8 zVqea1RvknCrSIW`_O*d-vrlOuOH+?T&J{#Yeq{nmd${E4#l)b)ZFPz}~pSI)w?ENK4&-cl*i=6*c z=Pk%|{!g7fcewL^YJR_h{|h(%Pd(gz|APMuH|ziE`JOz(*6aNB6TbV6>%;r6KmCOK zHqQU){3A1(JO8J?uB4Uof9j6oIy?WT&L7`C`1jD?Cv`cqx5C@a>={h>=mX!ZUyA?J z>G}5v|EK2PYy6)&+upzMf9i7c`1n8dq?Lo6|5NjO1pHsP@qgN%GMf*|{6BT+sx0UK zbo$(t8P5Ny^H$-xulARhwQ_{>f7+g5pTF>bYP>f7Po2GbxbuIy|3}#M;s4ax_WqCm zQy1ELwdzmJq?>yGtcka?5&j0ECDr@mD=l|40=2ZAUHSh1N{~K=n zpL&@6z5)NI=I=ZFpPKXI|J2MQ!~d!I`wIUTZv3B`-{0W>)MbmzQ=0!%PqM$y@qg-x z=J)V_YWx!ZFWmS)^+@}?ga1=A5AZ@z1T9 z3?@w+<2%cK?}7i*=Pw%nr!KV5r>y@QZv3B`->2dK)U3aX|5M{5@qcQ3B>qp0zr+8j zOYHfT_|js(e|SCopKd>%5C5kgZ=Wadf8oaesY~toh5rjT{!hPns;XYpPJ(zFQ=V~YW$zB z9}oET4{!3@>AD}EiE8{``1JTc-CwLvjQT6>7uh^z{GaZRLc2fl ze`?mB#s8^`Y`t0hpKtS7_&;@lc`W>&{(fgYS^S@x^|UiQoA@HS+@Tf8oaesVCX{5&lm-&O9mpPtEfK z|EK2u960_%|NP+ib*&pe^3CtB@qao!>p$cF)cn4B$X9>%&HB+zdVlIW!`2J_)AY}L zXN~Re{GVPQ!^(RFNzZ-ZUoUyKp6{T`zVxr(d|U4q|EKqh%+kKWv6O%L9$wTdIJDyH zWF6m0&g~j>y#E{Dz07F_&KvW{0LB(`_{PsgK^Q#u7LT2x6<#rnV6PP6{6n)P?_f9n1N`#ArnjvHjZ=QsbS z#?LYTFWk)kQ*-_Jzi`*vGcRT7zb|thk?a4_srgYow(b0sjU6uY^YBvoEbxu*Yn`?* zst3Ni*q@*6uYa~As#jK7=9~F|_&;4g9tHoWW`FU2>Innw_j~65)Z@(e^?YEZzy2bd zM~MH^{?hnAHJAVLAJ+Kh@*ntOZB*m`bb8iX#{Y#I{}*oN|EZZbi2n;W{!fk1WBp$> zJ`ew=W`FR1;l}@|nLmmD3pf5x&Etpv3pf5xjVHbJs%Z^Qqo@oo4&-?knv{x96j|I_W0 z|5LMGEB;T-<>CLrjsH{Q?eKrfZ-ME-}b)~ky;rGK>ugBvTwf+Bb$IioJ9%uOaQe)-;4vv}U7km0x&mB9z?|<8| z`}aTEd}w%oW4&VR{>1Jt?+@Yg|8G0i`^BC=*7sGl`D)?ot9n(8=c^sUu%%0~dVb0ozos z>?ZXp*8kP%nYV}kQ{xTse`-7+{?E6~6U6_inRkc(3pexs!j1n^%m1nId(8h+H)+zu z`9C$M$N#D2|CZ0WJj(y6<^RIX{6BT)Ce5Ay3pf5xjXz}mU%2sqALLha{*QTo_x$vP zZ>|5U?cATt|5J1S;s4Y;-uOQ?k9Wa0M}4<9?>D^0{7Wy@e8G7?8vm!pcQF6&Z!KPQ z{_h%FKotL{=K0&dKRw=$^?!AF zH0%GW@q6Lt-~YBRH}4ldKmC)>r(Jq#(JPUsZvJBm{_hv{DjWY7KK&I}M6Z912Mlk& z`pW3nAM5dkw{v>@pYDI=^Wp#0m)EH3{Ga-=E2=pESJ{_2|EIpH&Q;F;sqvZkKRthF z{GYl`ojO7Lww2wmVMFKtbbjXfG5=59vSmx>|J2O$WBy;b@qgjQ|EZbJhyPRK`|yA2 z-Zmf4=J)vS->#MOf7(vpdF3X*y-VA6&i`q9*LLll|5JDG)Yd#=d51q z{GWQ>+V#%=saLMv?EIg4g{|j{|5GnEFNpsOH~vq}{6GAkx_s(f=l|3bCNFjVPd#V; z#-Qh?J^bmXFIyk1tykHzZM|FkpH4q(%?{`P)U(&_bpB88Ukf(x4SsmMi$DFsE&H7R z)9E*?tMGs71@jg=|EDgPKHvF2^`sRWoc~iVv-@MijQ0NWm)rgI%+7Yc@q73`oqpzb z^Z(Sdmv46dFWjvETiKhO|5MMm^?{lHr=GoWr<*4(1eeLyq%>!@yPVHQ={;#%A$f#KVS3R_>m-Bz^>Kt|cFUQt5VE&&v z-h3JU@Aai-mOek5GH6nT|5K;i?-(}cuR6<~Kg{mK_%R=FsIAY4er=Qo}c|CjZ%L(c#8o6_C+zo7LY=l__0hW}Hi+xL6- z|NQz$*IN%(teUiG9?L z0{^Gy5AP@Vzjx~#tnhy}?`Q0@?ISgByuo=t=9%ID)X6q44gdGZHwT>m8)P1K$buG; zk2f7~-Y?F+-+Fvkvq-}$4><3~e9VGfjU!Jk*zdd_*N^{Gr<<3;|NZUDea`=J{_ED( zja;{OpYwh6XKiZx9z3&;^MBet!d`z5epNj(qUt{9`!enO*PUmp`NqfE`l^v{X6<#} zkMCdcf9jmYL!AFp53=V6{!g83-p~BS#g3ovab7Qdc^W>$_b|8K?1#RG+v92Toub(d{}*oj zpL&wbC&d4$C)hkZ{GU44)+fgQsng9<eWGV}k`^=HL7 z|EKO}^ER0Or|xgx_u~K5y{GkX{!h=(IP;Cn|5GQ<@9F%XI%{3BoByZITRqtMKXr~h zzW6_N_KH;J|I{PQcd-7iy7!_%&j0z>+peNu;k~;a8rXJgWNN~`ly!TSSl9G@{xW-oC~8z>{YW+j_xQC0v%f#d*LJH!}}#XF|7^H&=MTvj>BBmp|wG#H~lok6oGg z)QZi{1D?F)R8V(Lx2P`Zl$-eFe>OQEc<#a(yjo(bt(%+=Jb%m0%%Ag(_d9a-SmL9d zH#skO{sQX>-;wz7y&Ihm-*yW)Msx#W&W^6lKRZer-R6W zt9_q3eZo9qQ{N{~9}8YS*xL7rQ%70v*!PhW<|obn>GJj;+UNYA`i6u1o&Qts-m?=Q znWWphd+(0m#fc@pckJ5c{GYaO+qOO!|L5sRx<5Bqb>qCF${4zjj$r zvtXld{GZKsOw!}IXxS_t-^yMwJ(zWNuW$U{M}ND)_xOcnyuT#r{ikqBChtGKi)IdX z{!g!mlG#I?|5Nk%75}GZo-+PVooSvQ|EJEf_j~-Gp5M$n!~dz%XW)aM_NV9X1Lptf z{QXAvcK%P@uDq@Df9ejS+6TwZzU}uvbyO$k|8)C?+dL!upSp{!pZD1APki^Z-%H{D zba~9T-ucqs{q|wz3I4q7E8qD1f@a_PW`6P;Z&yjy<>#3H-qq`J-+AW0@qgOR?-THU z;Xc#8rtjQUBZ7kEwSD8ktNyyKZ|3XX->klG=Ic(I)4(^^hyT;x z9@X}K>bu*lF_;{hMNHYutXE=uv8XTR^l|LOWTJ^oKU za{gfF|J0)v*uUrI|J3Ey_&;@-ogV+E#uwuM)XewB|EZZ5jsH{gdmj9sy4api_`h)D z|J1Bse8bPiMfD@~Ci*T~n(F+YKEKiUKi~Fv;Q!RcODg=In)Q$If8l>vJ5r)Pf>8*KGG+WaHy|LX69V)H)uKYjimX`dJHe`%tk3(*_p4X$fN#7} zyNnxr4GrpM*i2u{&#1U z?GOG>T{y#@U*`YR#k10b4_BV{U22X0)Aka3zsLWnnFrXW%~{|4esWEf^Zxem`h0%S z1>br0e8>Ok_Kvl`{})_#t3Ur}dq3SW=r-T@KK!3fUu3^;#s8@@tt0Q<=}$kxydVBg z`^WE7@qcROyW#)TrFQ%Af9jIysm}kY`F$h)Pn~PW$MApZ(e`^y{GYnq=11cH^mxes zg&Y5;W<3S`U%2sqYUTmr|Md4EjsH{g`%V0xn#UXer^eqg|4+?4xqHq(8r7TM{CQO4 z|8)KMGv@!POD5Uxzs&!s<^R;9?D4?=smIv!1OFFp{GWQH-GBH$b;-;G=l|42HXjiG zr_LTX!1+IQoXz)T{+~K|+92ou)Z9P#KXswKe(-;4JS+ZB&F??)e`?m_VEtcpv3Xhi zpIZJe-1t8=$6J~Ir!JWt=jQ*ZN17jI{$IG6|EI=B)-Qa|KR)#P+kfwS^o&8lLl^(x zo5yS47k~84`oWVsf8d+-gYkcQJ}^%a{}=9epZwT2-tYe46W^@=jQ`XAmD=y)@qgjQ z|EY7v^b8(3{kiWEWnF?pul&__j?Mqeul{%c`pLE9@p}{gQTh7*&j0ECH#NJn^M5*C zJ!n{4=l|3_1~qp6Psa~C^=s$+pN>Cw9oW(NKlR|a{`S|?*^M7j2&-_0%o&^7=W_@4$pPKc9ng937Csmxs8*4r+qw@^k z!;We>J_gzcAZ^4sa9|E_Fq z5B^V=mz|X0{GXcnWcWWd^TqIgYUTst|I|EQ_&+tiZp**7q}V^p&iCQ#8gAL@8=r;$ z({>vFr)K?W{GXcVC;m^3hsFPeoB4lgE)V~w#@pfl)c895pIY<()OacUpPKbe@qcPA z5C0eL>hD%IzK;2Sx<6?ApPK8(|Aia>r{?nUf8l2RUv*wuy7Pa!{`|p1oc~j^zAgSw z&HO$5pIZJ;E&r!3O&;w0pSmn1J;48|%M*t>|EK*aOQ`UFdOdLc_`h)D|J3+Q{9m}k z?`PaU;U1L|J@1eEC%iqjnQs{09^0{AFm}FQQBt%ojP399c)Xs&*B|TK{;$pZd-(EW zJNEKp_cwNXY~zFf+vUglz1WVuyx8XbH+=cAeMOAtt5G+4o>=VszUuX&x5v)!i|yFc z$6g*jD7=4l>;BL6e#6@v)vfSRBp+KxZO|EW3ulLIRo@Au|i$NhG0-^Z;h z8*lmb;bVR~U9(nYbN^kt@u=TkyKar3+m}atUwcKh;K8&7mugS78A-L?OQDBNo$vd~ zYPLSE`9E!E-XH!?9hfh||Ft{#g7beg{_l!&FZy|V%>UDN{2u-<+~Mcf|JL_?-|7GV z{9pL`s#cBhwlN*p?GK+mw((Wr?N?U2JjlJc|I)n2s$V*seoZRt?c)DB#b53`C+qRz z|J3+N=KqD8`G3C6D>DC2&HO;-|Ea6lJV^YXo--rKG zw`$Ye`9F2r_SZT8r^ff;|I{5@wRZFW)T~d7|5Nw0`E>X{b+0zMk~akNJP$X8xbLN9Qii|Am|Nf7P7-ojb!yho`9C%DO7VZXyt*|i{GYmKtt*`W%NY8s^M7&Xsqug6IxRW`@3o8f zujetdE9U>{^}W`-9P9t;^}5dH^Wp#0_&w(TsTbM&ykGsczwf0hD(3%b`!ZYq7yqZ$ z{6F{!cw>-cslP)U&27a{f=fc>ZeV|I|4P);j;EE?BbB`9Jm8B^#Xo zQ;%P^DVVaNtG~X9%hx;qr|nbC=du2;dhxPVZvLNo=!k6R|I}57XE^_-ZfWxf`wr{i z&%bWkLg)Xq{h;|g{GWQBt=EhHQ_o($$<6;$&se_E`9Jl{6`S1rKQ*Uk{-1imn(fa2 zsi&{M-uXZEfZQ_Y|I~r~J-O-9wf_7;vnFo-pSBmYxi0u?lXoK5Ja^dny~+K01;2aa zE#E^2wGW;@{#)PWIdQ?I(ZBJXVaFd>|5xWPnh+mMyZrS?^|-^%`>{R;{x96j|5LMm z0{-voGdDW_$NCBQzxJJObp9{HMt9)<)R{Aq-Tc312M#&^$9f_7KXthsk7E9x8o!1A zQ?uS({Lh|<*fC@0{a8N;|EDgSli>WHy2y?<;s11g8vm!}_s#e}?O(qA{xxVG^PtE!r_&;@){oWS; zr%s%i=KP;Jd3L(JjTajF(K+9I-}SfK&iWo^&yVvnZuULcj(_6+I{*8K z^NGw)+_mkdsQ!A$Y2SIaz6bvA+oeaH4=gt?f&atw;s5YQ_&;@;%}2rdskwhRug;HO zI`)vQ)%)G`bNlgsy8meWpPp~2^Aer^)AMTIl zpF1LD3vY1VkNXGzr^egh|J2M+#Q&)iY`!7>Pu*vBZ|DEi{cXMz{!h(%Wca^u z?{eRKpNap|<2lmS8)p8Wy39Pl3!4io+vcrwt(Wh6tbO0N^>mK!5$5;se|kU5vi0`x zf9jk~#m@h!^S72c|EJEf?ZYRg`O6!+CfE5tzdz>39)2jn??2zi-;LNZ zvOX^UPtE+hcZT%#_a`2B*6<$w@#giqzDw6g)|&^M_v8I#TYsDXH}Qb;enai{a5KL z&i{qm)^GHuA8hNh;{UWg#nxZN|EWthWCa7hedFTF+}+OC(JzgD#W((M!2{3x&b0L# zYd3t_cdgGUzr*FEcFMz zQ_WA{|FnN8_WZ~Hsqwk^KXsOQjc)gy@{JGtb=_mW@rl#s9P-V)L|ZG;-yiw*dc^S5*q@qg-}wtg}GPmK@6|EY_&l{x>X&e>Ax{GXcFBmPf4baRRG zf9m1(`o;gLvp1DG|EJE}Q0)Aldbq8hjQ>*)U02}zpL&4pKmJc0XWo(Zf7K(_a(h01 zSUud{AMk(bA#1Xo|I_m|eRY=ef9hdtGMxWY4>y0z`oC(e|Ep&H7XDAo^NIO?>O6b@ z!T+g~t!+K)htyfyih?0McRzIZmM!-8*1nXTo2FRT@_onIEq1&h2wtzb#reR4=Wb*^ zV8UewH#-k_==@>k2m0Q3%hBNUz~>Vt#cg&z@W5@ynHQM2`_d-o1CQQ%GWg@~yG3=q z4|5a$G-Z?Xf%v=zQx-;b+=3m64L{lFeBk+8ZVDFGIi8rZc;k0I@FrVN_>RPznrw6) zkn{iS@rQil0iS&RY2P>9a@xGyTT%VVH-GVc@A*@<9&V7N%e(vR3FrTwxM_p)h4O#u zlc$b5|EE4}^Zjn>+Qy&%#L+{nckKJ{(SyMclluC;!TjIP9#8PS*X98}nm5Gv_B}g- z!!vS{bbEL0xjs1gj}qV4@7x-UDIK4r`v?Em;FmL!bbqd2zk>VI_cojN_xcZ3CF$|l zyn12q$sHSgFI+R9wVspo_{~^6&AjJM-}9DC4iY=;^F3?9_+U)eQ%UDu*%fJc&ykee zd4>Gm*>~TffkB5^xA-14z7y|HNqYa8Vji6JfA#v{_YL?zb*}wh#NPk>>2vMhFMEIV zop1i%-ama0wa*Xs{_1;}y?@#JukZ8~nY=&y=Jjds-@Y?!KApY4`%ai;>tmY#)BcXM zzgN;Wz2|RF;i!(mEv-NB-F|YX;HpRe@iKJWaxZd2c*?DNg)iOr+B+kGv3kG1Q&cW1C zjsMf-F+Ussr%qxXxcNUdpO^4|YX089|Aia>r!Ka?KiWKz=9~3EUu-eNH=b|P;$cyZ z|I_}mUMc=B-1t8=>j&fi)D!If!2hZFJdghiH~!DJJwEt9HJ?B6e`@?2{x974KXu8{ zq0ay5^Ih?hAM67jEYNsqu37KQ*Vv|LOACj{j4$J}~}I&HAnQKQ+%M=KraS zZGI*GFWmS)HP2uCU%2sqdi+Z8uLn2!=JIUbu5ae2PX{GU3_K9A%7)c8RAZ{K)7vt+*Uf%re2p0>3;llAu? z>yzUD)XX2m|M@mQ*RJnz-}s|{&OG6p<4^cMT|Vc>|M{Ml94x7GlRtg2^@yQoe6v5- zuDLm?2aG!B&(Hc288@8w&GDwOPhRlN{5|}izdrl>1plYz_8nPtyKnaQ&O7e#&AdbW zpH5Hjn|YVtAH3A$Gk5#u@x%Y=^riDMoc{|q^Z(SWUyT1#7cCkRZ2QrD{_>_QObvDU&PK|5Xo} zp6L9adf3cl=l|65f8oaesd+r`e`=2Z;s12~dDD`d|5In%@15~~>e2T5Ue^CrPqD`v z|EDgo^_}s5>S8;-hyPQT&P#LtPhB!M)%ia)^Yie3;b#3`b=F*4kKFv9I(wddKDPOP zYUW$w|I~T&Q=I=(vw!$MHS0l~nERT)KXUE;Y{9wLqZG8?3e~<8gYP>G~Pn|b4+4(;;-Vgs5 zZv3CR)PApy|5G#X5C5kwwZ{Lci_QOCKj6>43(Q}Rne!Llc{ZOJ|EJrVGrEuSf9i~~ z9?t)%^NPAV|EJd%jsMg8>7bGxZvLN+*YwJ2=lq|JSH}-)>HMF%PfC;ENaWjO9e-{- zpt19R>T46Ob^cEs*S~l0$s?Dg==kHHfqk9-Q|I)G_JK71@6LOxIR7`$zHeaupPG48 z_&+s11^=hUSF!$YzuyMV`^_-#GxyZgl#4Y2=k2B@rUrR;P4kV1`Z#{3KRsRw|EKda zFAD#s#+yAmdya2B2>wsoxqkeg8vnJX!90I`oF4zD{lSai|J2MU#Q&-Be^v7r`NseK zVccTh#pd%KpSvWgZ(Fm}H}e;F?po#>4>RZZa^K7o%(;C zo42j=x0h~zWWDc^@pe4g{GU!=HZb1#KQ-$G2w z&Hq#L{J{T(8~^9qd=&mqjko(^*_M<&v;GtL@arp6C!`K`{!cwVCC&LiHS6)>|J1C{ zivLqjN>6qEPdz@h!vCr9UiiOoKQ|H94uKQ;5(@PFaP|EW1Y{!fi( z!~d!AYe%Q;iE8|x?l1QLp~ZXscJ?>xtLXmihJAiJr=M4Szwd(dq0ay5`U-~(bN){~ z&O9LgPdzF*)%ia)-jVr#;b#7yn*Cw^pSmzH!TCQm{*(28{q3>m3-kZ<{9-%)PtANs z{GS?+jQ>-|&NJoy4EvGqYu=B-r;qi1Wij*k{;xhS_WZHFZd{!G{TK4vV+a1f0~s`U`sZiR#$( zdK+FHJ>M_Z=f%$Ri}ikZyYTI;UAuNv*QynL`88|S{IA=a*N&cN)~r@_H~-I$p*a6{ zjm;y&|Eak>_&+u4k>dZuHtE{5|~N zPg5^*eh`m{{|h(%PmM3c|EZhX_2K`*jsH{Q`|yA2YZ}&Z{!cCcr)E3;PtE$U_`eQ! zJ?s2m^J9yyg{NKbsKJWbB_xZc;^Lzi>?X2$`e*VW^ zf3;ZO7vuNvi{bNg`~F+U`oCH=syqMJ=lm7U|24GrSMh(dT32=ckNJuCKQ;3J@qg;e zFRxhtH{AF?HLrjCpPI)L|EI^3^`P;8>SotAbpB7>qGgj{z|n1fd)w=pIRB^1V?Ezn zXKeGA-=SqI=l}fn>smVhr*6@rh4X*v>#n=b`9F2nW-XlmQ+L0%rSpI4ey!U%|EC_< zuA`g(r|#Rav-5xI0bRPe`G4x3UAj8|r^W-~|J2L}#Q&+gw6E}g>TcF8=dSVFY5bqI z_h{3?`9C%55&ypZO23_MJaw7BKbdzJm$%e6+gblNeEyYf7yIp7q-Jq*^u~RMl>4PRMod47I>TNqY|EFes z?RD{QNBVztsKV>n-=lYZ{afD&sqKQ_T>OpioWcRYRU6*)ol)K`7&!P1-$gdx5C5mj z8*azr&iv(-$jm8+obRLS{OD!hct8A~w#)w={N!MT|1)oOYQuApUzHwo-Y?sH-d1}p z*cvd-@8#M&nm$vX_MK<*YVdzLz5HLe@qao$-+$o$)O=sT{696`FSYhBeKYS5|EJ62 z_rmx;?JwRB|EI?L;s12|=uba<#P^WN1B0=5UGhEHj%PCePxl}5{aF83jsKf^|HHmH z|Dk0M`OdKQEbxDq?Z44^&cU;io&Qr0nUm`LpSsX~kB|RTb9@*7r)GW}{!h((x)Uq! z^Ue25_`he`A9fzF+&m!uPtE#E_&;^t!UX64)SCaN9x^A+`9C$^H{t)(gKa%i{GU4O zJO8I<{b2l`Z}W=yKQ%rO|EK2s_&+u4LF50_%qPMBsZ(vfUs0zsz7uWz5Bwh{uh(1W zQ)v93I%!f@=l_`5H+aH@luVoNb#Kzih??8aTEXFFR$#cXf8pk`b@}W+{!jatXzJ z!~f~_;mh!U;l}@|nYV)f3-^$(=KALQG5nwIzal%HjsH{g{UH8N=cn<1>Qp;D{!gb* zv+w8de`@9@;{VinHXj84SJ@T*Pn~Puug%<3>bJ8V+29t%zH@D!Tl2dMD%-yQ|65|7 zZ#>d7PiI%Q&HH<&YnFe1!*AjL^!_$_Ly5f~4)fc`Zy6bU@>06*vdv}A|LOg*U~Pf( zf9i6Zr-T2~{+HVPNc^9g`8oJMHQ(oN`%zzi|7F^|o%;9n@{jLuTmSC1gWV%Py|CYT zzbx|(_&+u43*!HN*L}b9e>}hNe`>rS{;%QDea`8xLPxBb~zmxU%I{(+(d?5Z$&Abr&-{Z&kIR8gyzg92uS(`o1`}LdACm2z+Zlvj* zyPfwNVDl*Pf9f>*_XYo_=Joo?%<7TshP$2b!~Z5WsOCF=E#JRh=DW=1?b-T>7tNeG z-$&c}iN5n~{aXB=wwG)xbpB6Wwk6N`KXu8b9P?%$`qSra%woRN#WU@9Ip3GFJ_G;Z zyLf$Oup<49i%;IY(|H&An)5IF&R&-j+zg5cZr?9 z#rBK7OV{TH4}9=|?=rTV|I_{z+V|7=KQ-$^;{Vk65A!$v{A{=55x(=yo8kZb=~res z{}*ojpBg`c|I_`)_g(hizFE%~|EKME9Q>a;+14M#|Ebegr#t_r#<$`B)Wx>`F!TS^ zrCSP}{|h(%Pn~0rFZ2J@xm)p*@qYiyt$&u<%Qw%5FaFiRclPF7=l^v6EPH-1|4+^O z$oRi-)l-lyv9edxaKTO;4xejufM!vyF5^5<-J9&pv!O?EsX z2-Js8?`1wEFFfUPk_QJ{FH#HaeK4W?h?d_<>|E;UO!TG`4&HLg1)VJMyJlM9shVPT-P6Yd! z*7JSj^kJJv*wpv26NjAt)A?!qpZf6OeZiK8`X*_A4;|WL`A-?f`HXkub zw|D36?LqmaQs3LI-yGEMFd<3z&*rV`oc~j=HUDS#XOiyUb!!(n|EFHHa$aDMO_Cm; zMQi2+EnnT1q{na8k}3F3-;)=Q3!3fN=X>nja_9f_epouop1c`Z)N^ZJ$iMf^MC4*_U{w^PtE;_|I_;+^N;a=YUat||J23i z0r7u&zZ!3!7x91U3HJF2|EFd?;F)GUeKQ{%|EKNzz6t*qZv3B`&p-G-^#J?4h5u9Y z`y2e9n!iWze`@~T!~d!Idl3JpE?AiA{9m~7fBHPc{7d{_xbc7L^6&hgdYt`xjQ>;f z`5yllZv3B``v?E0F0uO$|L5EOJ;(or8~^9~JO8K8d!@_l^eB0y6{695*Z~dZK z{``FYzx&BKQH}r8<+I*1{!g7_k2n5L&GQ5Qr^c(||J3+B{GYmPO;&*aQ%|(d=QY-> z^N+`P`+Sc7)8jG9K9Ax5)MfU2CH$WnpNRic7n(=J|Ec+V1^=h(8Ooo9c)+JF0IzMRsrjc>*Osk80#IsQ*wXuj;}GberH`_8;}$~W8bf8o>P|J3QTQ=I=( zv%mO1-CpJu;{VimNBo}}Z#bvy7Jqqk%HCUjRZ)asE%uinO2!kjec z|I|D_%>N5F>;J0V@0rd2g&Y5;&b8xR%OwZ}?_C^rm%x6V-nn^4rR`=fk6`-im7cpDvH}Kk$EQ zZZG~%t@(dy_7DH39=~XW^MC4M`@K2y|I{OGJr(?4xbc7L@ss-pEzf_Ltm6;kY`)|D zuYcsb)E-~_pH5HX|I{VpEBs%$`<(sMZy#avn3?~l`!~I`oAZC_+=3p?|LOIXlixj< zlJcd0{SD3S7W{6>KmGe_{NPs3|LOR2YU*{)|EUubn>qid^Zb7K{^XSQN4|~R_IS-y{LQp~O!1v* zz6$@R?PG1e82;~pFaB-EU#?0mF^`7-^F6@UPkm^*?;`vDrv8&NeCH1s6#VV=nNj`f z2eT^MJls#eoE_E2s?GI{N5lW=`tW%8Ki_tH@qgjQ|EY8P_jLYGozt&}^MC4m^Md$4 zb)oGK{!fkX!~dz72Z;Yu<6-cB>Or=?GX77^`SE|@#{a4DGWb8;-!%SDJ;J;Y{!gc8 zz9aMh)NIH9>GZ<~#5@0|#s@L~Pn|Sqfb)N9_7DH3%fn}~{;wLpga1?Gh46ps(t#EJ zFWmUQ%=~Yh|0}WQ2lM~bqZ2FqpBf*B|5J}0T;czGr>8joryiYF;s4a-38~KisYfLZ zcI*GD%Lb*m`G4wS+h6>j8V`m43pf5x&FcgI7jFEYnt5>eKXqwpN`U`UGfxlyr)J(> z=Ra3AxBs;xds3c%@+G3Z&e>x=Xu%Bd=99w>RubzHdHXPR#nXxoOd!tt>g(%atY#jJo_-4;SmzczuNT zCwBeYSnn6x%?e&6|H_dh>A`rjkof5Vrb-Me>G$NInj(KVyJ-Zkdo!k5>$<`w_7udZ1=YJ0s} z(Vj1Mec{V%Mz3cYdw%wh^?!diDv0ubYAzrDr{?nUf9h(s{v`fSE&r$H`tW~hu8;M9 z)pf7B!udaS6`PlZ|5IOHr>66NYAzrDr*2TUrd$74jkm%7z1Z;E$dz~1N@d;_{x974 zKb@ZK_&+rs3;!2x{GS?shyQ!MOBLt;uC8Cx`9C$j2mcpt{GS?+_`-e1{N**Mdu8xw z=gMaL4{ti^w>PS1x4&U!*R5x_f7cPez0TEF1{y$u3*-OPtnZBfQ`h=#{-2&N%(KM*saemO`G0EWOXC03__JZPE1UUp zrJJ_;?VTDov(L|4qI&t9%I5O6|8BG2&idNS|I_}-|EcBw)ID0YasE%uyg=svsqul# z|5GzBkokXV&Hqzt{a&+gy(KXu<$*9PVBOZ@geEt?1UKW%T>x|#ETYCI?N|I~qbaQvV4zgnaE&i|?L z#rQup-g?}ViT?Fi-TW#3@2wA>a{jNr%@4)@sR#9obN(;&i>ICc-MW6W^MC5)>nhg& zRWCH($NWFN-sS()@_%Z4T7z%<`P0+P|Et_y;s3&o|5J}!y4v|a_27}?o&QtMDX#E; z;b#3`bz#vs=l|5%Ipxm(sfXm3IRB>}oLl7lpE};Qv;METe|CZMf4V=0`sb&qtPCdxP_Scsl%_n)O%kf2S`TaQ=^ZQ24)azti<8 z-^}~l_19lVHU3Yh=l8AnKQ;64@PBH4FOC0G7fc=C{GaxR^-1u5+W&m>Vfa5a-tU3y zAB}4KpTGSak2L?M&Yn2X`9Iyi%=g3psaf9_|EHG!Q!{Vz=W!4E?OZ?W|9+l-$az4# zBJ2OE3$5{g>S8+-*!(^GpPKc3@qg-3_Wck34}&%`{(QH0Z8kA)tOA$EV^|MYwsYU?ZE|Li*y=l@v$ z4ga@w&3@<{!d+Oey8gn zm-%Krw@oXT_|CEKx8AJ1$T#12^*KA=_qY|q?D*_l-+VuNa`$Y1f6;%xZl-U}kN?yC zIelZE^MC4G`@RkTr~9AA|EV)pXFLC=9=v3z^MC5x#ffhIU%2sq>I6H!j{j39+xOe} zKQ*2X|EI>=;s4Y*cK_TmCewHBnoOIII>Nu-jagsp{GZ;>f&bI>u|6>VPmM?H*=m5l|M>nL|EK$Ju+8(r|LO5fv+vvSe|r99+C0b~ zoa_?G{%WuDeyn$l|5LL*d6PEnBacko>%1S0|5M}dTIRHj)LXH~dA~&Su=qc9=NY}6 z|J(Na-Om4Yo8329TeETGo;kan_v8HdKQ*2K|M&XecRByZd?Wl{mG!%v|D*ALYWY9) z5PLtv|1JG^r}KZz`^5jLv+VK2|EUL?Z^HkbUc9qnJzw)s_&;^7c`N*%x_E1a|5J}Q zKW6JQUi{TJJDl$uy&;$N8+~VO&UXG!+cRwaTk{_mKi|5eV!oAmE&QJvABg``vpz8X zPn}~v0{^GRU*P}3jsH{QHSmAo#{Y%8c*Olt{poG@`evTa&MWWq&G*&#Kb;@1i~my> z+4Irnclpk;^|zV-r`u2C|J3Y%)nD)PjYl!t;hWcI;-+oBd40a|_D0{#^ZfI&RleDu z4!suoX8qa;A5Hh2XFl-Q*>S#$?eThPbcyfMP5I_~vVCXS`_Zsx2m8*p?f5_K|5)>c z_&@b%^L+R}HRm_464f^U%6GOs{x(m`ckZTayM0xB&$M}w9eREKur6<^z5kgX^_{YL{e{!iNrZU69p>Z$AUxIg{nOzJLmrn*W2R!-|$%}!IyPvKlD-C&5_s6?N3>E^D+*A1oiLU6!~SV z{VAKz?8OHrd|tH4`M~Qh9CZG#`CA(+<^$e(Jm|drg#`5t=KpM7U}E~TjTP$$UpN}v zv$=a>yV@HoJfLkqJuu(*x$`HS|I0qS!TG@R<^gT}*+lhCx10%T_c)Q*C2526fOx-Q zPv4n%$L{sc1D?KcD#-onVc)0DpS1aT&m?|zdY$uuH=R4}{9m~5J^!iSe#ZRYxQRiM zwx2$8%+?>S;rr;Blfmru^?V;XdDP|+HuHVt+l=1_cL(`rf`{OJMU6lXQDG@7xm9-(Kc>-PZNNTaQji(*3h`%bMUf(`Nc! zv3|Mpf7;IazB`YuPSX9qWW}7otY4BIpE)aL27fQuo}|Zb#*(Q#zP?MBj14}iwcq#f zskzSo>G_m7W2p0g>hy`p&i|=XZ2dxee@apho{ znQv?FkG?a^hvENpde)D(_gB9i|7`ESzVXlY{_LCW_Wtdg^=$Ef+P|W88P5Nyr<aw-@&i|>4SLHbWr_M4j$NWF_2=h|-KXtCXzvBPY z*>->6|J3|G0{<88C-1(>H}jg;{JWNK`9Ix%x%PR5`G4VN{+~L>-kO7n8ivLqj zS(oknpL&vgzQX^h@yhr=y`RzeKQ*5(@qgjA_1S&TU6BzidaH9(x9#1{cj>Au=l}G1 zq1aB3|5Nk%82_ivxBbKasr#?ZcK%P@%YKi6|5In!zo+;=^$`1e4*#bvvCl8~KQ+G> z!~dz}|I~$x(rmrz5q>-CSHE{%R#e}xB*%B5{d>&(KYe~GvGttsf9eU==av@x(~q^& z7d=(#oAcxUbb984`hocZr?8tiu}L+&}m~ z-T&M__&+uC{qTQk<}u>`)cl?f|EG5I3C;hhdHforZ1c_ijsMgBPP6rEU+l2M_qZ7Y zgRD9GllAvSnfX5ZZ{H>M`P{5avi^Q3oZQ>_KXtyXKaT&?-w%oQdsFnjFestD1f4@KW(K+Az{cyC^1>g8S{GZNGJsyh_&+uN4F4DIcZU4XH|rVW|FoUsYxqAk>%Zdv)MM>< z9R5$ue7k{<{KVg%%nPmc_&@Dmo*i$*|7knN&+vchJey~a|5In%@g@A9I?MJS|EC^huUGt^y4<`h z{?GTU1n2+MrM7?gKi~FxJ3r%h$vR$8X7d^2PQB-w`F&5n@O$5^&pYvoKl(1V^?Cm> z=zZViQ{sbN^FQ!C*^am3|8)7|#`kspPn~P);bheQliyC`|FnOFAf4aX5bK5!pr}sY^|EC_D-O2esy`T0^Y3}@=j!)+$Hgf(? zouAa$`9B>`9+cG5`M+?tXi+6aof2pBJZ%1-jzWWbIy^l=9xve>?Ao z|G@vL(^C_j{|oo7y;D-Yc;##7{h0rS|5NA24Rrobjc>vKsqroNKXsw`4*XxZ@qcRO z^L@KuR!X%2UpX(9+_QVoX5DPx-OTUd|8)9Z=11^<>LGnA=KqBo|EJFF+t>NOa5Mi; zjgQ3tsnZ7bbN)|_f5HE$nZJntQ};BFga1?aGhc-NQ{!pyf9i}uac=&fdT3I=fc1aX zDFb`B^?%j9``Ua-^MC5T{d+n8r^b8s*uTMVPw&^q`9D3L%zwoHspALqasE%8*U#2V z-@4gvFR;fC|EJ66@x=dy8~>*+?$_VV|5In!d>Q;HzE`G0EW%`yK^jYnhsUv;Uie~kZAGyf6)7jFEY8t;hzQ{%hv ze`-7&{!fkP!~d!Aclf_>&MsP|J3+k{GT3A=I7!6w4KKPspbE4dK&+yE|0hG^UVK+ z8~>-~@x}kC+5fPAiCu4({SR+v|HF;f4EOiV|BLm2#WCJ4BQbhDU930c{V{xfvCaJ- z-kuj9?Ge-M{t0i#H;4QC{9LRrjP2O#kG(&0lTxFuFDEg2eP#ZA2=5Q`FvA^tf5&$0 z{gFQ?`tjoZFnoEj|9;_n!rSY|c)$PQ0nNijo&I~emie~u>FZn_J?}4eec;%xb4~Q= z>6UdaT&nl^H_pp3Kkw5m=Y8YPE`5E@Hqp`)aDs7|4%Ldr`yB+;QzwS`oI5b5IDcb zcGmw@bAPb@uexr7T5kPcb>pk+IsX@K=Krag?}-0Xv;H#vPtANo{Gaxh#{a3gzwv)+ z9uNGVx_12v{}*ojpPKbX!_SXvuZW(1cg+=-2hTNKc&X8>XPoD&Yku#WK?{5{53tLa z`M#MK7{0u#sz-PA%WZSW`^EaX|IwU1eEOJ<^?~0v|1b9PV^1I3_{Q+{$9C-L@q6LZ zH>h4MsvFk0!udZvzVd%+*7tqsjUE2+=lSu6+{(t=;r~AQJaC>6@5lTPq2v-NrLe`?li$Ny>n zc|T?TpPKoj_&+tzAN=3nCOqx@F6(vU|N8fS()qt`ojN%Gr!L6IcK&bVpr@Sw+qQ0_ z^MC3UYqkX6%r@`$-S#CbHaP#M%cq(Dr(SI9<+A>-dZDdPi~kEZ{!cw;WrhC>H~vpO z!`2sO{a^LeI~=q z)ajFF29KZb>~DX(`9tRa>HbKzd4kOUQ>Trb?EIg4q|Fy({+~LppxpUCb+e*k=l|4w z=gbW{KhefNUNaV~w7+*+`(Ctav-5vC{SxaTHO%{c_xLQbd5SM|HShOb&$R7h^IG~| zuyJSb@uKT|k6y7VSbn&L@1Swh;PMBrt!#V4?)lO?5lqlaIcHP)+2_yGhu`*{pKZS{ zAN5vLuWa#K-@|Rast@0N(|1-`LQs1C4d1L!fdA9wb3A4K+E*jGJ5eCFw=Beq72^Gx`n zpB;KCs&5(dq;KZ`;s11bndXV`e`=18;{U>p|5LO63jR;cdLPXH)9t|rPKtjls_TCH zsBeysJ^YJDqPl&~BmVy3_w9%3UGmL(z)#JO`1><$Vq6g4_hMAz|87`!gY%ooQ!3{F zsZ*!LJO8KV{`>r^2mI-W+wt^P7k}z|g#BJVXZ=rnbN{YM`>}8C-#e?`AJzE3ck3N= zo{;sNb`JVcRImK{2fmpHf&c4v;h^(@%!|PPsR!FU5d5Dy(T;cH|I}&I`#S%p&anN# z|EW1%jsFWb{x974KQ+JK$N#B^+B_BfpBhhx|5LNR4*pMFVEe=TKQ-%n;{Vifw!Y_& zZaw9jd0rEzpY+Z8$!|V-BC;~>kn@3DU*?A6zK5HKdocN!ZypcU($M9*=fC+sH9iyj zr^jRX>;caI>GjC^r1(F*UQ%s-WuGa#BX2&p*LgpV&pv;8XJk*}Ug!DpZC=BmSv!2Q ze$$2i*ZVHD^=;5e`@A8;{UXNc{We- z+tzFS_Cou9`_%_l`OaOQ8r+??!gs-{^kDP*OMT;%pcaix({NE3U?sI;U^W*>2<+k1=^Z(S$+xhn^6MYx18yb|%81K8l z*1x>#t1-SaZ2homdq(-j|BY=~?mKTulC8f};(LV66R9(#$aj`~-#GQveBZ2RcX39p zZ@grqud{r+^>_DV_%2#AELi`^aQ}Q6Ww)n%&CsasT`S!;J^=rx=U1W4r^ElL`92%} zr{?i^ZBLxPKCU1Cr~514=I!AB)O`Q`;x|40HJ@zt#5_@`>1fI^M9E$6P*83bNweTT^TufX@~QE zH2zQB+dMD+Pn}@%9c{i^~lDsoM2ON{M;FPe#7)d&Gu}U|ZyOQQfNTTfUjs_Tcu{ zedGU%KY7V_o_Vgnk)?O|&bIrn{LKr#@sxi}zB#IQpF8P$sIBMQp~g|) z!|na%kvRu_<41br?DO|09?)h@`A)a%n_6d^?;$pyG?>59H;-T3O)Gu#_|2cN!1qvF zzxbBc(|wPyd7W>)H`aH)`I2kS7e{sG)GXhuzr3l#;HZA!gE-&JYy9-Kp1zs?iT~5{ zr@)>s_&+ti1^=hcviCFmpE`eYrt^R5@tZ3ApL&$NAK?GgMe9a5|EK3~u|0qAe`;5f%(2qoZYSMfAGqr8w=MtZ+PUi^}hPP4<0`he0Z$6KRxUFzMtGKs%^bv-}{g33;u9@f8RUy zUmyIwd$RAH`*#PwdvTcW%{#U-AJO+l^MA+xP@bgwXZ4nK!QlfFeJ|g*A~=vd%lG27 zOSnHPd)>kyYuK73-TyO}Ob=|9W0D@9S&OGS|EHe0Xo~ZH>In-+;)9d){K^G|5Nk%%zSfHg>g~o@$4m`{wfl z{!iOkpB(?E=KTx*r^dhG|I{V+c>({Y=JSrd|0n6+3;dA%``{bzX8(Tp&b5C(@P9gg zj{SSU{6F>RwK>lJsY_RkaQ;u7ZS%(Pe`-D-;s4Zpp2YvDnFqZ0c(r8hAD^$&KCB+q z_`mS!@qg-qWhwT4Ue`DN`gbSm`OaN6nD-CgBkl9f(8NYjjsMg0VUqp+f%SjYlkNQo z|EDgq`|s_`TSfK$(l)-CpPY7EyQsGJXWx@-elGq`?}s%0PtE1OyroA}Z+*R&?;?9Y z9MG+=Z+@?V|I_D<~s|EDfon&JGP8efn9Q~!Ug-3OGE<=yx38@s3o0#*=^rAaT# z0^57e8huO%xEt7?T)HVo7W)8hei^MzO@i7*mYK5`+2}-~aboe%IbJ zc~3mgdEe)poX79EXYQ#x%-r*t|Aqg;|EZbJhyPQLvG@1*KXvKCL^uCW&AdSTpBjIK z|5G!69RH`r+oeBO?7PZ*;-_88d`~t1hX2#)C)oOw_&+t*|MYIv5q;m18sGSQ{GZ;h zm6-3x|EZbxhyPPo+4C3wr^dVC|J3+G{GXb?C;Xqf*8aVYjhW*wztaAFdvEzX-xc=n z+YK)-@XhlhyT@YR%-6>M>GrXI{9m~7e`?lC#{a2VPZ|HG#%tpL)Ri`m8vm!pALIYj zIW~`w`G0DBZU^&!>Jodu_rZ+Kz9-sz!;A0S?4Qqd<^k<*!#C@H;{SB~h2JOQ|MYpH z#QdMFg_)$!3#F5X1by$=lcdjYsZ-;FZ{FPNJIm&&;s3N9e}?~4*PBHeyn+8yGoKItr)K>N{GXcZ zf9R##{r>2AXWZeN^(-=MJz!lQj@Mi|@B6;_eJ1`-`;-3*H~uf&_&+uK!~dzdJp7-U z{o()A9KXQ-sd;?yf8n0A^?rZ-;2V|I~TohX%39 z$C7mXA>TaUa|@e%7uk9oC(Qrp^u@Nm3I0#b^AG>0F0=Kk@qg+HTR*mM){_za&5Ead zSK9O8*FSmMw|hRm|BUa+wjT1z&d>RtFf+mVKkdKP{{6@QscX#h;s4Yezrz288~>-q zm*W4_+4g<||EI1#<^R;Ihm8MI^Ly>5<6ezu{GYaSJQx3`W_=R;pBf*F|5LO62>wsa z{ek}r_j}L1;_`3a_FZD0691>um)YZo|I_13G|J3#7^CrFfev*zq)YT0OzPR`=zDw$c2Rriq>buiCrA`G4w^k^O_^Nv9?2_+zyH!>fhAPfZ&UIZp`>g8#c^ z^jFURRhh5B|EXDTllgyY{09DS-~(Sc|A%kF|Ecjg=;s4ZJKm4CMIbnqJe`}_nK#D#Kb@b( z|EYO=@PFZcWyX5{c$At)obZp9&g>K8{GT4bVcokp|EJEf^{hK?*yzuXKg9oOJM$Ou zf4=Sci~kEZ{x974KQ%rN|EHG!Q{&U{e`|J1c< zcD&pCpSmg|!}-5(pA29)OkrM&i|>$rlvXnr)It% z{!fj+!vCr9U-x#~?Ju9(ga6a@(fmI>-ZkdEKK{X8|M-tR<^ObgeBG9x@Ac&Y z&d+xIpSsfiKJb5Pt{?tS&HBdS*R$yLeoIm#eH!x*!>5n#Dx1F;-u@qL*DqpwRF@@1 zdc2C%$kW$G`8e*c@ct^JESvC|Iy9-xA6Apj`n+PJ4VhA#E*o} z&pfGc<58mftKd7w>xO>e{=H@W$vck{7;oK9G4<_&;@ri!Ti7|8ms#RW^@m z!1$KN*M0r!t$sVV=f%Rv#{Z>F`5)&8-TXWAe`@CA;s4ak>pQQ{5x+nBjUzYv=JJ^T zr|T#G7jEYNX@7V@=Krag$H@FYHR}^I|4+^S+P!(uH<#b4tfjgBA3uGQ-;U?|ePT;< ze*B;I$NBMpYIpn1|Eb;WH~*)`Lo)wQjVHtZsk#2&UBA!Ye!S(9FZZ^z`O?x!`&v$K z^Ay9+hapk(BAF)`-u@rY=d&VxT&r^<=T`=2M0&f^qx@ZTNBh6%j`n%~+y0OFfKlrM zpB^<|FuE^{Iz7$&zhVFWy6M>^ZBpd_)bfAovo1K_`9JlA7k702ujamQnzqlrFh%qK zwEet}&FlZF<^R<3f9g)1IywIrZsz}~`*yz6&HoEG{x974KlMQKZp{DF^~1mA-L>8~ z{tf@9?aas9wr`#95k0y&|EKND^TYqCSY3KZ(n!j)SpKdRI-}pZ@+wp(u3(h&s`M;gFKj-`(&$l0b5Pw`Ls@Qg|@wp?`(L+ z`O0Os|7Ec~eJ{7u$Bgaao9p+=>KNaP?fSF+ul7gd|FpjuE7m#xr=Gd8+5hSE%WS?M z{x96GnEz9A{qcWl)?3E^sjpZv-}ygvVE-QD|J1`SJ~vpM@OIP7ckFWhZo%m6pzmpK z`L3xM?fl=pcVFjx;FvKb0sc>2J~r9rx14BtbL4f-^A%Ud2YWty&3ECr!9lABf9tzq z+Q?wkcYfpd&-@DfpDsVc*6+mssaeltP2MX_wg!yze%UsU4F9Lb+u{Gzm3BN8|A%P` zf?JZAH-`TUH~vqJKg0j&{H*Va|5I0*-@yN=N1Knr|EW2ChW}HKo;lp+Up?+y{!h1u z#{a3AUx@!xGmme^*5kf8-iZIx{mb!4{GaZB*89c(h5LJ-KkR#i{oc9bLl608{@nUi z5Bg?(SNz|jDc3tMi1)+)saanJ|EDgr_wp~Vcm9v#yZApf$9M66 zYQCSG{>YDfv)&Z`?~Td3od?9z;Q!Qk8~mTTWX3S(|J0-H^!PtDk1zgD&HA_aKi_lg z@iqUaX8srcPaS8c$N#Al?E4S=pSsq5pN#)gkG1tk@PBH2AO25`ufzYTnb(5U0; zY}@OgZ{|}z`llOxbAQeK?g8KOe>y*Yk+qn0|H}WV@qZkf)8oZ@NN3sFr2Oxa*KbZP zFkgiKQ}g)Z|4yF0?j+|2(A zH~vq}_bK>4HS0m)|H6&`)AhrP;{UWg$F4vA&$q3AhyPO-E*RzfpPKKV@PF!3o4A;s12`cs2Z=8b25}Zn|&$8~*RjHanZ=DO%(I)cFmW&i{oQ|EJEj{p0`C zX*M4O|EK2rQT(5p_0#ZwYQF!*|Ec-@8vm!3{|h(%PtEs}bIkv#@s9XEy?(NO9{x{V zVIB$pr!F(E^zy68E$6rSZarrt`exqS>aRxmF0gri_&;49_aFXG&Ah^guN>;{U;GpP zPmfQMecy=x)AKXizVFBXsq@S`;QuvQA()G;#$2a}JU(e(E&Tb%dnWxf&rr!KSWi~m#C z*t{eBpM9t5{2$Lh{GYnSychm2Y53;m`F-|%GyZS-W1F1+D=?pc|5J}x>wJgrk&U_d z58rr>FQ5PIv0Vk5n*MRe{$zU3uwVHuG5>-8)Bb4upSo;Sw)21C#{a4Di}*iviLGyp z|5H2PX#P)KYCaABr)E3;PtE!9f9jl7Mb7`J(``Ny{!h)kO#Gi3--`cJ<6FnRveP%~ z+kO_i)pv=_zuS4!M&G54B|-0R*7`15TN-S5dRat2aNXRNw*7rjJvE}ccCTw`TOSzz z=O0gN{GYnO8vhq={GV_8`@{dKdA{_V*)yVR`*x0K{GXmrxwalA{!g86kEi(@e|rAD z?fLeI_Rrrp{!gc`UY_RspPs+t?D>QLQ{xvu{o=d+^jYRpZ2qF}JoC! zd4G0${pFY0`SE|cJ_UCD?D_n#9?w*pS7nc{@1$Aj!OA&p9{zgJI{Q4cJ9+Hpadvzp z2x?w$bn^jM?cHee0^7u^x8AzjJm8M_yFOa$Jm9`t_5}C6`pfv=G^};=0{0%-9dzGy zeu8?}ZTo|c@dFcvbzkeeAoBs=%PRA|-_{2{bK#hYMoa6<6xi<^CqpIe9T^gU^A zb#QXqfkZu@GD=1{|EJC>iE;i$+V4B? zf9g8>eFFYZU1;w|?B5sP1?CSQxb7q0`L;jS|JCJX%^7B|hbR5^gxRsd-zI(?(fB`| zp7;B26r7%<%j5F^{!h*Cd+>kZ#{cR3MRVfZ{6BSpT^{~VJ>Z&w&i|?V&g|#>pSsw7 ze}MlB_sMOS`mVOy`-3+w_g!bNclLVfoA+1vKfPY@{tEx6=Jg8yr{?tx|EI3Dd41o> z?-S9Lhx_`*hn@3Lf8Y2poA>Iw!rl+#|MYsx`oiz8iS>;K!~g01NR7RJ&+RqJZ|C{8zo%yxe!adBVNzD}7hndbOF;s(g<%zxeq>V|^DaP7dy9 zQ|G(Teos&}ahz{1|B0m&{q3tY-?!++$-d?P^!|_E5B+A@jF#>8{(0j|vwX9DH2zQb z7w<3df8oaesd;|j|J23y`6Ts@CI0#qEsPI7`Er?W)(5|>Xoc@8`+F@vy2|$$d;fgq z=WBf9{Z7O*`YyN6)Atsw^WDq-zP2q}@4KIUUYUG!gKs|XCA_dPve#|$&p&*qJ(qps zL-BulewWTmbL;==^G5FUQO^IV$Jp@}{GUEQ(D*<9dCiU=;s3&o|5LO60sc?T?=|s% zYL5Tl|I}4>JPZG)WAN|-HcSdaA-|jBorS^E? z|8#nehv5IzRd#*xe`;>upZ@$4e}4MmEARDQ_z?ateEpdJr{?*@{6F8e zo-qDTUA`d0`9Jk|TThwwf7O-dy;%RZrDL7{)91@doA-wQQ_KJ9^fdlYjW@;rg&Y5; z9&N|t@PBGNApTE{pTqx!`+Mg9)U|ee5C5mGtm*6gpL+7Re$M}?XW8*S{GXcRkN7`z zo_R?8pE`ZYAm{(odG>w*|EHc{pI4dxr>?iZFZ`dHzaRXcn!g|XpSsA_L&5*4xjy(m zHK*^{|AfE4E9`jiBNN_eY4d%h```4<{6YMm9v?0r|EDgn+t+5;JHDC!i2u{}(c=d? z|EDfA?{{IxcawDdAivg5pYuoGnN|IQkt^Txol`R~c~YrygA!XMXH&{`~QEvCjYL`oxYIXvd>I^w+nzw7c_vy1#PsJ3IfUzpvcfuFn6d z^YgC?64L+a|NfHldjw0D{wqnZm!q<~1%F%qWs;6ZXJ$0}KOKM0%Ixaq|LOQ)diqsv z{+~K6t(#l_SDlbB(D^?de@sk_TJJY%UR3lvEIbkZPadHrKGFF zr>;%4d8p?9)D`CY@PFaP|EckJ_&;@hX0!iOSLEe7|EC^XToiP?Xh(9>#?PGhn_O7r z{GYl$JIBrcQ*+%}8_pFWg}t zQ_K z_KeYuzYd?D_1D84?HQwcLRzHPtB=}Wv7$wvlaKEWDlhZ~vQSecJHp@p|FL_k|mu zg8#exqJKI6N8|t0oWABCM_al>o1pdd$j1Ney5pqtfxT_M75*>W_&+ti1^*ZB!%y7O z(l!r|`G2hvzijq^*7!el*NZN2{!izp@qgjQ|Am|Rf8oaeh4+X5Q{(mUe`@Z3{GYm8 z`!>%1g&Y5;=Jfc#aO3~f+&}m~bx&L082_i{`N90Za5Mi;jsH7)|9*da=vU8gY570h zUim-udFP$y{Gaw0{rv24L8J%l9yL#}&AE~D@6J2R1_*{;-_AQDa{D>0BDY6-zv%wo zdcObH(?|Qh=sx2N1{^-RM*lk}%Kx=K>rChW7X9)o=l{+)=XAIJullUkXS(@+>Y(-6 z&i|>I2gm%sw>Nz4{9o%1?Sj)|TAKNqtpBUiUv^P@H~&xFsbll{zrIiTKXvEMo!$ID zHS_6M|5x4Xs!jp^Pu;uQ6>k2Yx{qzg|LOX1di^vJ85{huzM#{Y#I|EC_&r`i9h@r2C(Q?s5h{!fkf!~dz7?}z_W z5A5E<`M+@E|62M==l|4rNY?*Vck6Vq^M7jjKQ*r(D>^Sco*nm1Q_;k>Dfr{JPG8^~ z51jPZdA={Qr(f>z#N#i1_^g}PdC?hXIse!Dug^FSIJ36i`9F2TN5F{x974zi{LK)Qipc;s3&o|J(M=)6W0RKIQ+^b58lcmeV&n z|EFHku+I5Eb%V_>T-9!X-#?B23-1sA7jFEY&OdWSv;WifSu30UpL+hPEzbYF|M*kR z|IzqA_0pAFoc{|q{!cw`<>p}JZQXs(U9rjeKW%4zAM^jzcu3a&)#dYe;Q!Q1mTz$L z|I~9=Z*l%lJ#qdDxBjng->9)wZv9_%aM>k6+sEE+y8VkC&eNq`-99+B`7PfoCKWjU zxAK~u&I2}%FAwtWc(W<*-#eY}TV9nPJTU7G-xXuyf}!QFH|g|cV}=FqT>6^tr167; z9dEztJKK)e;Qw@b=2yfV`<1`^99zHSmG!^$&F`D>f4aUj{!d*xb5!uo880=xI(>)p zexpzMKXtYFCH!Bw@qcQLH|~ykHlo*j@U(B%H<@+cQxRRY@=4zXv*Mip)AcEwZS$GT z|EX(jy&C5K>GoFJ@h<$Iy41WM{x974KXv@%0l~#3O}-PR3=CSmdd%Pd1ruYP|LeA3 zm-CtUK>VM2)TI8-|EUwF4s!la&HTSlQXcT9$N!Bx<7d9Pzh8X%e&5A*JT_t5eZG18 zeo%C;?|l1x_v=sI)AZ44*Evtfdb;?(rajj=4_ImY!~dx{KmIS=V^-bmn|W9Gzilzs zI}gY_E&QJv-^TjC>OA}Y0sp6#{|ooWr`_TA&-a7xJbt@xPXF?T@A$^sHD%uBJKxry zy6dc?zH99JtAkJ9;(N6H9(n7QBfj~5b$Ra1zWII?|EKFS#2yd)pE|+j`{Do8Tt5C! zoon+C@PBHK_cQ-b&G!NLKi!{PKJ)+7Su^eT>NeXCB3y1>5A#s9rOcB}J$dG`Gk{!h){5B~4M_pf#S zFVnm+{x7xiTIc_mkAVMEv;G$TZ^j?CIRA(LW&WR9{%`l3EzbWH*xwia&(=J1{x9EN z&+vaX1I772*6YUqsZ(YQb^cG?*XE1j|2lrY$@#w_<`eLL>iF41gVM{tIc96jI`5ag zEZO-#b*|l?<|~fb3_9oi@J{$Y-{!;ce`eH9`M+G}|I}$VpN;u{>U5jWhW}Hu{vrPF zr#&}1|5s$b4*#dd8{+?T`cj)OhyM#V^Z&w)|5G!M4*#cSULF2V&E+%yPtE1y|J0lw z{}*ojpBf*?{J(JH|I|fx|KR`B_(A-idW<#xFWmS)HS-qjzkQFk^>%xk|I_v|^MUw3 zb;;^N^D%RMbN%pt+D_yD)Lg&OAC&vX+itl(&o@5qk=3cbbL{W=AK4>(XPNhlX*bY! zhCN^Ke|ml}zYzZyZu4`#6WqMR))9^W)9LZY_`h)5db_?0?e*k>jxRi-=PUF7)^2{# zH}fU&f7)JP&qtfj=g*&IuQxVN(RYqL-Zmf6cctwQ|EJ5RAD!L)5#4_kYs;MfQ)iiX z|KNk&59|3md{&zEMZVLP7TNKEAn4km(Rsjmo0mENmvn5c^MG59TxatFcf?P#f5Vs; zc*CI`!NAI2`@Zq!UCawixbn_5&Iew9ba(K#dj=-VeSCEj>k04s?tbV0?(DeQdBB@& zKHyKw7AJ(;{F(0~M{f+q^*EehhRylFn{Pc36db(U_fhkC@$DXs=vhzyBEe?fIWKtg zk^Sc7{^0w_EjO5t`_wo4yKUuZi8}ouJH4%6?0etg-NF7pwD*1ejXTXFcJht?yEdms zMBBVW-`maqt-gD>?+rUQnpaHry>a`7V19=j-)lClWh`bPuspcr z>xsVCY*-Rp@W3qJOIBQir}RB<JQ|3=L&-`$d^$7{;G zdY*rYdOppYQ_br`qMkoR1#$Rc-#yBE^ZMfZ>Z<+-+xsp2pSs9A75>lP zK5KjZ_s#o7{GYa$+WQy$pPKhq_`h)D|J3O=&+W>7pZQL*-^bwpw4M34_&@b9d;i?~ zn;=P@GPl|PsnhNE0r)?4hTUHLU%2sqx_x*T=KrbjH~2sGsJU^@|Ec5Wjd1=?U1XPs z{|h(%&$r!Q_&;@_t$&FBQ}cfB!WCV7^Y8Uz&vo<7`^klu$3(QfKKthV^ajU2lFG|EJf_YCAptPhDlN|M)+>pTGm+|J3-u1HX#%E&r$O_$>UN8h^w5KfQn9 z`BQsUs^89fu=qcno_Tuszi{LK)VcQi6#Sn$&-@(zPd&l@eZl{!nP-RpQ}ccj|EI<` z;{VjecK_r5)cigO|EI?9;s4ak@5BG8C))3a@PE3!H2zP`<@e}5%{T9N@qgN0X6swy z|J3CTxxuQcYyAG1uQ}j{b0hk9-^};Te820;7x^A-_Xqw@*N^wl_&;@#-QV~>HS-Vg zf8oaesY`4=AO25WVCyH~|I``gweWxHZ2SDWZO{h){NnePldCuSF1F{BJ@&+7;NPmPbm|Eck@_&+uC^YMRb&X4~K zH~vq}`nmW&b+Mfv|EC^1JIVP!b&dT#5C5m;_yPVe-1t8=uXoJ<)8{YwKW#6y#~c5r zF0sdVX7=5_tL*ZVR{h8~>&;$t?~i?#+3%b1e>#69muLP@U1yE|Q`g$(Dg2+Bd4l-A za2JjEnSVSuzW0aO5BTQ#FTM3a-+0IiUVX^-So5H_wtmESx%oZj|LO6j@qg;Vi6eq> z-#hNRXp*fD@#dqx@q1g^{XC-af4aWaHs2Tj7jFEY8c&G-3pf5x&GA0`pE{?0aBySe zbN=#5>#q(5{PcO>HPdbW{a;`3U1nX?!{GYnoKL6tX z)K&I=1OKPy^D+KU&F5qMpPIiv{GYmXiv2$IK4FPxm+T0r7uo)_2DLg&Y5; z#uMWI)cn30|EFf&-+OnxlceJXCAL0q!|!b#ppGZl{fqxobN}N1)G1>JI{&9ms~zn8 zpE~c9|5Im=?(h7cI=%dA=l|4Mwtg@EPn}+6p6Vwy5Af9WNvY`P{GYCWR^gS-|LOkA zENJ$B`g_gKk8%D_otxY2|J3PuU7i2a>t$MQ7w7+U{5dV>D!2Zxj{nol|I_i^#GGEv z|Am|Nf7MB;eIvdvO-}0<(X1bpel_&+s15dWvfzu^CTo2SA5sml^aIRB@{ zBjW$m%(t6%;2PiQLu`HQ+voVs92OVcdCy$mtWW#W@p-=Se;>av-*@bg0nYzv|E!OT z|5LL*E&flSx)MM=W;Q!Q|9{;CifB3&}cXT1 z=l|3^p7=jCJ{13_W*!{=PhFdqr%t)T6UAo&Qr;XJ$J8ryi4@?);xx{!fkn>y~o8 z-yief-hDE%@qfC$tWV7Pzv^o9VE8{ZehvQ@Zv3BKFPI;S|5M{J@qg+u*3AD?*Q75n#=zp)G8{ZZ_|F?Ct@57&k&mX-#x-T=27e0N54jm$zd12x0c$DbI|GoB)&zk4| zb?E5)pZfCl9i0DD<5%#1;eP0Mw?_1gF)hu!JN(~E>ppirQ2sC6_`h&p6W`L@-uQct z`0ZUUyvX@KoxWS!_RjzLw(E!g3pf5x&HnIzKksnT`9khL{GXcJhyPQ@T-?t2KXuPb z+dKcK?%uJjoByX~z9Rllji1E-sry~r-uXXuFI)c;|EIpR-9^s-g&Y5;W<6p2pKcHH z|L}im`9F2L*5?Hi{=Uzj|1|Sw%>UE=PB-6|`ubkqtWQ0-II_DvxyNsh_JU`f6*=!O z+Q*%B+JB$__rG1g_y5)VecSn?ug_Ug{x8}CMti|lw!U)s?<=tNT5o-N>+uN{Upe0w z*!s$k#fRF~SH}Nod+XM%o&Qtw_{JRA;~6r^}ajzigEtWpT38^|F2x{_aD=wNd<)iwB8 zN=q|8@0t4>{dW03?N9zsE&r#M{|h(%FWmS)b)2n#%ltpJ{GWQ@)qS1+Q{w^gf9gIl zJ)Hkj;}@C#r|#eVO1J*6`syBCoc~kfA@P4|t^cdO^0M}B{+}AJjQ?wW#@EjO@%o7W zQ{#d0f9lJP&$9mS&j&p1ykE!D&T#%uJ->du^MC49^Hw_lr{1u1z4L$SnM)d-{|on) zUBi!m=fbC)&s$>ttmD105qO7m^_Kka{^ z&9`IzU%2=EV30pO{*C#6IzRIU2YxibH}eJYf7(vt|FpkZc7FVydbW8-{GU!g-7cT` zf7(tn|4+TZZqM&*{a^LMWgFc3ziQ_5G5;^wX24B&@10~C|EK2m;s3(T{697O$Nz=9 zv0bR`{u?m7tKZK2z}Lri@jdI5|I_s;96!_fKi$4zr3G&OpSGW8{ucjN_ULx!|E9+F zasE$zc=mYb|N7Yah=1*QYx3G_COQB2v!Cy9{%>}5vGafGnz{t%|8)AwsyOHW)Uovg zoc~iN+wnF0pE}8o=ivWz`857d&3r%npSs+<-)9LgH$6URyYqgm4}t$vvpxj#|I`!a zq&WYluD9cl_&+ti5C5mGu;YvPKQ;5u@PFzYJD!dIQ{#)6|EKGhVe_Q$f9mn({cgPJ z=f20;@u%zwkNGaM^+7)E^{DUCiG$qyKixmW?ezFR^$0tjh5yt2&+*5(H$CE;bTm2{ZjtVsB37`(b{2jPV)Nf9i_G zna=;I%Wb|0{!fknTDN?W-(Qh^-*w`G1ra^u=v?2dkBk4)<@5a`{!g7_-~ZwN)Oa-f zpPG53_&;^U%%Qd(%>>^i=DF~HvA1q>9x!&s09)^-)^AT*5NE%SulAj7^9%8RI(?RX z-~MT<3csEC9(nuAd{?c?bpB7L&$IQy@PFzY`+gDsr!KbnF!;Z4X@p^;*Q|H+F-uS=1y|y_2 zS3G^F^MC46^R@WD^7}SB|A$}3|EckS%>P@Fy4m?ZygUBy=u4ZL*Z;kydH$cRiRSzt zJ_G-!#vgY4{H!LMnc}=3mxupTSC}V!{q0sw_MK|;d_VIV_&+uCDMuXn;@I{-ZE)U? z^_1~{YCNa;i(~gM+~B+)ehmK??!mj?JN9OKa?0691=W{vQ4>-1xt6&l(~Q;%O)=KPnG#?e4p}vY90^#pPI)5|EJEizc>7!I>WpN{!g81J^=rx zPBx!_|5GQKf2caq!*{~6RP#)oe2+3ejsMg0X^_ohGEd`sux-cxX}kOTH2f*+Hyp%sZ9uWVh^B0+K!T+gC?Ec38smIylf&Ww2*!r0GKi%FO zdpivf{*!L|v<5Sbt zI1jl0&~?GzI{qf2Z9UIFknf$h?Fr`XFHiXWl2y(J-gNYaVAYq4 z6NX&B()mET`>yT2@p=93Kb-L4A6GapNOz3?k?-4Xy)pRu(MNsb0sCxzB_a8n2ImF8 zb9ldbxj*JJ;U-;s4b9`-cBh zSDFXH|Ec-+(R{YwUzYh5Tff~mzrVo$>H6?~3je3Zcj5ok_%{5XTK-R+WAnlAf9edo zKKQ?INI=*f&Wt%m?+-1t8= z?@#f6>N0!1#{a2jt}Jx^Pd(M<_u~K5yg$MJsmmG*gJ0ED_}kC>(~WnH@r}0}{!O)S zd>#Hz=cn<1>KV2^^|?Qt;Cs5Q2mH{vlYMjl&Z?Ul(Vc!W-8b_dUp!-$?<#x$jQ`XA zuW2Z7{!cyKJ`dsl)XX2m|Ea6&?{Dj`7W?a8YCb={$Fhk2`;rFVmG*w%=4Vz$bm`@5 zd^4}G)lb*@uCTu^o44zG`triyp0n5cp3zX`{GXm*wYJ`}{kPvv!Lg|I_2a@2l{C;l}@| znSY4?Q{y4=f9gW}eFy$eojc9m&zk>hXa3!F0;n}sX1PY|5J~&^_KB}>iC(7&i|>$*zdvdf9mp6 z{!iB@dCCaq|I}%=zpw5*k)+S}_`>Ud_l9qdXZ2|RR!dJy2p-CM+jqLH_g&KPJKrUC zycGYZ{S{4!bN)}w@2l~D>cUCGo&Qr;PO|l4Z2q6Rc1D`>f9mv!Hm}mw|5e9T4s!la zom)B3`9F19ac}4U)ComBo&QrOm-Yz?-ut`XUrs^K;Lz_r@{d=x&GXy)n@^H-{DgUb ztpBUdwRwQd|5M}tE^PSRcV@v=&j0Cnb82BskaXWyN#UM%?B7W`-a9hCPjLE|-}oMp z*E`5N7$j?ZV&;J0tVdcU>v(WNM*oQKL$gN>`LE6VHvFG_0lp0Xr^f$%f6b)iKh}Th zyr2A^8sCTiQx_$sxcPq{zwmK{|5FzyrMmTh)rILP&i{oQ|EDfav)><^|5F#)`ku`H zQWWx9{%rnF&3c*mKQ(?2 z|EFfXTl}B8a`*`6|I`^aKNA0^W}YDaPt80p{GU2Iag_6aYOWvtPtCkZ{GXcjK$-s+ zZv3BG{!cCcryif$?ElntwmR!{vN~Ix%_Zfm`4nEy*;1*TSt4n()h^J<6*<+kG_07b9j46e58j<92MEo{xACW zMR&9ZjBf7l@a0FZzstV|;q67{i^Dy_*6R*;{D??z9zEYL+V}DAPx$=NmmfVZkk^;+ z>7#w#xAi3#Ma~P1p5GVUS44Tg&i|Kre&OqbKM8lQ%OZVXk4r8JPJDXwc(>G#-M^>! z!0EFi`{W;Qjo7}qF0wCv^%lRK{o()izx;{wg!s5iU%tgR*Z-NUmcHCP6aMdl`p=vX zx9)>~I{$~q!T+hbeEgppANb(( zgZ}(iwd)XE`@5SWy1KHZna|ey#T)&0{N%~>mS%nAXC6A>w{v|D3~uSRZQBOZzITJ) z&U()HKV2XBKiwYrzi`iAy5FCk`GEL8ouBn*@qg;G+t}?l|EFdi8U9brJTm;Bn(G&S zK1F-FXg~M=yQ42Jy1(u6qE8>)(dUo$f6?CW%rhhB9iD#n>5=!3%}1Pb|F+{V{^CpL zy#kvbi2r-H#~026o_@~R&i|>;KKpFv|J3+h{GYnR70v$dUk(3q{;%yN=Q{tVW?mrv zPtE$ltpBU-a⁡|MYmqT+z+>Ki{3N3)7|+$ zb#I&RhyM#V^Z(QX`u1}3|J1Da%ltp}@P2)Q3Cmac%O5eIZ;&=+rSHT6{oMM$I(>Y< ztDXN-vp?qlsRs{ep8uyF)u*5Hf9he~dpiH89@wL+^MB!H{+~KFrmORR>fyG&G5$}@ z{l)sf>Z`8kXSE_~AYzjmje@BE*7`K(1jMXOQA zn<}4hesA;Q^}!!vM*7~gXk9QjXN2#$i`EAJGb_$F9u5De^D`e1|EFgD9RAO@&Ev!W zg&Y5;US`|zf4Y7&{!iQG|J3uBHoEnHb^68T{qTQkJR<&2jSs~Cg&Y5;{V`t<|EIpj z=I!DCboy)T_Tc}teNMwh=l|4;mN&2edqd^p&iB#G|5LL*G5#;y_&+tL$Nz;J|EI?D z;s4Z&?E2yVeB1f)e`@9p;{Vih*Iw)9|LOYnO~`cX|Ehx_3C{od9yH3W|EsPmEOhJt zzIt+-y??(oxnbr^=l|5(=1g_|ugB)?&i^&kRXG2ruBdPJe>#0x%}D3})I;oe74!ep ziMBq=vd@3r^zTjEoIlK*Zok(y|EJEd<2Cp{HOB+bUi^!uAD!IlykC(WpTz&EIlhVi zQ?q`_#a}(&G-2je=VxlnFQq>5oNv|-nX}_r-|~Mtf4Lps#s8_od;z7U;JOVng6Hecpv^xjnBmYqf9qhQXd3|8}{t^EdZv3B`d5ZYIzudMn!vCr9Y4|^No*h5O|EcBw!j1pa z{^kGF_%-~Wn)!A3Kehayn*HPd)VcP2!T+iAZT=SiPn|PkkemOf>ytcdsPlj7bekuF z|5LLbGV}k`_`jGo2mJo-0%xj(hi?exR_&-b^ z{%@ptMf{(d%jejmn)!$Pw;G>^{|h(%PmO=W|Aia>r^_#}?f5@+p{+NE|5I1b&v5=v zU9&JN=(BB&-=1&ZH!}ZE+iB+ishLl~{6BTEegBI8Qy1ELy7<2>C$Dv$5Z{OYQ}g{T z{!h*A$N#BWzX|`R&N07*|5L}>>jVBz&HB~&KQ*s^_`h)P`*FSRK6ZQ_|EKLk=A{Ps zKXuW9bm#x{dRJiE@qgN0vT&61f9k3gY4-d662Bea^<`6`Z@v#LDbM$fzrp`$|1|zj zU9%$3`9F2FeSeGpQ?vdj{!h*NoA^I9-DDY(x%PM|M7gn|Ebf>m*f9BoZRI6 zUy993VE&()d7AjY_)VLf|Kst;|Ec5b`zZY1qz;>$|KsoLe`dC6O6aiBc|YcTGXGDV zY~L3?nR{-Nt(oS$U%Z_j|EFd?C;m^(ye0gf%~)~%uV{IGa5(AT$L?)f@4R2JeP4|K zQ#-%e@3UiX6s&jNuhhO@#{a2#e%#RKug6Y%W1aJUJU{S%;l}@|nJd-Ur3pl;5S5&ikAkNU1^EDd%gKjOREyj`#F{mggSy3*iy z+k1VpzHZg>yL~h7?c?8nKccVAyWMx;nv&qEdvEbw+*sz;|JD6dwx-n0|5KOSyg26n zsp}hUeqY5-e}24S=ca3YH<4G{!g869>@HgZ|47f7TY?a&FA>W z|Jd{G5uLxpUN6iK`L17GghzTr&sW;szxd|)g8$QY8vm!}@y7p!8~>-Sw)uegKQ+Dr z|EKGdZ|h;=|I}&b3GjbND%;9;BJ_qTg~3i4pTUqbe_qEq;3C{g@obUBp*V(+nltk^Hd4EG* z$nm{${R-wI`qQsi*ASdIx5oFP6$_pJ)AdhT;~TkQOw9`C~Hbm#x{{D@2M@BE*7Xh}C- zUlP^n<^k}3dcGx1YM%e6&YIQi|J1AxkN*od{!h*K<2E1FH^1*NKkb|O+vcl%Gr!yX zwQqi}fdA9}vTS`z{GXclzvjFB_2>68_WJLe_kZ^9gKy>&EB-^4+VGeDnTq-^!GT&Uz`$H|rCh?2_r5^@;I+dcT9`ta&`w zZ!cYyZ(h8>_so^%`==K9p1Lg0`9Gb%a#exzf8oae>Gm^^8vm!p1LFVGZ2xmft#7v5 z`trV+_m}_K_=x^GbCPdv|J^rCiRkfvndZB~&VNz-OyA6Je0=+C-@N}`{PrB*N{9m~7e`+3o{GXb~AOEMGvNXr}KQ;c+ z{@ZWo{ATxjbAJ4vPCw569`S$bdb>XOKQ*Vv|Ebv@{!fi3%s+8`l0NU1m^XT-%^u&? zlVgL$>3bu(^|F1wIev2U5BK}l{6FoF*H8SPn%7VKpPJ(n_&+trC-8r2e*bpGpAY+H zo*n*ApKmxmf&U9P{!h*6@qcRehyM#V{x974KQ-$!;Qzvn|5MBVshQV@|5Nkt3;s`? zX1)^tr{?#m_&;^Ylz8X=e48JeHuxw0_7_dF^&Y3(;~PJS|I__Ne15@ zo&Qtw`&9g&n%@WCb@qcv`h3Xo!}R!vA{zgv(^uQ?g=Zgq#BXPw;%ToQ^PM-{=Kq{~ z+&BKOU*e;_dH&%4v_F1-i~mzsOtAH+&Hw5CD64N?|5u%F>%Zdv)CKj!o&VGM6U?tA zfA<-Gc}aHv{`&Q2eY4*6%nP3PU1{?z|DE!JZ+`EK|I_};?06skuce#)pDrKohyPRK z2l0R5#{a1~zJdQ!^ZQ}u|EW3uzaRgtzdX(V)8(g{*PFWRb$@-+?D#PLPmdqRC-Hyb z#{a3gefYm{K@+aTfRYQXpWB%;B#QLf+fAO7D(l=Oo?O%N-6!&ocPuDlGq^I+L z>fFL!&j0ED!ULYT;1hrUX50L~yVF07X#Ag!ui*Ref8pNtqmxNGzMYldJJ|gGmq|K4 zotf7wc;KV2lXU!eRKe9jUf*wg;{ox1Iv$*s-7nZPvX$?Y%&Q~54=sz2^cvBfJ8FdU zfARzP6#So>^(66s@(LA6Hec4}|EcjN_&;?~a-#Epci!_+v;VXCZp{Bvb9(0g`8E&8 z{6BTMtxt;oQ!~E||EI3X$Z-BoJtiaB`9F1qc`5v#x-2u@`9F0Pr5 zNlA77PhFfg%K5)=GyhLL*1RA7FWmS)HS1yG|H6&`Q|FDe`Kjjr)CIQQCjL*&{4M;S zn)zAyKXujc=J|i>F|os)|5K+A8{+(5xbc5#<^|&a)TOq5G4ub_qilcpzi{LK)ObMr zpIZJ;&3dW$KXqk-`DOEeYMyWSzi{LK)c7ps|Ecj=%>Pp}kB#+z)iue@{!d+&WXBK8 z|EWt8?f9Y1|5I~*{9m~7e`>rG^Z(TNL;Rm_^HcagHP;XSr{?tdKQ;Tq|Eb;IgZaO3 zb%$EJ;R{!d+$9`F30x;P`j&HoEG{x974 zKQ;3O@qcPO;dkMJc>V!jXmr|X|Ge5mt(YCIS7|MYsn{73wsn&$)lPhAlo z=lq|#d}QS7S+oy}UN4vZhy6@+Gk-L^J=*g{&-<&6n#UJ?{^;iU7vBHqlt>TA;}@|# zYCdaTV&v`R^(cJ$XwUb*?f?emiC@d=+kx}*JLvOq%Z;{4y}yZ_<*U;j%wIRB@<AvkRar6Iler`YhPmRaJ|EanE z@PDaKeCqrk{t*ACmj6>TUk(4K^W)#}f8oaesquOEzi{LK)E#X-WBgyZ@qg;G?fHZM zQ=fU^`Og38`r!ST|EKNpe`+ot|EJT__&+t*AOEN3`PcE!d;I?JmhaWKG`AoBr_%>* zBIjEMXGYHVJEzru?`Urq-O>K;+d6vv;ONswZ*LWK{h~Yi^#8HH(<6OfvK z$42&qJ2&|4_+RG#>G5Q~CG-E({Qcnn!j1pa<#n?4g_-}S?%A`a^MC3twjMA3Pu@q73`b#}jI|EJSu+5VXSrykU|U-0|h%l+vG z_v;`0yu&iz@mKeE{!gbL-lMnkf9ifcdOH6XZv3A*wOeoJ|J2D{dOH87mj6@p`uOm_ z=K1sE`|y8yJn^;6|J!}|r1POyTyT!_f9lK5JIl@g`}}8*JO4MNbFbjpw?-ZR?ctw0 z@3(dF8t4Di%WS<_{GS@nhyPRKsBy%{)E)pL$V4v;S-9_0Io=8~^8f#kwFT zbx1_x|NQo4Yu)@m^}?lVg1_H6&~IO{xG`vWd4TT*^NMGE+TZsQ>pd5@^fH@Ai2u|6 z=3C?c)cD4cjaU0#WR3sR_Qf{ekNJOU=Ka0Uw%7509C^(7KN|n1#zW%&)Jx3|;{Vk0 zf9k~z&FlZFmoMMs{9m~7e`-7;{!hJd%~t3C)bkqG2b9@z&@2md0;7Wh}gD!2H z|I_VhKfH(Yf9lHOTsQykhlN|6$D1{|KA2hbW|Ml=)Um;9PruQ$v1zOGflJ1f2OD>s z@SQ)t+5c&KZoM5}we^41{C*Yxr!Jd3-1$H4AHRnGQ|C;Jcm7X}FT?*Gdh}Z7|1|$k zt@(dyj_=|Bb_~7N`M*M24+j4iZv3B`^WRkYjBkG5ivQF8_-}lY;lc%M9FQV~(+CRt7 zng6F|UI6}2%{&wQpBgX5{6BT3`7r#SI)U|$&Ht%OY+e`sPtClr>8%g@PM;AQjCuZ` zZ`R+<+J2L7zF&wfywNw`FW~>QzudX@`%m+K>iqd>!Hmg!{o}#>#CGkj_s>uHzuRNC zIR7_nx~(^2{tv_F{NFW0oc~j6{-3(czHi~!qk62()8oI@ctHH0nt3nyKQ-Tn;{SB{ z%#XqUshPir|5Nk*4fFrh)#lyse`+2d{9m~7e`+od|EFesvA*vuX}a&{Tb%dHJ>~z@ z%)2>Z{!h*G2mhzew7&=ZpSo&7Kj;6{74?0b|5IPh_ZQ~>)C2AH1^=h!`HTNk*Vy-m z_&;^xk{sv%)T0(=I{&BU`@MtLjPa*u{V4pOwvU<5@%l2~p z|5I!JpI$FZR^~bXr=GO3!1+IQy?q~!|5K;f_s94@b*il=hyPQTnODO9sqvTRe;(&A zpY_r3f4V;OS5t=g$CLRb_&+_rSTF9fl73Cc<2F0*$NFY&{ohl~`evVg*|X`rr#79M z_m>eYYZKFSLFFdr{qk(S7yeJ3X{Uev_A8sder99ydcW5AKQ;3$@qg-c`+LLx^{CqD z{9nBJW&EEy)jY(~ns!YKmuzTW@7JFH_`k`2S?~N`g?X+ehtF%WHPf8;%dq6nVmgO^Ft?9)6bR|`$N%-dztQ=>67zKUKXtYFIQ*Zw(&p{p|I~Oa=KqD8`G4WY|Aia>r>?N|T=9SE zGV@{hKXtLqgTw!Y8~>+f{u};JU1**V|EK2q;s4b5Mf{(d`Iz`WHS?itewXjERfYJT zh&CVQd+h35=l^tm8vmzeJzM-=xQlkJ_09UlFMYJsclI*#&X3OVZKKMZ|I_0|V#{CI{&9mnrrI`ng3H4+q`4^pSr@l3jR;c z>nr|GooBD__&;@ptsjj4Q`g!3f&Wv>|LOTVw!!?P`9C#20{^FG{XqPm8o${4o3(y_ zd26z`e|+bfXU6~O^jYRH@PE2|x4xwLKXs!0egXfd$E(czFaA#*o6GUEAXxINwa)(~ zm0T4(cTL;)6Rp-X?Y(qw^7?(#Y#!jw_$O;uy7_<`4r~h^y8Sot7p+*~JmBVoJIx2S zNl3hq5oG`P^^5*%0*1JD@ETZpw^_K|`_FLw>;EjiN2M4DA(f18EU1#$K{~6IGvrkW4 zxPGbggZpef-;9Ch`)0l${!iPP?}z_W@7ld3_~I`;6LoppZN8tackFxpjt$QL>GZ3& ztTC^c;?KWw)2iU(^|`*6ty>=4_iC9x|Dtt^g7MR86Lov%teg`RkC@_nmaXsm&v)h| z>i!uwZ#i(ZPyC&GXd1Im;pUE?7oc~iNXAF1#Z%NWB=RJFkY!}?U za(|+p5B-xb2`)STpznmT9?t*i`NMn}d;LjN$Jys4dwueqV(T~B>zD6T^B(s4<~!Mb ze}Mnf^Og56_&+tjXTkre@p||_HK)h_shK~E{|h(%PtE*u{GYDxuyK8y|5K;Uu=Ntn z|EW`_59Z$w-+iVJ;@=nFJtp_#^}z4H$owPzPnVZf6XVwZRbMixhx32xE2i~v{!d*p zd7$%u>O6aYhW}F!n9|evKlR}0eVqT(>p{8wUIzcCF12~xV_#|G&(H67F6h$Ech-VY zyngu3vw4OKAL{5k-~1l_Px~ve*X!3SF8AAMdp-5de81$6uk>ALuV{GS^Ci2qY(+2<|%pSsf4x5ode$Jlz*_&+u4x8ncQ%%j8qsqumMzi{LK z)I7iNf8oaeshK}$|Lwch-d~%|^Idw%|LOEJ{!h*R@qgjQ|EYQZkN;Ei{(s3~^M9w_ zKl6F7`04Gw@oM-#eIBftGSvA$b+xU>fd5k`Pa5F-pE|`}PniFw=J%@jKXvZxROkQH z{JsbO7jFEYy4+r`@qg+v`@H|7PDgy>@9=;A^N+ng~@qcQ(A^uOzJVN}R zdaV6k7XPPaejff$&G8rJ|EVkN_p$gtHU0|!r)E6|{GXcRKlnd2-i!HvYK{lt|8)Dg zeEgrf%H{<=apt{A`g}KLN^DR)@;=|ACyoq0oPB>pZ@A^BzKhI{UHa>vMKu0T`{Vc< z{!cyHZqIM$JnXxER+967+Fm;&!TCRRu6e^w=}k%cyovvtzxcRsj&I`sbbI)HF8)uA zH@m0diHOer(UZRMjc>gBl_`h)D|5`fE`M+@E|I|t2Mmqne9#P%w|I|4Z1DyX;rFk5bi9Se|AqVAAOFjDN)`*?c#q;APW6q?!T(J=@OS3{@f-L*b*{}@ z!~dx>Z5|!|PmNE(|Ecj*%>VOk^Ql<>SB+=G|EXDzm-TkH%m)Rp%5GXGD_d^P-E zxbc7C#{a2V&lUgY+n#^;KQ%rK|EK2q;Qzvn|5Nk#f&Wu8&k_Hp=K0P1KQ+&9{9m~7 zf8Xu%f%AX(F8rUG^^fs?>Ka=gmid2b&HoEG^Z$IC2gLt{8~^7!EyejiH69TE7jFEY zn#;rg>G~IC*zfsm{-3(o=5gZx^m@U3PW+!b*XB9m|J1C<%lg0S(aDkiE!wX|Hy%0s z`WM~Y-{I}i9lgJA>u5h1Jzp=nqkUnO`Ofh5iQbNH4R2@u;(u%Y9>UwBJKFa}H_zYj z`J+7_uV3Nq-`2dIg-;*t|DrqE3r6=PZQDic@7o%m7QXy%^MK#B9lsUcU-Wvvc%Sfg zn)QF%?fB4nJx+h;vfF$!Kd|N>M_bxFAnX6?^mstl|5f7)ng6H87c&1(&Hi63y!H6j z4*zi8k7oX#8gGdI)9LYx_&;@z4wpFpr;cfVvGadAKldm8PtAI|_&+u4E93u8JM^*h zfA}{1pSr^Z&FlY$yW7-5emnE?+P!(uH}msam9;eU_V9nYJl4y_|Aia>r)IrZ*8kPz zopD}kxBjo1%VYkZn*CkB?FQfYzQ$H9eZfVoo&VG6Y5boWFNptB%m3;6aR1@|)Oa-f zpH9#Gy2E|;9$()5Q|Hfu(``Um@aP)-FWSpRceIC#?&#A;ceK}w?r6Uk-O;E2w*I#3 z_igh5qt73Gf1P%As#=6oQ3UokfSPc8qa`yY>o|I_2stxJsaf8oae zsRwoG==`6$@8xZs|5Nk#fd5l7{}TVF%WK=Nqw|02OD^r?{GYm8x90VK)%ZaCpSpj{ z)z1H^2lVLc{GYmiuf9S14r~1B2VFfNVEtchAJw;yoByX~yr-w#awCE4#Y&f3^QXoi7Wn`tbt4ePE|cgVPSp_uaSi zrEdP8PLKD)|EW8lf1&e#dOSOw*T(t3ikY7~|JUxER?h#ayIg!>aO*GT9#_{68R`7r z$A5g(`M+D2u6F)Uz1rr>RSq3-JohihonK@9-P5b$d^3L!|EJUA{qTQkd>sByy~O6x zG5^oEc|qp?g&Y6Z(#`%a-1tBB?B$Kl|EXu5@_%a9`^EpM7c6e}f9iP)S3CcwW*#8^ zPmTA(|Aia>rDjXVl>gKHz0|xP^Z&xl{6BR= z!)E9I)ObMrpPKs{|EFHvxWoBB_53v(o&Qs}>2#Izf4aVbjU!#Uzq7x7gGUT;>;G1F zxYl{UiN&`5;I}# z?D!V`Pn~YZTbTc+{THyFhxtD>^Y@tlr{?%4{%^~cEzbYZ%>PqY+3#_g|EI3D@5k_e z5B|?)=l}S9FaA$mIy2tQ|7+<{&i|?Le@}IJy5;nCeCv}xKN-GJ8p z=RfXS{!h1u#{a1~eun>3bNmedr)Gcnzi>a%@tD6qIY0idRoku31Jd|Eb-DR6{9m~7 ze`=1O;s4YepW8Fzm!rthD(&3Qi>|EK2n!uUTmeiQ$< z{Dy7L|MB~5{9m~7e`rR{!h(%CHOxz^I7nJYStIR|EaU= z`&;~&@c- zFnjpFq&c=egU$a_^L;S$|J3DndncOzQ)~X88h^%rtNFeV|EDf8k9XnK8+1WBasE%&uhQl};Q!QR=H2jrYUc0Z|I~Ox{GXcb_&+tPqgW%D}mf9f9g{Q>?@oqo+Q=l|5j%Tt{HQ}g{J z^Z(R2_I+1|&Hqy~?*sp*F0t=-@PBH)-^Bl^D;mX?^@`NxOv z1Mz=){7TJh;{WvgqVaz-&fMhv-_3P>ny%Zo(Rn}lKQ$f+|M#;V8&CPa=JkKonYJDO z_vafoIRBSno(cb_&Njb?|5K;h-z)yFjXlS6et%Q)aC<$%|EUvfKHpuBwr#RkKj;1O zZQf6>k1uGtx5#E*-gh9mbfw*Y=Ks{$cK?3(t8<#{J5}fX@Ot<^HQx{4+jM%9%{X)3 zkMB?Mf9h=ezTDPFJl6Z0wawno=KbLR)Va1D|EDgr$NQT{KRjjzt$E&GLx%HzYP=f$ zPhDf44*#bfYkm>`ryjGm#Q8tfHGv@7t9Kep%FBf34sHowW9KfamIWFF}eT|W1Z`6k~*_WEJ-(tI;7%jPfoPPO$j z?YzFT?DZA@r~Pq%+U@n7Z?8A_KW)#pf4`Xjr%tkepYeaXzRWkl|Ec?z^swU}L9n>X z+NQT-_S>D`GgxpQ|Gq1J?mH`*8u#r9Q&)fg21U25Tc*J`VJ>bOWzW3j_D>yspj6|J& zx2@Ovd7BG-Z{K@u@ZRq_`rf*GbMWgQUm4MlH}>+qZtEKJiGzG^+O#G(+I^(&jT=|n z^-cBNuyJ|N_+*~%g{v2^K5|Q&_vX94q4n|KPEFMPvv|ey;QJ5E^*wW59rtIV z?(cLE7IrM%ZIiF&@Ijpy&{_C!6O63v_0>yvNh@8SQnJ;Qtt{!g80zQ_Et zZ|3dc|MdK&@qcRGALIYjyg$bOsgvh6`@eA8>$l%OfB*PDUH%~R@67*G51pCd{GWQ5 z%~QhvsfW+B`AO#g)WfDHIRB^18*ZKg|EC^m^Nv{mSAC{^o@D)Bb!+>4XTCT|jh|%x zpE}moPsabLhuZm>|EG>KkHY*v{rj0_l&=l|5XOOu`dQ}h0s`G2~8cs~4}y43#t!2hZFeFgq6 z-1xt6&d|pJvwKYZ(c9YIxyTf|6ZA=_Kk1D|LOe-jsFWb^Z(THf9g_u|AGHg z7nv8w|EbgFjd1=?on`YNng6He_c8cCHJ?}Te`-Dt;Q!R6=F{+h>Jt0C6Z8MV&HTS` z-y8$ZVMY z#~c5r=KT0SHS+-Re`>BD{x974KQ+g1@PBH4PmBLkv)%*#PhDllJMe$%O8fT#|EJqq zF~in-H2>Gqqn!WK<5gzApT+;Fi*3Fj{x974KQ-&S;{U>p|5G#H4gaSuvh{QEf9i^9 z$xAT9x zfAD>*|Es?jn)!eF`-(4W_J3;T2d-QGnct2l#Q*8|42}O&=M>od!S_%4W}e_ZUA{`v z@$UG7Ue5pN_;f;H@1SwdzmwGIsXd+l)A8lZbeoTE{!h(3JbhQp|1XMKU$SWE(BMxK zCM4f@=HJ~sqVf?Vf~V(A^oIn3rin*Y0M z_1~QTWBpJ3pPG4h_&+uK!~dyEhK_LlPhC1}r1O93jG@Dw{|h(%FWmS)HT%c^sWan8 zIRB?+y<7aBn)!D4zyCwpeTUgqmi^mb=?ST%laStfn`APXUNXJUWHRYJA-(rWZ-i6` zy*Cv_1O*$IK@coRSDF+>ilCwocELy9>%1r5d)8XM$HU?A^B*~nwaeOTm+aa5v#(pt zcKn|@Ghwuw|EJEHJjVGybxz_q=l|6C$&;M_Q?oz#KQ+e>|EK2m;s3&o|5F!FnBe?h zxbc7CX8m6^-Vgt$#t$<8PhCEKg7bgsPWEweq;%&U&RM{}}C(tylQ%>@WUL*T;NK{GS>> zh5u9ItMGr}#{a4FlWl$M&8K}ArDX?2pEUN2^laz+xb^%m3;0HCb71{$IF<%{=EXZ%$Tr@ZlScJv+0( z|LOIC%g6tzOKkt}e`>rV{x96&*R#*_Z}E9}alePh3}4>o`9Ri>4xfHjO4L)=+Wi&Y z9>2bL^LP!PK7M=VW<~y1MzF&)Bm^r55E&We|&x*jsJUg_3xekqw#<0zUK4r ze`>rQ{x974zi^LTc;}-(`Qu04_x^>SJNH{7iMtM1yhVf|k< z$K&H6?}_&+u4yW;=UEnBv9{!ix*+B9?iPu;9tOXvU8_%QsRx=XwE z&i|?Lea!z0H~vrEvQvBK|J2Ppv~}zMs@u10<<|dIw{FrjIQ7ugk3RDE|MA`r{}=A? zKGq{={-3%_w+_z#sqw!*w)ubR@dNuf|JT@qo&Qr$96Z$dKlPa5Bb@(J zj~hA4`M+>ie^BQyf9!~c^?$XU#{X&mM-3h3{GXcne)vB%^ZD?9>M^~#JO8I1*`tej zqRoCgJ{JF{?aWKW|EclPtpBV1;q@2)r)J(C^Z!;~_b2B&ySHu@e6(VN?+)f^$Ca=5 zot`i$SU+{0@2jRw5B~jO(xZ1wtarZeIrDG#c4+J!bw`~4)Ap?w{GS^CcYoa!e|~z- z9g}^t-frt3CivcN^8+9H?Ihnj?DPveMjQWkkuAYn*zVWqtoO_OKlOI=e#`cZ_vc?? zees>+d@r@rGyhMgXFXv2U$~k7r{?mQ|EK2q@PBI7)5ZUV8~>+f|C#?6Zsz}~ciOx| z=KtwZ7|acm6Nj-+p(1zy95OuLyEl zH}?KRXPp1j=~tNdJZkg*)IqBb&i`ru+t|EF{GYm_s?_pzF1q>qzUBXP`)T~2n(M>=srh|1{!jM@+c&=cNTl(9>wbQ@ z^MHKbivLs3yle{dbA0o88~#t*Y5bp>+uvmJHzSSz%g;XUJRrZPXa1iWzlQ&N<(cEo z19H6af8m}|_<(QuzsqW`@E#EVr{?T$OI4gOD^X7hoV{}*ojpE}pp zgU0`<3-FHS|J1p5`|y8i)|bWqsq^gfd;Fh{FWwLTr~41jhyT;#f7+^s^?&y~eZ={{ zie)36|HJ6v|K@IJSpQee_r)u3K3?DDXNR4qVm&w3N>Ss@_^ood`Rr1Suj9YfMK)g% z|EJ66`zidN8js2RKkZ+x&6mResS7rxIRB?Ev+t+zf8oaesmnJ^bN)}wyej;ky4sF6 z{!d+L&*uqUH~MCNO{;s?`OaNC#rZ!S&rI`otpBT?ZjTrIpE_;3`6Tmy;l}@|@qNty z3pexs)WtU61OKPS$Ke0ewKi`J|EHe0yV&_ZHC_h)r>?g3!kGW3F17h)_&;^Ac_jRw zTK-S3cQpP_&G)nTzi@x;?o5Avd`*j_bl-emjQ`W+^L;h`PtEtQrBf6A@#gz+{GaY0 zdfbZ>{Nsi1zwv*1{4nnW|EI?r>o?>7l9nEJ{*Ui-2d^JmzwobzocH7TpRjmP{R^uO zIp0UOYCga>^ULsm+Rl8)*M88u{%@ZibiR-6_pZ3aH=gh-C%V`7J$2Bn@5}eWUwp7j zeRki2Zr&gLYEGy6UkpCrydTE{|EK2r^V^5Ct+$yf&inEB!2hWWZ2sG_4lV2LJ6GrZ z@QnCBHS-S5Kh)p)z&_{w@Qe6AHGUEQr)EA8{!h*G3;*}wi+i2_r)J(9 z{!d+F^Cj_rYJ6u(r&rET{p%j*p?JLftnNkMcvSqKPQUO-sq=s8b^9xv|5LBtQ|kPm zy4u#0X8vEeng6H8+u{GhjsH`#{xSY9-1t8=J{JF{F17Vy@qcRO2jc(K%n!u>saX#Y z{}*ojpKp8ogwF|5M`y@PF!bJKp#|HJ%s$r~OM_)!_fsqvwpZzt4j}kM~hCM>+rZd{UkBe+df{ zY#!j*12ew{PF+eBhP0Tphgo<%ubk?`?NJ@YD@w z%?sA}K7P~bz-(HiZN8xI6StfVic)S*xwX}H=Lb*Sc9qQ&{CZ05qHWFxvc2Z+$5Xy| zXsh#pT;8~vpZh*@-T-1zTuS3$NRhQlh$v3vw5n{fB7}XgQrfn_l^Ji_KNPl z@qc$^^z*&{sw2VKONRU2cKL4BJNAA2NL{eUhMo|iy!Q8{%`Q`rq2KA{_8aPBIo}O_1NS5-|&)w&i|<=R}OamPmh=Eg%h3s z)8i>+*|=ax>6cTro%chh-@ecHRP(%l-|~$}e+iL-TJ?Je$mYT zQy1F%8~mTT$X@^Pf9k9~70&;K8~>-~{P;h0vAw?F|I`ciR5|~ro?ln#{Ga|k&E8!U zeCbd-fBG~#9*1XiNYnn;+I+dGcXaYS*Iqx&1N+7&-9ELOZ+sH|PuDlcUSIHk>RINc z@qcQ(KlA_8r3Xr#|5MM}R~dZadI~Qdkgb_;l}@|@qzfiaO3}c+wsHyg&Y5;=KjV1g}cZ6%Om~qk>kGk z`{1ejuJFzK|GQo~;k&{f|M)-sy->N)o}cFb)Va$No&VF{8koAAVjsH`Z+ji#v zg&Y5;PPTdf_&;@;eI9}TQ}g#d{!fiZ#s8_NZ^(20Pk$fftj~4+Prbl??}z_W&$W4e z_&+t?5C0c#{9m{qJNYGleR#nckKN;&`GojCou0=3squpNzi{LK)QikxHeYdf9mSxY0m$t%NCgrH~*)uTr}DFKXrw@|HA*NlWhBw zJHMNzzZa)1o)Yx_>chTSk7VOpkN9Su-w!*Tk2LfDbbk3ib-H;_{9m~7e`+od{}*oj zpL*8vsm}kYYwhug|5I0(Z^QqonP-UqQ6aS~?^H2Prn$HLEf8oaeg&Y5;{lyF7|I~awi2n;W{!h*4 zqxe5{zWGG_pKtqpfm{Fg!slE3{=%*Qd!fr0OlnyF_d=J>o8bJP&R;%zY{UA$7q(Z< zH805ezdF77K)3$yh0d>O@PFD~QZcAu{of1Q3rhMmtp9tV`<4%I{!gbLSUtq~KOG({!fjs!vCqce&+wF zxqjyVsdFb!b^cF{m&5<5Gi|*l{GU2&%2en7)XBDfF7yA?tapq5Q%^RJhW}G1CM7uk zr=C6~!TCQmw~zUM>Y8bjo&Qr;Pi^pjYW!c`J=@c7{PZ`@*RlUkJ-EYn_Qc6S@uNE< zjsMg6vnDn8zi{LK)c8C6pBlgU#y|G@%bR1zZ+z4JzGvC>e|)U5S-%zkr~ONxJkj~T zaO3~foSylAx;}g&{!h*R;Q!Rs=0jQkH{AF?HIGl`|EX*2@q+(TR*mytupRQm2Pc8qa zW;^~*osn$6|1|%n&Pq*l{!fkXWB#A6pJx7_n)#OaKQ-&);{Vi~zWT@J125bjJRJT{ zjSs{Bspn)gtpBU?*JR{4|EI3a$_?;;>cu&^&i|2IJl@zQ1w* z7w@=ljC;TM_IS^-_0Ge$r^X&%;f}ATjF*mVH{TlWxDU)ujIMY5dHyec{NvXbU++2Y z|Kc6@esSN2uLKw{I0B_PfsCo{QSGa_j%<_Ruf4yVh^VAAa%BHNNp= z+djEE(zzQOyLIc;LNdM~)ui*8f$H8)54gR_yktpD=1%&?I%2Z}~r+e)O>6&i|>$4;|qApL%5f z2LGp?(En2B|J399_HzDDeQDnw&i|=<_i6BdYW&}?k8SY#)1z~{;IYl?ee?Q*|NCgg z|2Y45k=_0HKXun8&7A*JudJzc{!hJi-lAaA-=;qL+~G%T{iR=~pWD4J_;>Hd#=||8 zndrCE%>Vo6?(aD-xW(4z#s8@{?>gZ8pPKc8@qcR8yT$*78~+#X_6ZYx?=ydg{~NUV zyz_v2%^%|bbo$Gz@qg--c6$7uPS1M8_&@bJo4<$uQ{(&af9kEa9sj3hJzo4@xbc7C z#{a2VFB$)*-d%Up`9JNS{GXcjeDQzkZ5RBXdb@eQI`eQEXdTgM-zJvSh z`!e%?y8b-}Z9OgXf9l=)Pdfjn^Uqkl&iOxe(7J6f>Fz%M^82-E8NBu5OMNdbEecM2 z)Z6!}nN>kz=f>W?bYU>6>6`T@J05f1Z~n@eL62^)*FSj2QRf9qXXQEnr_P%{+4(

z@y ztJ0nS)BVHg@qcPQPwsce!@imS_w@4bMjHS3#`VYiyg>Y)nt6TrKehayn%j^6`)13_ z>wi{qXF84l3pf6+<=M-f|HCul|J2O?!~d!Ae9ZrwdC76-|7iSQxbc5#_6PqLZv0=k z@qg;cYbQJZr%t!|8Tdan>wV(?)WsM4pPKcA@PBIN)8YTr%uB)lsncz}F#Ml7(;EM$ z&a!!c_&+u4H{<`pjsNp)pNHfB)TQR>@PBINIpF_vJZb!&?k_yxpp9qhS#vjI@~!Eq zOD6^2`r)a13?ANZ+LDI#f7N;B|8A|EDgt+mHWKGanKEr!F^NiT_jM zE&1$HU1IZU_;25~zxY30KkL!G`}hIh9A9R`Xgl+2Hh+7s@51%wTg&Tw7uh_Jejo1i zop1B+nE$8SpKD$a|EJEh*BAVsI>S65{!cyCouTbXNovwkuDPp=nz|B3(e zZQcq07jFEY8c&D+3pf5xjR(X3sVi)r82(Q^%huz?|EX)uyD&-K*iG~Z=*JnpzC#docp zfBPLtzGvEez{9ss@%LYueSbJBDIwAuE}7sTKX|$)9vbVL@B0eBKdSzniH91zpFMw{ ze{OjFMNb}d-jC<=qVEr>e>nM|^L`oj{UZJ^+>`72*Z=C71J3s`Ppnn{zLCcNX*=HT zwfB0~w_JF@dB1Y=c`vu^UO)Oz`_`h)D z|I|Ew@qg+fTYt}9?|e_O^&;_q+CJ6hMdJU|g%|vvI{$+IQ)ij?!~dzXx28G&r)K^i z{!g82^YQS1YHmONPhDv17vulbtgnp!Q&${p@PF#c{bkPosVnxCI{&9;{bu~1n#*JU zpL&KJU*`Ym@mXb_1^=hUU*iANl?O_k|5MkPN5ucBE6wxZ|J1x5;s4YP^8>s1#{1y^ zw0)BO{sjN0{YzSzf%ow}ej&dH4gx*C6YcxK=^tI3{LFK^od23oJ={FtmC3#TveS9M zCW~@|HA`PhUfy$O{TFY#I(^EuyIC(d<-wF4&Ig{p?#f{Ehm%r1Te#hMz^iV$Civ64 zGkxED^O?YA&H29Z##5|6n^JsaoAYSb+;k@B_4Ms2H+*@k^MkH0`bNro&unS%fVTed zZ(sRAq<`1#rIfxSwm2Vn^>wGr%e^1zb2t2>v9CWFJUFIBs!o5U`M+B_bnt!Rnj^un zKX&(h{M;d%N7&Ez&``&5m`!<9d+pAZ!JQ}Pr|R}Dwe@|ovM)>3@z}C{Nib~UM&IjK%@1srU#gDZ@?}-Q z^Pe8@oiNFMAG!Ug@7B}01V`7MNY(w*G@*TP%SUHZb$WRrGiM zPmh;^h2wbrNmVB=9qas`I%jR7^M7hykMV!%412w>*FWF*ZF_x;^!Rb#_l-BX;qfOT zZLhzLZLjC{`s};X-XGZOw{L!*V6X4K`TY#@|MdLe{fqtk;G6d^%>UDN=6f>#PtETW z@PB%~;i>U|>QbA(ivLsdeunvf;l}@|EBEF)|EI3lGu`<=_1xWg&i{qm)+=v3zr8=g z|7m-%y~e--~QL^H$Ga;(MX_N_#!^&A%`B zKVAPUdp%|SU-hE>4gOC(*Zd{^Prazlyp#Dq^*nn$$N#C>AN*gq@qcRk8U9br?ZN-4 zd4HDr$zDxo6T!Hy*2(XydD1+Zv3B`dDZwoHNUsR|Eckn_`h)D z|I{2G{GS?Mi~my>TjT%K`2M>8J?VSN*1TYA_SI?n`>y7)Y0m$t@l^P~aO3~f_$U0I znt5aRKQ(_}cX{I&i|?9|Md5m{GS@XiT_ix9x(n-jsLrD&=>sW z)1zy@80oduUrf{AUAl>r7ORjroX?r{0DCSN~EVhe{ZB;Z+4$=ykN?Y zzvi!xe(_)T`(|Dt{!h1;d4%{sbB|EJDeG}ZY(-F_PXr)It${x974Ki_tF_`h&7|4&`C$h@HWKXviq$?fjoU z?IN#{cQ_>4FmTeKY^%o9)d1)92M$`NN(6)92G^ISu|#jrSX}t!cVG zKc?4pZRR^Zuc-^LQ&I7U?|EI>Qb?mkz{rZC6IM2s?y9ooA`c9iLBB&a- z%y;snkG6MR*5_sZ zU%2sqYEF;;Q%_5rHM1i7jFEYn%j&2Q{xlyf4V%5AO26xd_Mf2TK-Qh|EFd<{!h(z{GYBb zbK>~mJA)7T?f9TwUukUC@5TS=^!P;lpBmqY|5N8po#OnT8V`v73pf5xjo*8+@|eGV zd?5Z$`^)v?|J2oXdH6py{uKY$Yw5cY|EK2hiT~5-Y5bp>^S`kFgl`@X%>UE=F&~im ze`@(Zb-t~)jsH^@XJk45r!LJ-cK%P-S7P)0@PFzuYy6+OBx9=cf4(pHKiwXD8~#s? zC&T}#XJt36|Eu%Q%$)B0pIZJ;J;$~)|4%*JykM__Yy9n*k(ufIpI%?+l$vY(_R`Gs z;Mq4CyF5GU)mWcA>@(v2FYfE&^X}r_EZ%X?#{Cn%zPKlhcian>+wF;*Kkf(9qT6R? zMCTLEu=T0K=l^fLU)=x2k59bg^AZ2!_S^F%ygxi2!_D*c|LXE7(fNV#j{Cv*`ogR) z8@~Lw|NFfD|C`SjzPz{x#M6bh$Gu_7fb-Kle1H~&w~dbOHN$;!vCq;n-66EpSnwjhWUS4gMR1yU)PQ{|IXI`RdfF_|1aFk z{|h(k|Ef8@_&;^)&K;fqQ!`%=|EF%(p-sU2KkW~F{e;GD-lLwV z!udaSllIM>|5LYb-Q4*gzU&q$bd4bI?YUBK$?k~J5^Z(S$t6To}!~XsoK44(5 zeNAKc9N0fN_Vyvaz1QG@&j0EDP8ibL`9Jlz{@tDbQ}-X(JNWqB{r>uB{GYDB|L8%^ z|EULzvGsS&|EWie8tnX^df148&i|;K$md*cD_v_cs&Hq#51Mz=qUQh9V>Rz2%2Cu)p z-XGr%_He=ft)Kb_=K*^*YvKH#dh`5+LFJRv9<6-xVdwXjui57O-}2|b>-^sqn^%Yb zQ#0QV|EI>U;s130wdVQof9iGS<(U7cUSD^_`9JlBJx87YQ}3ud?B@T48~>+1W!~^R zwG(`w*sZ{)c0IbN#D+Hzv~EJ4GA+m-6r<&KI(O_&+uC5AlED#{a3e z*>?P2xbc7L-8P?(`G49!ddK9UzFEH)|EKMH_FUoS|EV{a=fnSn8~>-?vA1FUUv=HV z6VCtX`nMjr(yjli?F-iLcK%NtELr6IpYL8ho&Qr8_v+#NpL*fgQO^IVlShwq{!cw+ z*bwLcl3qIE{9pCdj?Vurxa^4Yf7|CwbpB7BZR=4m|4&_D--qJ=)U3~d|5KOPysxZ2 zKd&$S)nVuT7OY8k{!cw?c~Y?K<>%{DYY#i$hu6F6w&x;^{|j%&|Aia>r{?n^{NK{w z9diB;uZI6qz}_m&G|p|TwDM1xtAaH z+wn*EKiz&B{}*ojpN=2v$uR#<_mBLaTK-SX?Z^MAx&1pwe<#xTzruM(od?9%;s4b9 zzL@!c;l}?Be(I?6e|(;Z{|k4I&fkbM{%>;SG3NpKyd3|hX8)JAyFb$SzuaFOa~_cW z!T+iG{Vx7b&F6dgKQ-$;;s4Z0wtf)v|J2j$`yl+Ent4k2zi>1EPd)vD|5In0m%;z3 z@pbq=b(;O&8vmy*S=KQBPhDp7{_uZl&Hq!gehL0hU1;+x@qg+nyFIUNz0Mymz7N9x z>3H(_{f}zS`TIA+KEKERRW3Q?{NI$N6P^FV+~NOHmW~X%H91*-*}8)lykDa8e`?l~ zWB#8y&%7W0PhDp7C-8r2ydVBgJ;UZv;QzwSXPIi|1M=VD#{X&m@QnDsaO3~fZhc$x zf9evOhlBr97g+!Gz;@q-o9*-CUR!;0`FA|H$v5lAZZF>88_!hy-df*$pN;?1@#OpP zhhAOjyV|}lKCym zZni%?jsMf}ah}cmU$|dcm+X&ctWi``#uu?r!HmQi}}C1+8uEIkM&8HygIP{$G7cw z-Y?BO75-1n`n-uZ_No8l#Qo0q;e%Rd^!8n5{;%cIp7kS6?sML6?!nTa!e+h>oc~kLvdg#mS$=!2Jzw#E+MaIvkN;Dr+B`h`pE}DP z-}pZ@&)U-I%m@~^EY#SCvLKNzUKe5J$W1Ry$XHv`hx${_6l2X8ULrwv*U;VQ|Iq1bpB6` zzr+8jIX~SMIBD z{!d+MJ_i4%&fPVg+v~3n?`Zq)oB6)BKaXgCCfV;R@PEGT`$+tsdX%j%%K!BENU-k< zFIn3;Sv{;`h&<~(5j!CgV> z@r0CreX`Ygz0<%%%4k9pR)OVAI!NUNL z$6BQ7^rx>p7}Txn;QQd&gTc}nJ$&yyx!2|q_K)ueM!Hf09zE^Kw!Fhbf6#X@u1D~P<;PNWe~eGLIGC{fWUB73w8DP)&Q#r>gKXa4*XpiK z)%`uJVkoa4sd_vlR}OIgPc8qa#*Z-nPd$CzROkQHlWhJR{!g7~z6JlM=Jf^tr{?_( z{!h*Np7=j??Z!-Ae|;C&dY|||Z7;OLLo-eF# zkN;EW+WRZ}_s2K$SMA>?-^^cq_K$z}J;%Ht{!h>6+2*hDe`@}{Y5IE8G+jRZt)VS^ zSMSaVR&Ht)Y5bqg&%aMEv}xzJm-71r^MATL-ajoH)G1B3zvgfy&v)Myb;ZFm-|8A^ z{GZOh#QY-uPrb?etzwm!*9>4fMHR}cA|J2OS!~dy^?e9bv^LVjY zlzuyH-rhIsU;o1VpRSMj-1t8=^SkkXYWyYsPd&q4Z}5NWDto=c|EamX_&+tr1OKPy z_ha}!HNS7c|EbG1mxNH17&oo_x*`RldU`{whC z<4@h-o9%u7eWUMO`@97Ir@x2z{a?YdTl{wV&FgRVoo4Hy=TzM8PoHi3_u7#=d>5FP zTlestk#73OyL{v0estsA{_^Oa1HX{w|9&z*ivLp=u1|CRPc8qa<3Z#9!j1n^cVwN!G^@I`7T;N&E~b=?;DSZ|I_i{^9%f+n$HKA|EJ62@q_>Ky*Ve?@W4ZU|4VEh z;*-Drrtgdmxk2x4-}XIiRYtHe?>oNve2e*iy1ixg`$+ts8lQ*%Q!@__|EDgs`EdBZ zaO3~f_%ZxnxT~i=mZrZ~@rL+6HJ_*A|I~Ov{GYmfdAjp|>OA|rwaK_2`Rz3G|8#v- zYf|0(KXvumH0S@+OU&Cb|4%)C*_2@O3(xp2vE%WRX3zO9UNSMj|LOFFi^n39^|@4@kZ zYSxRv|EWvNhvNTyoA1Q`sS6h;2JMo6<-2(P6gU4**N^98{a-cn{#gH4U1jqDng6He z_wmgC3->dFKk%JfJHh!sZBMoNd)trywsCv;;DGgiwLQObXfWsxzxU1jzF+tJqkle3 zFCXFjpPoNy<>v45|Ky)fH2zPY-{1k6|EJEX92tyy?{B_~N=F8t_4igaU;{U3~z1J|$FKL4Ff9mN|$2bZ7( z_&@b*^MLq2HU0+wr^d74|I}p@Mmzr(Zv3CRV%&J=|J0Q>uMq#I#=GJF)c7;}pBgX6 z{J(JH|J1Bso4jjt`k80maej}kKeEL)=g+!wYowpJd7JOd#02O6bbi*;#s8_($B%XM z|H6&`)AbjQ8|T*lRTqsPAK?Gg_&oeyxLN;K&3e78|EuQoC(8~*n)!daezvpzuNv=% z|5I!IUtM0MtuKuK)AqSG9}WMfW_{S?@rQjgkL-WH+1S~({^_I1NBs8ml&Q}D>GJV) zS$RkOcDmU!ja`+L>inOskH-J0XHQFU{!cwCDcSiyH69HAcdq=`5&x&gL*f5)dK&+y z=KT0SHT#GE)BbaM{9m}4|EHdw)!_fsx!LK?|Eck0%>VP3Z;k&`&oDoR{|h(s|J1C1 z%=|yy9!`({Q#0QV|EFgC-cM?-^o`eh{q<-w|4)}+W9P^Jsb`pP!~cc%|K8^s8!w0d z({}tB{x96&*RQx&`@D|(ytwz{{s~`x{Pi(De-1wyK7IW1^HQVRi!!70^=dMs^8~p+ z!j~7H9~kerXN=$exDWh~HV+%VK74GrJUT?#VhYfd$ zdE{_sBt*BzJs|U)!l#e>ySNWzK2-Shalgkrt?+g{Uby4_k9m9H?eUJEpJx4ETl2$t zJFbuUe`?Op{697RkM)1U&HO(#>+`Oh+1RYVi~l=v;5W_}cIeX9`M+>8|4)s_!~f~> z@OsSuQ!|h6$dG6!+;WTG&iUW%+Sr^Q|EJ5>{J$oje&GBcjsH{k@7&(`zi{LK)ZCx= zKQ-sa|EasS@8JAjxLN;K*Ux&r_&;^$w(Xq%Q!~#G{}=A3hhOV&AHH$-?bk$lRL{m{ zo*?u8bpGZon*_&OUF}aFm^Vt=cP`Q&{Ou~=&1^l}>((_k^XvvZdCuQH)}zJ$?cMTQ z=l_^*7=FCzIFQ!T7(>`nSzu>-)w#h|LR(`@hby^@lqJ(fNY^asJrl z#l2v>SlS`1=bli2u{$k;hy4 zfX42BiOsjO`G49zd_ZqE|1aFE|Ev3Z(!ie1|ApIr|LM;^anL2s|LOcR{!cyH=KF1I zw%0#CN15-t_~Sa?Lx&G={!gc;vzFEQ^A8y^#Q8sMA2w{5^MC3g!}>e_ryew7qrf9f534g~l=_5Qj8 z&i|?R?cN{!^_p@1`q%F{6ny`Yv5`LY_88wQ_Z$goTQ&Boy*6)e%xJ$I@Ar7ZXn%e5 z`dOoV@2fj%eqdyze{|;v-^}~l{G;K%ch(&X`u%=bs2lvB_Mi28@qcRO`{Do8yY`(3 zdVgt<-@k49PXxbtdZ6zudyl*Ie|7o;dyc#Hf7M5A-rs?X2l&g|a_lPS|FnJL^m6C_ z)Is9(;A{8y@s}SA93Sj@=~CbPeUtlXZ{N%_?>wNfGl%vI_NKg5|Nf1Ko%b7O9-sMt z>R^0x=l|M`JM8@5Xj>nH^?%iw%kBFE^M7g^tr4s|^>Y2Rdk#6@$9%jQGhXtYw>HW7 zKW%6IkEHf5)~_0H$az0LZ^i$q@peRF-~RX_F3 z=dbubou0=3g&Y4DZv3BG{!cCcr{?os{GXcNpW^?tzYEuAJO8Jiy)xDLKQ-&u;{S9! zX#AfVABO+a@nwBj{GaZhN^9o-g`4?*;l}@k8~>-~@`wKETfXsU_`mPiyu`8SI6 zY{&np<^R-d$N#CT%-7)m)Xe+B|Aia>r^avK|J2OWYW1tT{Qls{rrdd_Z+s2@Pp4;n zSo~kO@qcR8cVYgYy1+iq$N#B|ZC)hv|I|fxeDHs2*7wE#sY`7AVf>$tSFwG*j{gfc z{!jOBo~<{8|6@&E=Kp0apWyr-#t#3Nvtpd{f1OhfIR95-^YfVhr^e6W|J23yeI))* zU1sy9@PF!3^Hlgh^&I;?2LGqFrS{zXKQ+gf&o;x&zG?rMPlo?f^Zm{9U)$qP&;AWA z-0i!_=3VW4Z%3%pod47L@j3Xv#!hkmPhGa7!T+gQzZCzcX5NT>zSr31XYhYIzI@+@ z|5MMm`Cs@yHS<02e`@>}{!fjU!vE>@gl7Jq8h?lXQ_ryPC-HykYFlqDeQ346Jm!~l zKVRXS`6a)vD)Y_yZ1_K2Ki_xa|J2MA+|V=Mca5Dt@BZn&Gj=!lKb=0a&en5H&G5%3 ze`iL}^yO6Fc{|br{GW~|&rkfHn)#Yf{(7>%|CnEf|I_1R`t}Ux|I|h1b?|?Q&+l*W zf984dfAg2_cm9vZw7)2&v`%k%7h{HOW)b+ykE9mAO26BW1es6U;5QQ&~~r$ zetf^Zv}>RGPbTegzK>qlqgVaRp>@vp6>qc0^J6`HSMQx3O#6M;`nyVZJMYIl!-slx zuK#G;F6aHK?D>NKQ_KI^%oV?$FaA%>d^Y@_8c&A*v+rn~|HI?r|I}Ib{TlQC)Dzb? z_`h(QpEz%(tYN;Nt!It@Q)k)p3IC^_X5Rr)K^W z{!h*03I7*v{GS@%h5rjT{x974zi{LK!X5nM;qyx~wmDD5y>SbH2zPg&$8ER{GVF>Pc8qa&e)yl{GXcnS@=IS^FZ-`>YRNI z>;I~!?>C?E@L+#?@qoWQ*V}i2`9AY6zRPWUUT&L6Z|xT}wyp1*|M5rP)A7U8*yG1H z^C4|L((mc|X~CVxnj4?BkbSUm+uVz{qP9ihs^ugddI%^ zAK4cCk5Bz$i z@1?6|2DZ(2_3S*3XR40pd>${Mb|d zvTy!9djFkY_+~zG#pYl7=Jx=PG=0~1p{@Tu^r{bh7n#Sy|LOU}^Zo0G|Kx8k-K*!{ zee-_i(7m5V+FoDMbUaGUlZ{;2G}3Qw)5{% zf8YE)g8$RM?==2TU9fVJ^MC51)i%$`{GS?cga1?Wd!o~CkMWmZWAnPRMvag3-?vQk zU19$|ZJs;XA20luy`K8!_cpKpImvg0-QV~>UEgXu{`f!jD!YI2f9fT6di|192_ z<>vpXdB6SAihO^1`tolU`krf^EV)^U?*;aFVg8@aKVx@saL26`etV_)z3SgrHMU(| zt7$cne)w3e?^!mlaqUa9eb2Vv`Cj2vwHva717A7id&b&~VD<~Aee?Mg z{!f3O%(CAr;{VjFM~eRoH~vq}=U4bYHJ@KSG~s671uIgW|I_w-TaOg~r)K@&%}?Lv zJ7cY_rx4uXo6n1GnRI8QC$6~5H$Lid^ML;EC2Rbj8V`v7Q&*V(X8xa=`GS{x_a5KO z|6BjNFZ*VG-w*oS8|h2Rzv`Rc`{Ms}duaThn%@WBcx zpPJ7X@PFE08vmzez9s%oU1q)!|EI3D&(H9G>MHxaGX77^?_2SIYCIhNPd(Mv*+nm5k*KXsw~`;Pzff3MD+==@)}@qg;c=Ev}V>h#MR{GS@nhyPQT+xy3v3xDjJ z+jrlUKk+@oeqYS|Kkd(a`#mlGPd(ReFaA%>?{)EiYK{l~Po1+Q(fL0$>mTF))XdMs z|EXD@1^=hUlj8rvJ@0{+{r=9i-@iWi_A9>UnCHX)>Gqb|=gG|fQy1Fjjrcz`^9S*N z;l}@|EBHOE`9C%5dE@`og$pMIi`Kjy>F?a~Yu{z_Cj{-EdneNPKi!_Pxefj=-1xt6 z51jd-@9CAJod47I;<8cB|EckK_&;@S`6%cA^n93JHqw5-`ak~pky$>{`9D3M(o2Wi zdKZ88&#$bCQNbU-{+CGO|MYoMp8Z}0|EDgf8XlbJ`$?KUzn)Rq;Q#b_b#=vP=l|5x zOGi8Zr_Zl53WmA$fBol^*<*vJ+BHqr=gV1X<^x0D|E5lh`ihKHdp-VSVS2}I?>OJb zJg48cTI`$kf$@LZj?ZKMpBnGR{696mZClE6-`VE-SpQesSsxewr)GUz{GXb6eE2`L z{GXcna??+&@!MH%82_j31!KoL|EI?L;s4b56a1eV|AYVYZC-Kml8xz?f9q}M`^u(H z48F5&lkaldj{np4(!>V;r)HiN{!d*w)n0GS|EZae#r!`tw+H{HX8)Q0r^fd^|I{wu zY+pTZkKbQBApXzqzs)Da|Aia>r{?~`|Aia>7jFEYuAkH6|H6&`Q*(Qm{}(<#{!iQS zUHCus+-!UQX#P(v|EI=F;s4b5)cub&HrI#$({>vFr{?%G|4&^#EzS8q^^7SE>;I~& z5|V;TK0B7)F7;Q=`|)_d|Ecj}tpBU#`tW}`zx7n5^emSF25$D!T+i8f%w00 z`Gr^c)3Y7_r|YBdU3_)4&Hw54Rhd5=v+f$dy&!XH@P|J~JN)_;_j35f@b>t6xwYm; z!`tKQ`^J4+QCjr%u`qRV4V9-V*3yv6YK#k)4<|Kc4#eQ9R&^5>*SZ}051 zs2_}bKi0zz?+^1a|F8bMGX-6FLwS< zJ-JiI;M~cZ{dU${E^K~_zrJ2wx(2;=-|Tx-mrlKwrvsg`TDhfe`)-mZcnpTO`ZP> zH~vrEq;=Ea7iX^a9oYJ!_&;sO%i;fg+q}Q?Ew1v%7oS$N_e$UK^=zB8i2AeUt^aTT z*Cn?8FY^V%kJtG6zj5yu@1RL^eqMb3-teZ;^>hdShySyy553v4Gclquz)aLKm{6AfO&ruEY|I|Z=4t4%djn`xTpL+1XVb1@l zt14=o|5K-zmOKBazGV1F=l|5a-ZKABjlXVs^G4sio{ns~-tTW`^R_?v<67T5-td1q zKaKy>@y+Zu$oao(SA5I)zZ=)pIsd0#X`YPrf7MGb_&@dP?G5Yyh8zE<-n`>*u=vzu z-*~~X4<6TYP{e7RF3l7H|{+ad~e4{-$(8ETz=~a--pfj;s2V| ze%pD+9kyOC{!hKjJl^j*4)dp{zhmA{*GC_kGbGYw2L}7zz4r>||8)AD*7(10f8$RB zd>`9;()mAK|H(sFI{&BMbmWZlf9j!0+0Or|gC3VU|EJ6EWq&W=|I`Ilwa)*kOJ>fE zydKQ8zgO^oS1&x|{NMPF?VSHpk4R|g{NKZWJ?Q*j)%@|!|Eb3H*CW} z=l}S;4F9L*^P~iji{ZvLOTz&>Ba|EXCIl=*+*X8xbLc=2TC|H6&`)Baa3 z814L@x^U)T=l|3>v->&!r{hzyWVrKx>e5Byg6IDHJ%9X47LIlPPxnvp!qLwEg&Y5; z=JPB3pSsAtpT_^G*?;_>x^!ux^M6C$Kji!$-Vgs5Zv3B``xpQBS@~h-|G0ngf9iC* zfAN1;zI@pEKaMBhOQuKIZ?`x7qLfU$s5{-TJ>5I?ujO z#Q$l#{GS?6<<|ebaC$tTTmSb$FEX#_*8jcGe1F6IKb@cXf%rc)^8@*8Q;qLqU$wt9 z{!iPpH`@G1^M7jQrQ!e7Tt4&vbpCSN-@%t|Y20r6yW`s%eOKD|Z_ie)_l^G>^oKRR z@uK)YT^{S1{j>W@-+aIQ?ETAq*V^}CcjqsS^scuT`R4fH|8)P*?>#locZKag{!gzj zH2zP`_g^c|)cDi0zAXMvmsf3#|5LMG)`)vb{q@uT&M5X>Yq#g;uNC;7wXZz5cT=A4 zIR`3({cWfF#{bpaofT>PpN>zdc|H7}y2R$!;Q!S4xs7>K{qZd{KZXC({Wr<{6#h>= zWm|G^=aKRCPo(a1-j8{FBd#1%-|@1&&im1i)QznF{oFmy`{8*XJv*$P_4o4MzA>G~ z|EW3sxzd64`@g=s!TZ^Ie&^QotN+RCyPWr9eLwu4n)BoT?s)Yc0dfmO%`9Jm_|EFgE@qfPU`|DrL`|$j-XSX=-S7hD+ z|EFeNB>qobwx`JXKQ-U4BL$`|gMAO26x{^I}Cx#stn|EJC~--rLx?ai~} zh5u9M+xolsKXu{3BIp0qdHeE%t>*vK#kN2AKXtx69`S!_UVrg_x_%n}r!L-+;rw5? z@qg+f^B(qE<2&Dc0sc?h@xJ&!b(+l!!vCpL&8y@8)JgXK0{`dR{=LWlsS_`2@PFF> z)Fo4#|5GR1`!DAI>G7B_YaCw6cfXuo&j0;$;AZCm$4nm@Jo{twe;0Z}!AR%-a!NKi z513kE^Vn|NlcJtu>)AfF_H4@O?Hip3+_rsPaA^0PzW40iYU>F=f1z`WdtzE50rg{_bKY099d*E>JB|EeRl9&XE2_0AJ}ZT;bn zzK@;U6SP>?(>MO_gE<3y?>W9Rc&c)w@9l>+2VX6i0&luz8|ApILKm6$@*y+s|r|R)B zWzKl#|J38``(=B5@~0oaU}ErC!F|42PtsoBe5WoS@BE*xk9p$wKXtynU%>yVv&?tk z|H6&`Q{(&af8oaeshOXQ{|h(%PhD(23IC_gxBbEYsqyLfKlP*yiNVR?6zkgMWhX(_D<@(N9 zKEnAw?SJK#MCbq1_*49!8V~!2@-p8XKm4Dz)A&Dirv3YY|5In1PsjhM^KJeg{!g82 zeh~ks#`oj@)VcQj!~dyk?Drb@KQ(`U;s4Y%HqR0Nr=GE9it~SJ`M+@6?*sht%P~Lo zV7raJc|PO+bb5TC-4}j)sXczox;D1W&$d~VzRPSrH~vreU%AaI#Q&-JeH#8xm(TC< z@PFaP|Aia>r=DTghyPPwX7k$Bqj!j1n^^Y=ggPtETm z@qcPQFJbs{GXcNU*iAt_Y=Rr#Q&+QY`a_k z_rl-j%nNnv|LX7g_36(4>GWmR_&+u4_2U23ctHH08sD}4;C+$C|7rj5g!n%--f-ND zUyn5YPupkO=O4ZHKIkuRfju7Zf4aW8wmvZaPhDib5&x$yFh7R>Q_KIU@o{eb-wU^& zatm5-26Xv!t625|EYOD$@;%)<`d%o!j1n^Gv5&Zr^e&C^?xty4~_rR?Ju|WEAW5n zQfvI58vi%@^5^{JmD=yWANcO`k;eb&^sMiT|5ML0ujtnQy>R{f-k{aKm;Cve--!Ry z{?4(-7yeH@+a6!|KQ;dK)>E&g>F@sx^Lu|i{|n#z`&9IY*L_!+_q((2o4#4!_#dTj zMY?3)FMX#kob3Fct}oN(1LFVG<@2UE|EDgUlMpNk-t*flW={+rp76f!s<{ab>;GQ3 z{RMV<{GX0bX4Pot|I{U=gPi|UmzE87{!cCcr{_nW`8)id8sEqKKYjj#2gLuW<^R-d z$N%Z`B`zQTr!J@(>-?WSzpkm8H0i5F)Qj_=1sGC`{w_i`s7#61J>GlwfH|Z z{t5pVZv3AbUx@!xrzIyk|EI=F;s4ZlLj0c^FNptB;|ZDnr)C}<{x974KQ;5aSpQee z{4V^T+RYa;|EI>g;Q!S46a3%7+kV+F-_IKVr{?tdKQ+gL`G0DBA^uN|U%~&W*^d8H zGye+zr^bWf|H6&`Q**qkUf%6HJ7Hq*^4oR3nMX0}qdmT>CM5*;Ki$5W3Fh0(|AqTw zTmM&=&+Wngg&Y5;=KjI|h5H}3Ha30}|EKNvP5hsl+mHWK7n{#y{-2ur5C0c#{GXb6 zVE8|E&eUnn|EUX7?cXc&f9k@t4CnvU#mQ+w;;v)qM@GEmykE{F`#j;Z#%6vQ{!iO! z{GVF>PnXC2!Tdk+9nGbbII8 zr)K@$+un;d{!jah_hkN`ZXezd|EKL0IrjI2`M+?7y#?FDU6q>? z>BTwr`DMtP%uA219~@r~H{RU7@cHAtAU7|vJ>DhLqx)Bw6o3d7i1eb^<;_ozdc3&*i+6l|;<$hOypGR1{EvBv_V^C(|IC;-jQhTL*V^+reExXH z=l$W+!l%cZ{a+pTexEo0uV=3=k<06Q$^YHME{R^h{9m)GUpfEB_2K`*{f~F=@ZG*g z*WlQ^Xm@}4cEA0it``SiC~fSPo!SQpKf29tZ`ZC}@PqWm?$Dt_u)Y4aM-M*vw)2JU z+qVzi9)GJpJ$?}Xr~Q%tQ**pd-*~g%KDv9Cpl_GP9&Uc`z7se3?E^Y>asIE_)OVae zr15{@{_tZv{e|uQJ9ZAfds$<5>(DVc{>vNvcIN%fs%dQIt<8V&dVhPEx7M++vHRQl zx%H1-=ePH3(=u3_)Y#1T!~f}cFwYPFrdjTRepP5>-(PVdgY^sfAyAoKNZ+|w4a?i8|m=l_4DS{b!{1)SJ%0D%gE!imHET) z<;DG9^O%o|`@bd*?0tWqE~B}vm#Y8f|2xJ!UAx#k!T;C!fARf`_kZgJ;I~G{IdRUxbc7C#{Y%;+Zm00Y0DPQ z{~i3wyUx#EV)r-xPtT{0Et)$27jEYNsRMhy;Q!Pu&FkX-)cC+Zes`yD*576QUtQne z!GoRuQ}^l9$N4|?kpAO>m(T9-`(IPBF!=kf?Y@`JoA3OePG3`2?);y6e)2Hq|I{-R z`aA!p=Jj(!-CF;AHLe>xyLydpyEB57Z?5tCAK2rw)lXOZP8*Tr{NLCIA9DWh_?E-Y z|EZZThyPP=u=RWYZS()sYj!lO|Epea^X~9}>eY2eo&O6r{!fk9!~caF|EJ!t_ptMS z;l}@k8~+z>=KrbJ?K$fFU%2sq;l}@|*PHKS{-1iwzGKe+g&Y5;#^d4t!d?BuaNpZ^ z9}oKfc9`!Sbyqn57d}1yPc8qa#`od>)SCaNmj4Sk{!fkn+t;(P&m6rvC`{|`w{Jam zI_SQ%pYL{khXlVq-q&}~q@DABy1YqKGM)cZuU)a(`M+?7pa1(RvYh|R9D30CzuBYv zIRB@foYLO;zvbUM;QZh0MGfo!s?(P>_&;^#ifL~CUze!|od4tVBK)6P{_n8|_dEZG z$J@5>h5FwV?Dy;Q-Z}Dl-^EKOIRB^ZH1q$|tdGL{KXtmz*Tes*@n!fwHS6;-|4%*J zehgh9wJO8I1Uenk4KOLVb zOGi8Zr{?#x_&+tjw`KmH?w@?~n9ToE=h^R#@qg;+a~u4hn)N7ln*UR?{s{gr+|2(w z_mzXr|7F?r;s3&o|5M`w-#q^f-+bO(c<}4KIetf9dZ2z?*F(++@_poAuD{lHKq z@B7yuaz2pz3;(B1S(y+#e)g-8{-4TwedGW7b^D6%Lc4tYpU%(cpZGsDpLgQ_)SMsx zr{?o{{GXcjc<_Jfd^^vgB&u9Lhn)yKZKQ*@x|EK2hhyPRO*!Mg5KQ-&S z?f&=%e|_1uK4-sP*Zbp@V}9^EORn|Dm-&A~hF{~m&^#;tPtQj_AI1NTII++9Kl)og zJXOycy7)ilN8UNnt5x_?cWw@{GYbtZ}5NN#{c;? zzlQ%)yZL~}SNX0sPlf-}@#Oa7|J3Xc{!d-9EhE7Hg}Z#$0^i&o{GaYG`g@D!_~!Di z`bVvA=4;^pbb1>9=i7WsRmTc{`K%{~|I_ue{x$wj&G+H>KXvWi3g`dAjsH`#ek%S? zon!NM@PBINbK(EgCFbFJe|4Hae$4N~|LOSV+x>WVcr}#g0#?}<)|9ZY&=lmbX z=fhu&uCM?1F6aGd{GS@%hyQCmYM1kW^yBvouCJK6(|JGE|NX%e1L|))w8MG7B=e`w zJ>Iw8-UB+{mv8Ie_FH?YZ{{)HeD0F^%r9+o^Zl4thX1?bXImTmpLw`*zwc6SYpgln z$M^Mb-+XbT@qgj%_&+t@_uKk|_4XaD^L_Zd%nw@mmjBasPLKanvpymIPhDp7DkmTN z*ZCE-o1OQg@qcRe5C0c#{9m~7e_ubm$@xD{kN;ES^YDLa*0*E+pL(&aKW#qb{68Pq z=)B*89r@1xsmtv6;s4a7cKq;vYWH|F{}*ojpBm4I|5In%{fGZk=h{3I{GU2|9rKOu z^ZS>wVVd)Q+CJSLulPUpLfaqwpL(9HXNmt)=bM+a^*wzT+4{BkKiz(wKlnd&xqaV^ z|5M{*@qcPODE?24Z^Qqo%jHB2j#aH+IqhDKV5#+fpX{n)D`@RWtPmMRk|EcrLyWs!S`8Mwf z|EI?L**r+!cv@TE)Hi<9<~2szj=yhSU+j4L##7qy@y-0t1+5c(PctuLe#bZOU+{lA z9{ipG{}=7fzSHde0{_!?eji|$m#o{9x@-cE58ny%5}g0j<7reie(d5D^^lzI&j01S zxxsnB9#dM|yujHh>L9U?^M9w>Y;Yd1L-9mgKlp5lx^(8uprY+vzGuvzZ|ey^l=8~t z_09**Surp8`?WvxJ@>Nt&j0mayw3T+!krtP|5GnKbIkd_Rj1cF|9A3Cga1<>KY7sk zKlSO;`9SzYDKtlWNC0|EI=tGXGCKapq{}|I`Vy#`5~%w@r$b1I=PtCuN_`h)D|J1A}kN;E4|EZZ@i2n;W{!h*OWBi|*`OWx0HJ%6mr^fr> z|I|GH@qg-K`}Yz5=iBBp*>68)BSc{UpqaV=R4Q@lKFPu zMeFVNJr%{i3(TM3|8#k*pZd!W${V*^o0s>^;~)R0)8peFHvgyQ_?>RR(VW>5Tf z{(c+&%>%wUeobFL=$rX$Zv=;ZS8mE=9Pc8qa=KT0SHNSs+;-Rnk z#s}j6wEy@%{GXcjgzG$U%2sqYR-@U zQ!~#I|EK2nsg-x1Pt)I{e13J$OZC3F|Nq_c`@Sn|eO>1N>GU&fyy+w`{Mu9v(~0N|EHc|UK9VP^VitxHU3XM%g&Gg zQ`fFa2@2-Dnzp!Ao%_8X_YeM0U9!}EU-Rl~Y5M!0+dH?_>%KWYo2I-GY5bqg&*|}h z>cWLd!QJ=&D$<|)@@?Oh_U|F{|FnNJ{?E6q4~+i{cgH2a@m)TvVf|knj{;kNm-Tcgr;Y#fpHEI7 z9h~pi#CLYauwY%+X6gF8I5B0c{WaD2{ccL;q)0O#3je3?tMOX+KlOC;W9=SaoWAGs zH=U2mH6M89nI*nCJ^oLpFSU7e%>Prf9sj3hJN{42ygB@z8c&A*Q?ouK{!g7bInmAk zQx{CNd1{l_`u!7jFEYn)@IBr{?nTe`@?E{!h*RF#k`Dcf$XLoArOycqROw?$1g){`fyN_aFW* z-1t8=x0m^Ux;(rh{!cx}{2~5NU1Of7 zcm7Y8ho5`qp;LZ;YEsjj|I_}l9xVP(Ju5BE`9C$D4gY7R+xfp*Ti+M|=i9d9|8#oR z1IGWUIllP6aO3~f1?JK4e`@AA;{W{q+y3DHbbDu~r@Qrk)zt<0Zv9_%Sx(f)m6=Zr zzkXH5yx*eO_W9;N!>9ib?`QK9!`sU;(*DoJM}|*7KP&1FYto{=FWz{|@cI9vZQf&K zd#vYWrbf2M=K;po^Nn}h+r{Sr;((uDdEITEUik8d_KcoBKF=@i0ps59lHO4-)a%md z^^NbXgH${(*b=KCHT(AZ7Q9}c|fO255{`9qt(`slWeuepi=_|3Avk14xsqY}>ud=A09obIy5k+Q~WW?CdU^bIv*M zl0lN9B1uIMBpZ-0qoOFHWRxTZ#E4nsL(%Vlt}}Z-)9?FLN&Qq&wO5@Er^DOR-RJ82 z>7EIXU(mw%iTHone|bCjgPi~Pe`4|g|MJU|OP;`7b;z0iJU;TE^T1xcqmSKr(3jtN=!L=m)B1ai z8Xo*V@rYrgL;jz5w%u=1|5rSurZ)J0;z_I51piOG+s0GK{}ZpTstW#}_`;d?{n9_S z`0tVP>qo!d?2P@2|EK*ieCUwqxw9!vPyOei;QK9_n;ZN;@wt6xg8wJJ=wx&LpLmJo z<>CK{Hymm9|HRbK#s70Yc1iI6#9L2X7V`hZJB{)G#Jf*j5#j%d_np2X_a_*Yo|A`Nu{aDEV6Q8hpzU2Rj zPoDW$g#RZd?+^b^e8Ux=3jUv%{fqx6j@oq({-3k?qSXHt&$REe$o~_MUcE8+f8wcI zcPISbPgj;iPh9eo#@=U62ET8k-4AUpd((M!!Jy#(sr}&j{6BHY>Xhi{cYbWH-%0!b zwv4j1Y0+06e5LWt4~_@FkN00gfACV{nDNJh-^csUqEEc&j30>q=k4a-;s1&81Z`X{(}Ga$KRg}{^s1}vx5I8USRK^$o~^BTs|ZCe=R&S z_Pn^3UHTZvT{`gez z|MILpH2$Bny)VW8`(wlD=K8?)J{A8@j9-WUCr;Zu$A0hkIODJ3|Eayf@)hv^#LMk{ zBL1J4@5Ax`#C10Qg8vt1{68_{NBDnn#{X;m*6HRvLK_do{}X4}`)d3@F?o{se`4|` zhi?0fFApx6c9V0l^te{9ym!|LONq zYvW7!e?=8Xga6lH`vd53Zhjp8pP2Df{68_{NBDo@3iC}4nExlPwejR1j^5~8Wq!$sZ>)1JHr~HsdZMylY>EbLELr8!t(7t~yy3{6FnK z)`$NmCa>(DMRWXosoIwomHlR>bEV}wlK-dki@ZquziV$h*j(S&_z&++XngJ21Htzz zG#~IUt;aQv`uG0e`xTf!@Ylhk8@Ei_AAG-gyB6~Iw=sXrzTo>UuzGd)e`4~7N`HM} z<2BWLgYQ>u^`W2cKCtoCQ+tB%mv4D@d8z#xM?A1Q_ghx_1yBLbH4edcl@-`8NXve&7;nFcKo0H z-dCK-r&^u%pfmo7`7_?1Iosw0|4;p!w_{%L|HMVc_Q$P*=KZg<{_lLYgERF3 z&ChvU`)i@KoA2YCX4_}yk2Ah7{-2g#V)>c)f8rdg$Bh3cUSxTs_R;3^?mXG z#F^$B;Qxsi+W0yCpP26z%tw4oj1Oqbcb;$eYc_oX+YNT4>B)z||4ZcSoM)|?8~i`* zkJ*+lg8wH@tDa&$*Ief*Ire>y`G5NTjLaMoU2@{MbDx>rEkE#D=YcbN1^@3y-`N)Y zzzb*fv3kN^Nfq~=*CY6U!~ecD_<)_Kb%^f&{Hv+rC}&#m|2B@?8hpUH$2LVfe)g|a z@u9=JqW*tsmnJ@VXs6X5?(Tf(&^pUEAK<)y|7xp8Ji__lmb&PM-%WJhy{^LY31>O) zsY{CnUXzxl{_Lu;?;jTBr>Xx-vIa%h*H$=}&gsVfNz?x6p3}|p=GLZZe-11iVCUO5 z=LwZ#%qQFLJh5tQ@c%UZ6!ZP?|HRYkrUd^_JjHxI^8dtB8=Cz;aYp^L;Qxu!7dQKV z;^{WMU0;0u*>?YJ{;{+CKTSW|@_+FE#N2p)poyQzhCDiR)74Tv->#LSU&50NBcP!+5O|% zZx3+BXUG3jf5QE!`F~>WSMmSUAMStf|Kg1QCzk&w=6e|YKXIAeAHH_uB*|iIvWC)=iDRb#k?Hs`*;x z^ECK{i!IO2{_R|Os3iD*YHv7H8vH+T-9Gb8 z&HoegKIPd}hkX6iuRe3n5$EOm3ZnV%9dll?EBw86#-GIh)AI0#@&BCdc@zIH&iH>~ zo*%#d<8!_|^5L%k@M33t!fhiib*`}AH~yc_Kk^>&|Kg1QC$6;Z!~YXkSpFdXpSaYv z@ACg#?Od`q-+bR|obl1p3$Ar8wfY43e|nx-vUX0C^X8}0^}Nzx{@16v-sDVuQv5$X zPc63k!1#Y+`G4Y4yI$h|iFrRU;ELOQedMR%|7rbPf64z77ufvd|B3nDkNiJzo%wnA ze`5K6alU2w7rp;%|9e;8?ToKS{-37j`i}o6=K7BRCuaIVzrNp@I>_6uJiMih4|B0(Cj}ZS)%>4L&;;OZ&!T*ah{-3yRO=|G}#MS1jk^kpxd3WUh ziK{Fhul1APcTU}u6)pMuGtRlY3ZwhR{IG?$7X<%L^Ji_z3;v&&{^S3Nxjwb~{R__c zf6E5Hl)w*_zU<8P4gXK`vpoDiF~1M|KXHxuefWQ0{lcN(|B>&9|0k}ndMRgzzm~4& z{~EiWx~c4S=Oy<368}%{3zn@;jV@dF6X&I?Qlg((ePGQ`zT*4se(GGldVci7zy8dp zFSqYYDto-`>n~j~Kf?d>{x-}G{-3yd$*c(fPh4WW?uOqu7t~IR9{bL3ol7dm1^-Xy zTVYvq{+~Fvd_?g7#0Ax3?ETfB{QN8~pAh^%T`!8P{_pJ%|JAP_B_(5m|EKp!#l@q8 z|0m8U9v%(2@cndgR_VwH|4;AtOH0QF|4;9y%gqNU!eEdH#%m2os z)_#6}z_({u`*~*iv)^uE+Se7H_I5b`*%l@baD4R{Z|8X8|7m^2GbacCPh2>CV(|aO z)O*JN6H`AK|4+Pl#;j=XPUG|aTWWr2?RzbZZ;Ah>cIuDf|A`A1&JX^dnC-*=6VIPB zBlv$>-@>i0 z|B1;TB>zv$_Tc};nfyO7J{SIm;}!Z_nU{x|+8zb|?D`DuxH zbRXrk=BFeczucrezzh2%`gX~j><1?Me}nrb`hdyYw||d>?Mtrz+rNLJ zA4L7j`2H9_D6xO|h4_C*`@b3dKYTy(|HRZI#{Uy{>en^+f8w@1I|Tnvd_mVv(J%6D zZTi%N8TR(Uz~q)<4p;? zxMw0ib@`_g+Ed!xD|u?A9mR z`tlj)5xu*G`oFCkeir;Zd|B%Mim5OB#{APhJ@u+boH_07aL*4;C2-NrCw+SA0}t%e z!UL_IF#ezVLw(_1-#zT-^8oV&r#*7Wnd?XC7Y{l|=BsY~^a1Dg?K(!6U$Ni0L;FtA zpk4=>{(brE!>ztB{-3z>_))?C6Q?!Q z2LDgIbNQ0!_hWbY^43(8M3?v3>6|rZV(|a;`|N3_3;v(j%5z5-tVnHIUi4t_{U(kc z8T>!-tog;k{}W%dW`FSi#6=r6h5SEp-s-i%{}bo0*%p02Yo0H^c*CyX|Eaxp%bwu> ziR-uT5B{IHVfWGC|B09HI}!Xp@w)xZ^?$`14xSGFpLn-1{-1cifryy8UIgw!j@0|pZL_NtD~>a z8ryW=$_E;+zVWS$OU+OGe8ZRozQ*$Y)PB-@M)LnO|8esl*FQJX+b=PHuj(HooG-I> z{69^9<+GvC+N4|~>`JT?43 zO<%F2AozdcvTcik|EJ{_Y|aY)pE%9Fuf_ipr&f;&{-1b3#qi+&iF;Jpc&pX_6%Vub z_xOL}h4#J;|4*D^?}PCF#Ej3qZvLM*&%RH_|I_|iY~#)UytUD}&fbrX-SmVr`E>Yy zzJJ$D5B{HyN2ZM*--;0iQ)gnnfyQT+@&*u|0kZeY-aHP z#N?BlI`-w3=~vB)rsh2CoMP|8@c(wqIvM=HRC`~B|0m9}`XG-idcZkvb4E0#^Zm}` z(XCo`Ut`ftC(rwVbED^n-RqpTAtm^KLx!9Rejs@j_+oW6O+Gz z|EJ~2{}bcy;s0rW6rIoi6O*Tc|EK-S_w@LGI$k9<{piB${CvsSGAkqGyb2LJVg9IapCUN;QxsW%-`bOrZkobms}j5p)|i3=@1><9l?>0D~#y~D4&D1pcHUhc<-`gZt# zy1r3w82?XPYvZ-}e>$EuHa-5In0&FJb1QuL_+I#b>QBY-{NVq^8UIgQbD}WX{kcWX zb*GA>@22NES6V$#{69@!W%*$Ef8tte$Nv-8Sv&cEV%qPxcb=ag3kud5dSaE z{T57XT${Z=_>&yDRvAb(Zh*KUWNB+_7?J@cr;1@&Drdjjg>KAGu~n z@cn9!6$SrKj6a9}Cnlc_|4&?M%OBF%vC+nGgRh4lxoLNM=du&#W10V_>G3UFztK9@ zUSjzxk@HgXxA6b8yawyfpaJhcVKrof&sS@H!h>i3n!uLF=3H~E1V7^mb7q3y2b;eU z^_xZ}KDY|HNhHQ{w-{*?c%>&QJV5wNoDx|4&Rlq4_GlJ{bQm-hcc*G1pi8 zKXHm(pYZ?08CDMy|4)oxivOqe)!6>S{}UIQFKE7$PoHngGyk%Mn|;azw*BLrW%UWo zuXD!#v;I4C|7rbsO#R8(NIl={9@F~CC&vF1FEl@d|HSxzw!9S0PaYfff5mex|Hqc^ zJZFuK7n%R3_IWF21^-VxwQeHE*W0HS4GjLD&hKF%2YMPBg#9{9zk-~%pSUmyHG@rsQNR)4rh znxz^~e z9sZy8Pqz6FcKvjoXyfU2eRZB{`9^mAb>{rW|5N|?{s#X~JkRbo@&CjN?EcrzXJ_sY z@&D9bWZ#?M|B1;v!~YZGbKw7pdEU$Y$)CMH{2uS$_@47@^TF`{w0&vz_Zt6CTwu=w z_)H30?j{hev-Mx_OvorIP|EKn9 zyFTOpiOH|V|BEyJpP0WV*^{O_;|r4ir*`V6lm92qv-@H4|HKXU_ZR<9Tx0b($^X;+ zNYU1u;Qxv9H)RI@Pn=``1VzpUxWXr?JctP4Y%ZO1$$|Xf|Ed2q_B{sqf8t8Z^TYoWlQ)k4 z=j*rc8SwwaeD7-4e`o5c;{WOS1s@InPmGU-|EK4*>htw~#hicS|A|ZN{^VQrx25a( ziT#KFCuaZP|HT>qFV6UX&UU@N`RO~nKRo~c?Vn$0;T>5~;pDrV%PhYQ|4;qL55)fy z^SqD$r{&{s;{U}N|4)qXhyNF6{6BHX|1@I zYs-&*)!X@g_>OzO=1hGD{69@!Y`z};pP2WP_MME+l#@&DpX{-3zQd{g{CF}@o9pSW`E!r=djOSj|)|4&@D z)%iPcfeE%&f9~bifbpB;q-XHmY;@sK^!T%HI zS5ApWo%^%5XO}elf4ZKem`^zO*MIZt3rzl>-Y+dM9}xdfoMOHo{-54o7nC&ne|kTS zUx@!FE-0B4{6F!cqGtb3Tv#w6_P6U#@e;kLv&D_0E;%lYIJL8=Ud8 zhPL12jBj##ug%W*SonYP6JY#5apAnQkpHLkm!@O||4&RkRs6p=iY9PWbfrK5xxA>5LDA|EK=L_1i@c+d4 z$M}EZg7n1eQB_)^kIeXL{Cc%GJ+Zw$BQejeHZyT~by6wH#uKxWY0bc{Y&-%lQ}sb@c(d<|Cj6ob|0AN|0Q#>Z-|eG|M&F|UJL$TmjT^_ z|0l-x!~YYL_ecF-al2j}gZ~$2{J*bW`)ct2+V}1h{68`IeboQe^z#42*Ye0+UDXl%KDCHH4&Qhnob9Xlt?-(x_c&)aA4u;_=s zI@{Fr^qax=!w1Cw6O%uR|0f>at80{6oXB0ib=uqU^YH&PJ&gbN%^7b6UvNa{4#EG6 zbA0=#XZ`XokNWuv|Lv6{&iH}&e>#5$n}3M^CmzwQU-19L!@Ks44x7)X^Sf==9#Q?@ z_d2)g*d@B_=susnoB6I!ZQJYIrER@x=do z@8kCe|8LIF;lckC_ZU7q_xl-|HPRki-Z3so|RD){6F!G z%);RRiAT*$3I3lrnwK5?Kj)zng8%0{WNOI&b8go^_P3lp&#P;z6RsbXHAM+r zRGJg~zt@K!4gMc_75)3Z(I_rnYu^W(|0kCJ_t3B-!T-xxlM?-{)hmrJRU8VwAMZQy z|HQTSKC|BwFErj;elYlceE*66CuV#E|4+PdZ&C37#Aydgga0S4+LaUhKXJDCX`edv zeV@O~>g~2IecHLSZd~yH)Sp7D&rAJZamDIc!T%G_-KMEpOsXKl+4{+~E|drt8GH2qquM}+?;Ub(5+{}Yp^hySPj%lj?z|Fr)X zT74z_Kk>X}lY;+u?H`W@|8GkD_~8GEr!JWg^8dv18m0#SFV5uui5cI-{}baA;{S;k z+4$xg9UgKnwfaw&KKp<(^^5WU9{JO;;0G3OP7nT{82|5v=kE1(xYZ3`a_0N=^tbP6 z-1)@u;0G?X@w+d5;cjQfp9XFIqBG-9mrl9M86O1y@5aUx&Gm)t{WkuenD^KCe`4~| z@c+c*hv5H-b1csQ|4&Rl9{!)W(DG2e`I}pu@&EpO_s!1K=f(fi^!R@{*MHjk3*-N3 zd#M*ybnA`2KdP)AFaDqQA3h-dpN>bqy}z!1_*y@o(l^fx{@;724!HlfdDc~pWa8ob z;q&4DiK*v?|0m8hABOxtG2j49Fg{RmvOGFdHPgA~Y;}bHH}{u&g8!F)vMRc;aB}1EetUxNmwT){_3|9j`q&fx!%w}$`cY}Xh3zo}o^5&XZ!=HKD}J<(%( z@c-C9dmioE*fwWd@cm%?Kk?#|6~X_DGyb0#e-HmpTyEQs|7V#l!T&2bQxW_>apBoY ztB=;!+lx+D1piO%F#ex-<>@NwBR=uQYny|=xBNso^%I@T&F8dyCFhFMCHNQ4^k>^s zzkXs=m(9(-o^h*`x1H(#C+>gCndv8ue!Ydw7i{|EE6!y{i-Z5CQh>tn=^TRR-e=vU(nnYXMAA%KlL9U5dTk{YCd%D?^HUcTYX9VKXV3x|A~K$ z{}*TcKQTTZ{-3z)FuvVrUtYnXX8%v?D?FTq|KjcR7ynP~)pow%|B18BN5%gW=UO}d zpLm0vFIErQd9CGVS$$LIqN9s~|EK8-EdLe%&)NQdo6qH(XL&*Re`;T7^$GF+#Ix-F z!}{-xUxojt_H3(1Y0G!U_p|Ap$t&hRO)vjXykM=>gEIe5Jk9c)@&Dp%%S&~(@kjFi z#8Xx>eS`CY+KIvc)A>2IXjt(7#B+-V2menz+w#2a_mL{@RxkkH%ei~uK&zkoTB?4J zW3n%dhM)eu^N95R(Wq~HnEK$(jlmCWmD4x+1piO%+z;dbi6_|oGx>kwiB_-Aj<56d zrBj0cr*^)lvFnHTpZq_&zBtcZHY50d+MXG9zmNYXo@>to_#)U9)a|0kYq-)rFiiSd8%|HR~1 z^_FLi{}*TczZSN3j zf8ui6o-;QMbLReK{@Wv*`QF2>&(8RYpW8jwxz6%b>mMEOOn!CO){~s^7r$9J#d)#i z8SlS#nsdGR_>*3n;aqHg-|_$a?}Od1;s1%Z+TYvW=KqN|+27ai-jw28ZS{?hzLVx$ zYu9`Gd*obZ)8qf?ex}_1UVrLax!#_4#O`;xZY_2$*_9dmKP`{v zKm5Nq|EKL+$?wbjKQZ4s;s1$QAO4>>`KEpNDGdG@@8 z|EKk3+4C6wpSZ?;-}ryxvJEqW|0l-h#s3p?J;MJJ^Zp0_PfUIo{-2oo$@qV9#{Y{m z{-2oVW&A(!9J`(r|MfCIU+3BL_?UiIICFgP|MdIf_~8GE$v4IS6Bk>3W&A&Jh52## zf8rAJpX~bY+_1s&_>bR|uJ=>*=KoXwSI>7GPy9bI$GiXEZ%)_q8uetij=eR3@&D9b zxOHLh|HQ@S)8YR)n;(e(CoVBR5dTk%uZRDq=P&txV*EY)KQX=@{-2on@&ClkU-XT8 zoR?Yt;B9~TlJipY(cd3=pELWrq~?BSmiO6n4N@c%SD z{l))Nd!_we@c+aO#`u4lewE!1R`z(*+xedH3t5jjSqF;*9?%US;nG-+t3ZJ1$i9zV@cy@)$-~3{)Aama@c-hB{}*TcKQaCw{-1d9 zmekZ{-2)zGuJH){+~G8 z>XG38iK%z|^xbbd^S%=QPwmxfW(EH*&iH>~@(J<(wElYAU;nIl+qwFpdC`YE-|_yI zH_VEvZ~v8Zfid}i+F!Zn{XcO*)wtmQiSsMRM(fAF>(i&&_c2c_`Ga%8MKgl`r}KHy z()q#v6KB-Su=ibm@$)^aW?Jz7bp6S$weL~P|I_s<&)V_-#JSZ|ga4=Z)A)toS^QzT z-cK*8m>m2+=klq+{}X3h{a^bpL!47MA?oy*7Ea9`8TFpu%G+nAjEIK3+`@CxN89Wz z*UoA7|HSxD_ z*G;$jLgxR)8UIgQF?~kx|Khy6?3lOX z%gwGo?o1vZ{-37D55)fy;{)OU#Toxkj30#mC$5+`Blv%D#{Uzu{pA0}8UIgQF>^}r z|HPHEriT1K9WQ)E{6Do*FB$(&Ox`2;e`4|-$^R3VTD~LxpO|{q_76XQqX|B3M@@&Ck2Qd5KfCnnDi|4;p| zv--N!|JD8|&u;er#QB!DNdBLg-w*zunEu7DM~jp4?v^FxlP2f?QU5qTe{%g_@($ze zWf_T_?5|PpIX-=IK44v1VtZ|BqCfXh`F|xDiSw6bCHjlYG828p`qV_J@|j(e%*Tn|4&Ri{-2on@&B|w82>NM_F3{l zDfoT;`VNTZmbUQJe$D=$+6T93&i@nR6H@;-&X(Wm+@?cfzFjhR=+GhI{QD?Q_U&3F z<>@7Ja=u&n+?ZH2bUq3n|<^M&=oRk;XzI9^WV9zdzzt^Gt z2P78WW7ufO5;QNvPiT@|Y zXD0tod|{`q(UI((O{eGoz{Y1U$Q;tPV>CN^M*_c_wcU9{r!LVKKfk@H-{v1S{$qTb z%#oeD^8JaQUqd?e;{McmWcU7&-M>0_?$U$%Tj#ds*FCa*chlO*uLR$p?$eOckVi{2lwyJ)El?^duJ=x&HcY~ zA6q~5fA#z9*RD(O|HK12bc-HcpVGAa!!HHj?844HqdTrz=q&&5s-NE*{J>>fPX_-_ zymHsR;Qxth*KZE~pEzgL_Tc}C=hmzW{-1b4&GO*?iAR*wMoVv>)AYns_cgA1=VuuM z@(P3hr}l34JrebQ#jWgl>e|sQ98H-S-M7;6{?2btG;&h(=}Ro{PuzECbnZUO`xD#s zcGoLYTG;Ydulo5EUq1PE_3c}@wOwDy|I_+ur~a?A`Lxvkbv8ea`oH1}?0Wf&cP#Jk z{Q9Y{{=+UU+`Dg&kpHK4e0lQ!#C?Yi3I3nB)2LCw|I_ljj~^fE|B5e|JT27!6}O%= zHTZwxp5vzm|4-a!(v0B$iN{Ty68t}LWd8LpE*t9Gqx?U$kDoj~_qU8Oq90gXnHf!L{gcMuA37ZTvCJhiq8W9sHNO48f#A0lncsKQwjVc6dS`#|`|#7g zJMTvcjQ^+hMe7zs_x$C>#xuX#*PQQX`EB@rV%~4!|B0#Rg8wI`ehc}3;zE1BNdBL= zXtTZlvHHK_%#{;^|0iBpIXw7(;@qVZqn!i3=hIWa_l>uoa;~@US@ZAzjx+UP$^X;# z)Z6=F^8dt)r;-0BUS#ht@&Cl+Z;<~dUS!`7w_VWWyxQKU&A6b^d4;`CBL7eOJKO39 zRnL6fIcv?-=<&xMYrNwAgTc34aM6_Lt}~B1&$aEV?)Yfq?E4M{e{=leQBkYsA90?# zyxITL@ufcS*uQ?&kN12Vzr_DjJNYE|e`3Zb@&Ck=Y<~Pd@r>2Y{-1chz3;~VyW!xG z=K8_*{W$r5V#eq2|HL_#$AteU&f76J+EIUxbE%Dwy*c=9XZ!^GzmnXe!4HJ-|HS0G zz5nMgIP?Ag+ArVXOn%&p2R`r2_*quU=bZ5=?)%T}&g6yQ|NSldSnvs{KYPWwTfM!^ z@(n&HxW$?Ah4o!-b|#Y3vI;lMTff9LD}o@eU${<`7v#!VG_g5O7; z+O-odOJMvzwHMm^ZT!DD{onJ9pNjvd{@|D5|B1;5+c#yIGxbsN|8)GQH#cnU zVsEGZEB>G6hui(W()){_*KldMGx=@!f7*WX+R_IWH9mNDcku11&8NBUk$h+B1OIAq zUIH(8Kij$5{GBU5k?D-z_p>?a&MV9Z{GaYAjh!yu6@0ymtUu2@IN!P6e8QWn=O*y3 z_hvcc1Lod1!+Ghss;Kaesf`tn?hL-)Dw`kwPrUqSK{R~%gvJ~HxFh&}QfA#RjWA)pD-&bk*ZId4!()i?+TSI+c&Y!#A7}VJ5 zn_GhKS8MxYY=;4jRqt&MzTYCtx4UhA-$tv+*6iz@D2m>Fx0f^i-~8KqB=FhVZqDQb zzR9S1{~LSV z#^C?qQ{n%K$pggyi!=V8xZHeE{J(8aZD{uYjPd`(Xa9oW|A|wNWd{FGj6aC~C&mZE|I_lxw{vV|A{lrx4{1s zPc_E>6HmAE75`71V*SVei!=V8nB}!fS>v2-^W*>d@w4s2{}UHk{l4@s6gX$t-^b0D zWH@Kr^2|4LF0*>Y_OZv6!EpLn{BKjQz1r>vS2{6Fy| z%LBy!6EC!U6YBr!e3)K6KKOs)IhNmT`^TrBT{0~Ae`+6DIwbgiakk&DFK=@35c5sn zbsm%355LN}UC{tLpF5;!{x${uZ2di*+nK*tcy>?%55H+t3m05yzsJeWovpvmes7NR zq@vNm|I_lPSl$T!pLk)#1kUd??T_@DDeNETNsA{1|4;3c>n8{QPn>3cp#8pld9dwI z=PC8m`F%Q1wdW!G{W|0O+3!1n?f37D|7X_+XZe5Xzx+Qj_uJ(EiRWH4Gx&evg?4|9 z|0hmcHzW9e;+*sOf8uoWXYl{TS@wMg{+}4X1^-V>-ZTE6nD006|FpljA0_`!jNeE8 zU!3v(#Q1&qe{shD6O(U^{}*TcKQZ&;|EWLtf%t#oOsh{!{+~G8`a}Mo7~c^8PfY$8 z{+}411piN5W6zs*K0EV05dNR~Q*HNq_*{}UJQToC*}ajD&Zlm92? z?+f{V;(WWGrT(wD{Jj4suC(t@@c+bhmQRNN7iauGF@7KZpP0Nq{6A;Ap5y(alPeJw=J{s$tO{qI4=pd(nd5osQ#H3)mf2mYUyUv9oA{-2oh1OG41_q}|J1()R{tCSFV6UX&gS#3dv>qSpS@#Y@c*l2v#KRthu zfA**J&p6|2|U_KlEU!3v(#7vL>C$8L?9sEBr+mHVzCLa#}PfWfa{$HH& z|HSp?!~V}#A538UKeaEn?IZs$&i^d>iZl6o_eDVLp_=Wg?amN1>*Kf}X{$HH&|HQTC&*A^+`J3|r|4)o>hySPP@$vBg#N-p= z|B1;b#QzgBKmMP%+RhK^|B7qv`a%6)F~0Nf4*kH_PhMiy-9L1$w(qxZeEnHx{KP+W zdfpj-H#g-4=ZiMx1piOlvwTB#@c+crhr$07Q}3AkKXIw$7vlfLx&L9y13dpef%+=s z|A{l#F9`mh-Us0Kk^dKG{6BG?-OuCyiK(}O|0gEDll(t1-?QWYiEG!*iAJyac>?4A zsXrBVzmET>{ukT#BKUveiuz{%Py4^v{5tCYit+2n{}bnxPYV8@nEbyd%>NS?+xysF zSNzeL`oiS@>3UIEH$C`&E!^z?>HSi1{fy|DLGPuD3+#Is{6D=vhhM7rAYJdXODiWv zD{B9huJ?`btSdisUQ}WE*-!r4IkRXCk4G7Lf1O=0KKOs)l&lfaHy@5Nw7hBat^Q7V zE9bcxqoa@iu7#8R7WmSyuFBB(A3jig{1vADuiEjm7B{TP(D*if)S$I%TX_D==&fz* z68QE5>z(n7@c*6Q_gwwr-%B#nx6c>pPf6M(EitsXPl`AY~L?9uC=_56(cY9_N6)b(XKDFF!^<7CSKz09KVm>m&kX{ywuwlnUC6Z)n&f@_=C6g zy4)FG^7M@@Tw~`O{-3tLEMdU|KK+u+ ztOQQ>|C0It*KaG#Nc7?AlYF_Fh5vv4U-J5sIoZcsl9uS#eU$%~yuJ9D@%@$T|1Hf( z^a+!F$z)E>^Go*miqaDO@?=iVD@@KyOs>b9%=kL-?HM*;U;=mT-{-$_w?RD<+LM|5 zzWDMx_fPbP$nT4{-xYVY2uUGV?J)HBBa6XSoz&!1%O*s)_`yX7awr|0;_ne!pe-Mc5A zzvS1&+gtVMlE6`00`^+2znzov{5mD&?Iq^}CUbILVQ1U_@#RyWHqLFjb&lTYvZHCr zZI9b{*?Sr6uUCg`ckb4)ZS;ew+nhPy8#A^#lRx=j#TMs|0}`(fy+({mSl^H#L!y80 zIM4F2EW=Y2o;e-pa*4*s8bWQQ&h{-1bi+fKp%yKMb4!T*Eb{_M6U zaqmt&qJu-XH`U+wgT}xAyG>>v^W%E%+SPQ$*5||h8~J~K*tpX0}gL5Bz!;I9X*+usR-;e7T{+}5C82?W^eeCq;nlCSKKDocy{~JB!OTh=+bN1@s z|B1I9zcl!N;vFY04*s8b_vy=m|0mvY^0MIniFcm5Jotb8dfXfQzhkE^3;v(lkDk0V z_K6vzO@c+d74xI}ApO&|C-;v<|i8pQE z8~i`<(sdhy|0k}wXjSn4#B~izga0Qkt*i?EpVrrqnH&5+ah=^?lmF*DVRG>Q#1*5) z2LDeycJzec|7rQXdh`wcpE&B)H~4?fZ8``4&$)HG;Qu*CZG!*jZ0AeAwZnY>;;Z8S zseNXL?jiqAye=g>;rfu5mzTg56%`4bUzg|yW|k*DFIO%$U+#0SHl9ATH~4YPh7e+Gs+nIa%01>J;C?m{UiRLxYFJ~;{S>B&5y(X6Bn2-g#Ra|o(}$>IICu4 z@c+aU>qi9tPdsh;*x>((iRr@c+bh7mW%2pLp?#vBCdK&Dj@x%L1!6jQ z1vXxU|0l-Z!2c7IhlKwpCSR%O=XW{hpU?jr_spT-1LAMt|A~vuAHe?;<6GhXiSe=U z|HMp>|0gckn;i}Q)@{z5-}rxOhw=Z!CH6iP|4+>L2L4|QFAV;lxXgYJ_8~KQiy||Hwxq|4&?Fz7_r- zPF(I4pUEgbS|0pAamlfYkpCxMv@bvSf8s2A|BwGC4)y2E{}apq6EmKR|0kyYGX9^q z$i~y~|I|PHMEpN7{m1`{Gyb0#f0%ElwLF-2rDE#$@^5ju`A7JF;!AFe*7`~KXH}S-^BkD7aT7M{$HH&|HSxp&wOu*GyWU?pW0WQsfivc zt?~7*JY8+?-zyv2j@}u3zAE#>ZhXDWxy<~#-yJG(uCqL~4ta%*KN+_p_<1!}PxJL( zEpo=^x%bjs=bYnt(W!~q&g8vS{~*J;%JS+yJ~g#*;|<$_f4AQ9=GMQwz+a#jg1_p4!^EWZP`=)t=Z{v_ANL^;>5I|4&@Ec^dx26JI;I zF8F*ETc+VxIG1lGAL|c3|2%8Q|I_p-J7xv{Ph4wxPxyc0O7rpY|HSyc_S|4cRC%lhX$c_qKE250KS;{R#-$xEjO|4&Sw9rb_3j;{|Gd3oG{0YOpISO1_RdH+w-li!E`CoZ!7;Qz%L|4&T+@c+~w82?XNVP)8YS#>nwlUd}`;FwtW0Q z-Op^W`&s-yafAK6CjT$a_P_c%T1Dku| z%=0AvpVkkP|0m{r!2gRg{+}4X5&uuj_nY{CV!oHd{}c24h5sjJ`Q-nJ`CbnHPmCXi z|0k|9{}BIAO#VFif8tWh=d*lPKi*uQ@c(pv!uWsU#kN1l|BEyJpSa%MU*P|VnI8X7 zT)jIt_;i$j1TtL^`CPt=l#|vKkrPw9sZv$-}3G7 z|HLbd@&Cl++u{F-i!FZ-|4+>GKKXxQ{5JeQaoy&W;Qu+>{TBXTobms}9Dn@3IOG3` z@%ixo;*9?%rXDZ;pP2U}_|BEyJpP1?K|HS$By$AlExWK*#!T%HE zi~Yy)|HS3?z7hXVO#NEw|BACVEDZI3#T8Z`8vjp>kB9#!rhYO0pSZ-{KjQz1@k4*} zoA3GgRBrxY`oQlySK9sS#|xivuCl++_*KN!S{-3yd zU3&2U#MC3k{}WTM82?XPX5YWy|HT>qPwxwu9{(@S z-#Qmpj1B&uj%T6W50n2VE+`uj{6BG3{iNXki8Jb_1^-X)i}=2U{68`EhM)cIUlSPr zPwxw}EiW7YPw&ICY<~Pdy{|5=nil*&y>Be4oErQ;adu_1|0hl@9uvL!!GF@lIfbL5 z`TIj`B?aW zV*C*NKQTTR{-2oqDEvPykNNTc#OW#X7$5ZMGtGao@k3|k$N$sxF#eyIyfqu2^yw=W z+WQLg|FnMm6a2q8(`GvlkeB%?Gw)Q z|C9SpI^*Zy|7m?3Py9b|f%$^ZwmR*M&xHS{cKkj3KQaBq{}a<+{68`IX%o!<6W3XP z@&Cl-=~iFF{6BF`&Z6M|iI?Rq3jUvXNp?=~|HR~@;s1%rH^cuE<2&L1X@4)t$qxRX zxXk=R{J%Kk|B3Oh@c*?N82cthMV)eE#G-zT~{VvHkidOrOljzEd)j&lg``kG_fiRPy?I^h%tb z{G<5%?K`#!^?$eB_EPZs@YgnO{cMvMpNsrIG5LDG<_?p7fStKan$aD;Qwj;zeAqvc28|B1<~!~fIr+S>Nx|A||7Y9IA}|C2ub1y=8r{6Edl{viKPOnu-E z$3Ncm(rwQL->yTawp<^a+q7$iKkVC2zTDQ|+~ABKi2tYMwK9K*`oH3KmX}8UpZeFz z`a}MoII{lY|7m)BKkEN#e@7i!2mjCe*QRx-|10j=v3>CW#KSst3jUvXsMR~h{}Xe( zt-iZ6{!;vWO7{Pfnd$#<`_ZO{Uw*7{@+JSsAfNH%gGZc`&+lIS6MaDHMaS1?yE}o~ zC;5NLoSZk9%paBi$N3sxKih-<*ZW(K2LG?O<(c9CiTiZz7W_Xkz90UdxJQp3!T%GF z7<6Iu`Bj^}ef)@#3F{j^^1|T%9a;LL;QztY{}oRh+FbuvJl666@&Cm5$M}EZF++z1 z|4%$>%+TQfiN}r~5&SW(L|At#VT>L-rg?4`7|6O_K_k;g8s8i?YlZUo9jehBw#%sRSHk0%3;l10O+5gY( z*y_yn>#3h_ZTfQmADVC1E|dDrrz*BJ^n`SM}%|1|y46ITTPPkiF^)uH~c_~@ytg8!%fA31qt@c+d7PF@oH zKk)(c6PJHD*|+!TnahL!r{x_!b!qVb#0Sl9B>zvm@93G}|B3e=I34^y@t*ysg8!%W zt=hOf_Tcz|A~2DhyN#DW_}(1pSW)0!r=dji_GW4{}V4-((M0< z$5##y{-1dEa;xY2+S82(N_IBaJ6$#_%J{{ueN#>_OM7ll@c(iwF9iQD&iH@7`QF~(|ItqVpBTRn|4*E9k$s z*%$mj82?Y4Y4woF{}UJ4{=)wglh1+wCoVHT1^-W6WO;7*e`4yJ{&LBE&cz2ZqHBlU z>r8z?{J-MM_Xj_a{2}~5ajDg>!v7QFSKW8IXc|{}68@^w)<#FKuiK}dUjr>1xxs8vK|L1J^8RY+o8PCQ46I1Vr{J%Jp z|0kxt6aJsL+QxJ6|HSxy_twpWGJwKI*&v`KD^;6{jkL|EG5H^=_#yZTwrSt-+_Ov--6678f-x zShywldH98ow{1*RD{Ux6e|4&?R^=irg z6E8L25dY7&$M!G&pKp&{KYse;81E0)BmBR?4{i+pU#8`qWc+1lA|B3PW@&Ckg%(ue-6Q|hzc#3-=aOMgI~z?9sf^^e~kYp z9Ia&C=S+T*_2)6Q!}xz%AN781dT*y5F#lin3ydLHMC^9=hQ#LhowzW*?v)pE;s2?9Vcq25|B2IWd=mdJ&iH>~d_4Pi0^|Rwo&AIVCr-EVQ~W=%{J%Kk|HT>q zFV6UX;%RpOP5z&l{^0+KCoY>3>i>!-Ef2n?w@+Czj_XsJj`!@9Q@MUQ&tKJ?|EKvg zZM+`;PfQ*d{-2oN2mYTp-SV>V|HPT*$Kn5p^UUwY{}c23v;0k^c01pkSs(tNmJj3qiRJ%k|H%Inljno~C+7aRZt(@qC3e5s z^`^GYHTHb~{-2g#WqIHgpXuaWxj)159=kYKTOQxzg(eF zi5J`b7XDwH?f2r#BmeY2PY-rpWj-AKpQc}ZuqgO{;+6KiV!tn+zRG;RSAI6ex!Uqk zuNXVtxze7WvbIii#;3yn)AH~o?|px&x0l)T!s@gc&J~u2jsK_VVf;U5`+HyfzF%O#MSn_3I3nB&YpM3{}b1kpNIb^=Kdc4PfY$X`G4X%^EvVV#5`Z(|B3N0 z@&Ck&ZF%-@=UQWP+Y;Ea>YOVrpOO4O&0lWM$M}C@z8}H=6PMfhivK6(c;Wwv%kBF% z{6F#H^Z9>b{5$+VG4+-4|KeC8|4+x8^Bey!&iH>~d`tYlIOG3`SMJFU{$HH&|HMmn zX9xdJywrS4yZ-y{1Ah+xPuCOb#p3^o$)Cgj)AL%TU9a%}#Kmi-M^6vFC4uq(^t?$s z{-3zQe6VNkz1^oLFK*;ppLMRY_i^}tnx5|mpH08R+n3n&d-RSkIP?DN@U3?`^ZxGn z=k9W*-ZK85mdEov{-2olANYS_^5Mw;6E89U@x(Xp^X0)m`pf;!{5`?{)AXDVXR03Z zcKY+`>4y^-|4-9X-xvQ+T)$~v@c+d0AOBBG|MCCC_<%q8{G-17YWw>!`<2I>sjqN( z+b5i}HdzkbO?EVn{Ps>kPKR@LE>3FAG{ay0^#2i2TKTTg@ekcB) znD0&T|HNfh-}$;nzU%X|Kk@&xJnEa^|B3M#@&CkZFaDpH_fsV={viGSr?-ah0}HG_ zYg#?)jNf=@`g6`TmPdHaiszkK|D9LA;9O(d+xWzb&iHXJz59}LsritUJzJLkfZ@s>~Z zd*_9vgM@joRn{-54IRoeYD{$HH&|Mb3)yuX!Y|8UN??``fa z|DSZdA1^lk;>G_=*ZXUj{6D>~&MTi7^8dscg`h*M(7rmY0<~ zHG1KfEu8HCkKq4l zdVCQ4KQaE7<$E~G|I>K;Li0iJ|1^D?`BC_PVy4Ic)ATU@pBSG6|4-Ay_%p!oT;yT?6SSi_;I&iyU)3P?!4$bpW5$SH+xR> z+uIK~k9{j&J;qPh4mFe^iI-eg4I^ z|L0uU!nEW6#ix(^Ahnr^eq1sq=hr3Y_Th^?N^R`pUG#yu@Tq&Nn0P zE55zSj1TnR+LNazUo1X-G7qqPt9W}qs~;HW8J|I`lS|A{$1bKA5q{>|r)eahS0bnX=V zKTY4ZOXq0Txf{K|w7)y$hNgQuJrn#Q_@2A3cb5NGbkz@o4@f>3{-3rNKN0^=jGt)r z$DQ$uHr#b%)1z}=4t^IrZ&(X+yf%F0dhajC6aP>BwK%EZ|7rObSpFRKf7PFM{d))h zPuzX@;Nbs>7xeEJ{6F#JPR;(GxL4PX!T%Gpe}6yiDqlW%cUB)hftOr&tm%!veLeVo zwB!GYSswnM7{9OgHxDQ9UC$qK?$R^SziS%;{#x??$a9RJ@5!9(`z15`H$Ff9SDZQj z;>`Jn|M$V$j|BgZJVX3HF?ojM|A~9`>J|LIIFtV;?%&_)kDC7{9%c1LKe>C8^MzwZ z1^-Xy$Dq+8ga0QUKWa$G{}YcHJ}CHqVthjUKk>Bj6N3LIo-koT@c+c)#*GX9pBNwT z?dp?F55Dd-#Qeq)O>$8%Z1)~0_I|DZWf(EL68KXKHdZSeo%jQ=NQe*C{Uat9S7K#0w@j`+wro`wj>Hujbo#1^;jRv5SNMC*FAAWbpsQ zI}RNU{-1c~;bX!76K}P=z13IEX%cTcd^(!?@NDPfhfW9oPwmGJo(le-c<+HT!T*c% z@}e0&|F%PCga4=gZ$Er4_ee|0_On^y1+E zi4Pq+7xMqK{fBLR_=%PSxy$@Y{6F!|<7b2aC&ovd^v#h?3r^kLSk&bg8C!Q8 zj=uKG5zagJoQQHewD6w&r=wPVMl`KGcu(U8)o*9)J#;SN`g7{y>k|0Nb5|trB_}UV z;0?Q1Ch(%ljOfMOR~t*-*%th{(p6KU)Sf?fuC+Wd{J-}1Y!5zQ#fJ3Y|A`xR6$JlJ z{QoFB4=Agu^KT#Q(m}z3O7DGWGfanpVR|q0J~R=KDj*1UO%%Jv5;Yo)MzKdD-bw7e zB$~t+Q#4UyiHXLvJvF;#qs2b5FZx&fWVtzjx`X{NVqI8?8P8 z{-3kuYvBKh8!WGb{6BG3!_eUWi7V@eg#15omDT5>{;znp)sMjc)Alodga0Qkwfe*4 z|EWLYU-*A<#{Y{m{$HH&|HO#$x#a(8`^hW9|I_y3D^UMe%=~HQuFL%V7Tfyq z|8zYSuNWEqXz4|%{(m|-_6$?Ulx2m_$Mb8Ia8mr-?N1Y#{W}) z=11}W#LSQ4|B3N;7p}{6uCn<`{6Bp@K3DEJxUp|%L+l&8r=c+LY-rjALbE)MI zo-uH^FHip4p5uo2=ha%?Sl5XIQ>*5-1mCa9e9h1D`lhlvE=e6c{Hpw1JD>P};(WV4 z@c+cq%m>8(JAL}%;Qtlc{SE(5On&7{4;`JdIo#muO}9LS<5qWf=I_hW{#_G%&zqf` z%dCFkKQHd!On!vbOHCd2=)&OlW!m4{N6$ITIosx|EWapK_QitW_u=nZeZvIf|EZlk zTKqpT`A+zMVtm7I9{K0T_KaQ-d^xz!?vI?AU%mgU_nhl3e`osocbqG?mqjNHdHb<9 zR?H7RU$tHDdvE!LbIG>ysIc$r3C90Z|6=n)@&ClrY`!1=Ph4&JefWRka=TyS|A|Xi zWkmRY;_Ny7qulc!aITx(H+uQddz{PbkB=7YzSFsfiE|eX5B{Gx z)80qG{}Yd$*FX4w;xTjk1^-W6x_D6V|HM_xhX?;pJZ;6`;Qz&${6BH&$)kh+C$3nN z5&S=KiRCex+v5FeHfIO_Pwm{l@&9zbxgX;HiK*xNn@M@TJbpd?pO(kZ#Qzf)na_g% z7iauGG5zuX#N_kh|B1`D6_d}kPt51r_2$g>oxJ2tXRb%{k@jhOVf;URKc<*3VEK05 zo^A8H_NS?TK*sYpN=2(f${&uLoFW;|4&T*9R8np zWb-imSm&XQL&)279#l7w9_a9>Ok#_w#XEhAt`gG1Sf9~Pw#m+q6Ue-|UTr@lQk

I_lA8xoT=Aq z{;V^8p82&2w&R&#^8d8G^tb%ZM7#OD&iH+H{GIuH{68%ZqC#JqG{-0R>U!3v(#N>V9|HT>qPt5Zq{-2oV&429qt8Xv$P|5$(@xcG< z|D%8A>hA&hSGCH|jyradp>|A~2C z#{Uyn+50W{f8uJ(*T(-7SK9k0w@;{W=J|8p=~d3W|6=vTo#p@O`A+_yxW={*|4+>O zJ@|j(T6_Nh|4&SQAO4@1d_?=V^CCN*=F&Mgng5CZr~WYhpP2V&@c+a-zvKUj7uoX@ z{-2oqZTvqm`I7j5amN1>x7hZR|0iB*{wV&RnCHPWk2&3sSKXHBmOs5S!T5hV{;wt;SjsGXE**qiof8x5+N`wC=p1rj)_Z)B5I`&xijfCckz>zk8i0ugeMkpW4Y!#QzgFm_Ik_{s)|?XM6U$4?5S` zc+6Wz{lK}%o){7=RNI=ulvjQp3c+wz+!v9`Y%16b)Ikj z-x1TEb0(j$_lD=4sXsj7J1;onAD%n##XOBCRJBaB_X%HeW_*x1xzv^6L*Vk7ae&U?BU~JTF@=u-f?fsS^%U^e{xA&3ruYAL~alwSB@yVY#H`x2! zt3Ug>bK{aW|4-XnxilyEe{shD6Ei;C;m>d7X?z6kd*a*91y=7QtMu2-d5bfn>dn7# z=KY)HxBS*Qb4gZ&|EKkrFS6&Q)_0vt7i2{%Kl#1$?AoDG-ml;DAozbe|FxF) zhyN$8Dzp3z^Z&#-mA!-ir|YR?_K4vBiRJ%^3ucY9@vcAn_19?ie)0b_epY9`-+&YT z>P+4r{-4Ir^XrEP|4-xJ1y-+k%31%&6X(^8h)&=4b)Lo_<^O%OY;Aa-eM=;QxuUi-$*#?ri7nQ>SDm<}aodCH)e7kvra-pRf71O7qWN z{?h{ID)ZCu|I|)@{68`NNA}@M5{&<+`R?hHbAtaTF0%YQtN-Qg<1DWa|4;4X&40oF z6H~9)>Wev(A7}N)oY@}yKlLZi4*xICC|A}+Vr^Ejfvwr+PG5!|yf8$L4U!3v(bbgipC&mw?{;wDx zlKj6o|9Q#5u;>u9=<}{6BG3QBLsx#PrAi6LbB3yzP<%AoEKk@4lzIX!&4?U z$J^66{dlD__n-LkeBa}YuNCKXpQv4$KXj1g*Tws%`$ptT#oO^y5^VW+aX!L)y#K}r znQsv%282mo!*B)LSWAm}_ z|I~hvZ7%hHwfrH69u)Hb#N^xI|B0!uivK6>)#-@f|A~*cdbId|V)EDU|HS04;s1&8 zhw%Tzf6ABg`a#=j*0@4Y3j1YZ-z|I_wz{EKeC)cH{J zq52kF;_D|*lKQ{;Jbbeo#vkAbosW)wb@#>IKJu`RQLmu~nEJrv|2=Wq3&C$>fARms zT>togVy929^|y!qAoz3mf9q>cOECVQ`lsg&vj6exxr<#- z=EwWz!{*OBbG=X6n&i7KI^T~c+n0NIl3(0;p0`uKb@rF%I&=Mexb^^Z{rzX#8sA>> zGB3OElmrjFcD3`d-MWYTKkff9UAqPUPfQ*l{-1cjfC15kXD)XhIB;O_|8#wf?>iv) zf8q)KY<%DH|HSxs12^t&UGwOx!QUG@Y`Eo-?Q$MAY*_IB)PKm3A<_6>o#E{x1`Z1T zpOzmvXmIfV#Q1>|ZeQE_``J$gzi;r+e$krmu5lhSsBiH9)IPlL3BmspkG8x}{6Fzf zyPe|yeR0jx!T;-Nz90UdxQ88o{J)D^p9%gS-yi%xeIH@`KQZ@H{6Br4@jvnZ;!OTu zobms}T;KSAVy+kbKXDiPzL5VX?si1y;Qu``?z_SN!{;XdPmB*r{-3yTq~$4D{-5|< z^TAqP&1(Iq%Wc8`+hl$m`G4Z|`~5%hnk{Yle{mkRd4jKRnfZJ@ZW!;p+X z|1Zw?e`2-=|4+>J;{S=)Z`~FAzc|11hr!-{%C@tD|EKnK<^xjySG@J~^Mn5KQ7-eFKXHHW~$$gRl)Zw zuFDPnpSX0vxZwYZE6o?f|NC{}$-)1twD%jy|BEyEf8x4DIl=!Em(3a<{68`87vlek zOPj_7|4%&5nEXHScpI;H;=>o6CoM7`&HO*LXSdjRs`-D~-l^tK;QxuInQw&ur~ZuB z;s3=M|4&RF1^%CShK={(|B1)nPn^ygu^(KK;`v!3WG+I5GHt;=;vk{-1cN%}0~} zckR1tg8zrVIcx4i&J{L(hX2=i+uGm*^8PaZpP0N1{6De$KQZ|__G1!=)ce8z z6O+e={}<=HKiuhDZvMhYcifTStJi+d89!{=#M_ ze9PBgYV|UgZoS62#^x8h7hLU(?|}cO?N$DtxWUc`{-4forM+MNyODeRdM~i~%@6+c z%@ocWeqX80PhR%eH=K*@__Z8!VJbRkMVMbGvHX)R@1O5nY{%!3ht6}JX6JA5Ip;bT z+W2#)#&eu=?fU+~z_Xq4l@@$)rZfIu`=@q0<6}H<`7USXNAdr(z4)C^=I(T^wfVwh z-`eiX{M+g+Tb-GIY(IUouaEl8bN{fxxy14=@c*>_EXy;&{}bm}z6<`J7=MPbQ!zdp z{}z{-e~14kuCRJz_;*9?%uHNteiSZBb?KRQc@%y5u$2r&U zwEDek$2yZ&c;oS-of~Yvckk&Vef!BHELbzl+e@sT@t~E1QiZ!0rFz_bResU>%xL}b z1DvOCw0cteD{NVR-e;C-agERLB{6Do*Z}bmc4@+IScV6)QVEjMv zD63bC|0m8c-vIwlJl5vR%#V2N&5z~=zi+(lulW*T)BX&${0Hj)iYKqg3I3mWf<6D- zw&5CIU#9t3S%10Qd7Sx0&#&I&JfOLMH0Q$$od?bwV1CKD&PO+#80~y_xAXC{`{Q%@ z=V#0r8vH+fex~IIlm90ky132%6OXp}V)FmQnfCX^{HO$*KXri3pTz%D|LjvH1piMw z?v%;F{}Ycl{~Z6%+47W{6BHo_Nl@D6IYr)jsGXEu=_9mpBVod z|4-L5Z24x+iJrKXY&2{PyL5meLic?7LTy`Q(NAdd_ep^wX?kWb2-|7^8U<+bDn5< zarl2~A7}a2_5e#6xTQa()tw|EG5O ze`5K6;(=DL*RGFTF@B$2Kh9%pd+`6%o?+XI|L5E^BKUve@%FwD{-2onP5eJG`)kL? z8UGRgPwk`aeHr{eG5LP@e`5ST{6Fzn%ip$q&IIHCsh#?~_m>&g6R=RETz@c-05 z&;Fj_|A`Ci`)xj`GkJSfpFP3&f7*W9@&ClUAA$epZ11m-{}*TcKQYhO_$+!I|fSqegU2uzi2?;@ek0_9*8{dwy=ev4?ZD`5^dz+TWUW1;PIl zlc$dV7iauGG5+C7^Z&%vcK^ly6Z88D|4&?MzFF$h!T$O9X&Zkw)S3GB_G_8DvGD)I_*(dX;u?D%!2c81 z+xsZ^f8uh>3&#HwSK0Fj{-2oVWBfmH^VT;1Pt5k<|B2aN{68`Elb`KapJ4L;^gO5f zzhe9}{68_r2men@KA`>Enfya@>71#DjQ^+pi;eOB;*9?%#`nYj6F2TC3;v&Yo;_dT z|HT>qPuygA@A!Y>=F_J~OA0pm{w}cNd)#?j68zFDTb-LN&l3Mn#|y^)6O&(v{}*Tc zKk?j6(}VvfCO;4VPt5Tr|4%&2d`0sA#9W``|B0z@ZTYNzy|Mhp)6RFM9ske!TV5vq zpSaQLGvoh>TWou%|0`Z>^?=F$6Z3t=|BEyJpO}2TKHV;JCSUKX@s~R{n_rFpr~WYh zpBTSw&cLhv{4|=sh5x7D>-bvuf8sj3pW*+B$sZ&CPh7EJV(|aOW%fQO{$HH&|HRZ+ z#s3qtKJx#>_*M9S;;NS1;Qxu)KKws1^?&jI#0$+&!~YY{v;D>Y6PKDli2o<9u=)t( z|A`kGbG_sLiTOU@|B0t8$_oCUxX9MO^R?f3d&T@o(Ut#x$GLo-jSmmEdcga~ zXX<8JeU)DC`Sz99j)>|zec#OR>QKKAROc9!MoJ@JY2 z^qHeW{-3Tl82?X9{@>BPKXWd(ylwoy&F8NS?+a(w3=96B#?NzV+x$O`cT?XN|4&?4 zJuLWt8m}&^8XDDn_Rl+QuOqANaZ z=ly3CPDspWluSwHG1cWvjLte|UcTo0sL-Y!T%F0 z|4&>!Zd~yH#8WdS1piM=9w7do^Y}LZPh6H|;|b>fiODC!{}bao;{S=+Ui`l}~jwk+~nBzTv%9(yWasAx%)B)!Fy*uM9Z-?>!v^|KQY%c{+~E^+?bI6r{jSii2o<%`Xc{N{n=mqKQTTf{-64%*QdoNjnB8Hb9(=D zKaTrXeED=v_x+R`9{G6j^+$&$eZ6#l@PGM#)XR;p z4?i!?_*!vJum4M49sb{Oe|;hNe?6&RYyMxH@&Cl+wOug#+pWcqJRf{N82?XvSl3R$ z|BEyJpBUc@|4-|~M;mqD_0IS(_FSX?zn!iW=Uok!p^?%i$}t{-61EtBy_btjjMy&~E=p9=a$24XzFuc*w|v!B@nKy%2mep~`(sr?|BG|W;w_2xSsOMxAJ*Yu{{9^}{&qg?@1rx{C-di>@p1A0wEvu6 z{J;45$Nv-Kf8zg%`F`O4#reAG^IAuK>*e6n;iuyNY5z{>d}Q$d#9W{Fe{m-NPy356 zNdBJ~e--~v-22$$q784Z@a4(dJK~SaoeL~4@Y*kzIp_559sECCKlI1{)Ar)?;s1%r z`#Wn%lJWo4K4S2Y;Qz&${6Fz<^8xYynwp;o{vVA0C+A{a^7>c00rW6O(U>|0h1q?w`|-UgeA*jsK_bUu4%W{+}5C8vjqzvm$?^j6|HQ11 z{6Fyq^A+*`#I)o8iD}3G6Q62K{-1d5rkx@GPrP)~8NvS(FWa&^_^B(j4 z4)Ctv|LORX=ZF6%W_|d7;^lU}?)$87jCV&nk3GQnnD~F!w7Wg{e=Ps}6a8Ah@z(9B zceegMf91BbEq}MK^K#?(-}BXHT#(>ZXPp)Oc;z#CeNH1piMw#e5?CzXyJ?BKUt5HXefiCoY|DdGVWmno@uKv=65I#5rgF z_^7VSYtH%0tiI=4uQ(ShFN}uX{<8DLb*0f|8(wmrbZS}j?}8Vd3)dA#D?7cA;1iE{ zF7?uYIvx5I8=KX5?KkrJ zgU*cq;s4#6aZ2z3>+St+{68^1AoYL6Rpy)E|A`kd{%QW7c&WYLjQ=N=|0l*j!T%Fi zoLUh4KQZ(D_{68`EckutjwKktRZ^;?XoZl|XcQ{k8YSH1_ zovHu)(05NuF#ey`hYyJVCvLL(U^f5dJjvz@4;`@9d92O<;s5FQ)NLsY{-2onF~&~C zrRMYT?>OWCiODA+|4&RlNk_~76XWyUe9~P1eCG4;|Fpf$mWS5(WMgXOCrg6wNBvy< zKk;0f-^`pxH3GoG7~dUErk{k~sulzMJj z>d1!{hI~Bgmv-7T)fqpL{6FmC#N_?q|B0#J zhW{s?WBmGAqkMa2S^xfHM>tP6fAJTO3`t#_u^{+e_pffq*PDy>;8P(mH89Q|Hc0kPqq6E`G4X(^NV&z$E0jdH~4L+^=h=KX z{-3ze@=Wmm#6@;};QxuIZm$gfU;o=@2mf!{j_Tn5iL1;9#s3pmSiL&@KQZn2f8yFR zs-kb)`Mbwj-kTMCzm^>}!T%F4Jgq$Vf8y!p1LFUQi>a??{-1cFec$l^#Qm0x4*s9G zV!`0x|A~v5P73~?c;LLD!T%EvT{JTIe`4|(@c+bFHs3@3pLpzY^FjapUFUH&zk24j zo1Js*?`e-OuTL=kpOz=@1piN5YGKfwPJQ|}Z1FV6UXV(Ne5|HYa7KXH-$JtzN9j4zJ=Cni4@ z|4%&4u2=H^oGs4@|4%&K`~dR*#Fgeh;Qxv7Q}F-9^8a)_%l{Koza9TiJj4E8;{S;Y zt$sKDpE%F*WbpsQ)JMht6Hm7M68t}LhUEj||B1&g9nJck$1e)~6KoIIk+z?FK06-S z;?XvLiT|hdaedXhf6n{;zc}OniAPvoIR2lQ{5|}?I9sjpTtZm-_87KXY!Ts|MYp2?0FvlPfUGn{J%I~*6^w`zkmMo ztJj_R{bS!>XPy_|{OE1x0;}I?{yGrFLC$Sw4B5^Y86{-65ueiQzm znD?9T|D4VL!2gT$^Q*fi82?Y(PaY!vpBR7e#}6Ol%>LT_)S2H$qY6$)F#ezJ7v(x9W4_?&^^MNuwm%uyH9PaZ z5&oZ^_t-xBw=>7bTs!A_^C|KF)So;)t0n8}YuRdfcBL)OD^9Nr`G4wPWAFRm|HXMv z-__oq-xt$Xta0Xe|Kpx@&OD#r{pI=u_&pT{ks)VD}Haf0g-&FWmdE^DOiK-udk#&a+g9QUz}1gD7xUm zFP#g^2Sz`8_^Ui04=)=K{6CFfmstOSL;js7o?1CL_apVgiSe!Q|1@8RKZ5@!#*e}O(|j>L4E~=u z4;s3=M|1ZwFs#p8=P%rb==2M)T&6jy@!5U|Lv`?0= zO)&nS_6L6r|4&T4U-JLNMHAZc|HShD#Bhe{rV%ubA~w|2NL~f8zQH zZT_FQZoK)<=KqQD1@ZsH3XWS%#SD=H5DpW5aBiRJ%^@y+o6#DzJz!T%Fa$;}J?pBSGF z|4&?Pd6@WrVtg_Dzc}On#ToxE&iH?E#{UzO2Z#SB=KGHSC#F6t{-2ohL;jz>Uoifk znB%?p(c9=Fwl?#@i=lBtL)hgyiykf8+hrneTtRJ)I{^ z%1E?N%1VAd_wU5=X`GpM{L>k~DZcz+|D*mc`El|7_;_(n_w~rfi?<)t@yG<@M?9`Z`*@Py9de(H*)4|4-br(@`P+Pu$D$`>6jLXZ$}g`EdAuV)EJW|HSxx z_u#UdbKfP-Cz+o#YRR6~x!-s^_|OrGAe3l1>(f#vsI?8~!1Z;n2|_+nS> zxw!SBcb^QtVaKD7As^MZr^8V_ga7wn?K8pu>)EYC@c+c*?VURH;#M*BeD|a-a>gg! zn{|N6QzQRR{SPvImHa<(WC4%l|A`N>ygdBB>Y4|F4~V~r|0h1?$PS_Yuefj5qeA}Q z_e<^%J|K+$C+2#_{}Z!)_+`ffo|9nm|FnOHb?O-WKk?z6J4KJ&ak97f=-ef$_~9yNKL2;mt#t0u zv3v0Uw0!^L`vm__JmRE2!T%GF?A>MiOIjj|I_yY#{Uy@zVZKbJ@9?T|BEyJpP2sme{shD z6XTbX|0m{tPX3>m`@{S$OPvqv+$}nIeokwz+rATgzJ9|-2LG?+m79YfSY22f{6F!T z8_o{?pZep^;s1$G-FQau|I{BJ4gXKPVe{_b|B3O-$o~_s*m_ok|0h1x>igpViShaH z|HRuiofZ5)@z#xP`F~>S1C#$J-e}9?|A}eG|BEyJpLo-zw)($u#{YA+{lWheZ?@xs z|0ibq@&DpX{-5|{>;F>6B$NNAc8)LpU!3v(oXtPnc6)zk{6qXdoez9I{J%Kk|HT>q zFV3ZTeVp+HM@{V0`r3|LLOvkp=gnEYotJGpGx7I*wdD;qEdNdFi<4FaKWyDuyMq5W zY5wxy|4nJAjXo**RZ2W$PHr@4gByH!5=JJFgo~u;$fCog8wHbPX+%^Jbgu8@c+c+Yl?#ZC$6#i3;aKEwfS7n zo%}+o?~j%SzpvElHLjohyfgE|_TTlxi8=n{|HT>qFV6UXV$Ki#pSaZK zd+`6n^8dut&&2-|7u)zg{-2oo$oPNaf|jh{|B3NM@c+aUYTmw6Nmgc z^Z&&7c=&%}>fPf1>3CIJ{ssAe;u`bI@c+c*k1%#Bt~B3?b!mP0b6@>tVS+1m&QCD@ zU%dZWeP*U|E?E?OKm52WJ2$3wzP7L}&(HEbmOW7CO#R=f&sU|6?zbTLe9e|WcBzSy!5BUNpbW?=$}1y5iI|H_uBA9(#2@+xKPfY0l&iPJeldGwpNw75egxR&V#t zm-C#-vw;j)S|_6g724O^M&|- z;>q@X!2c6d-w^*V&iH>e#~b{=VfOvU{}T_l{0jU(@x+yRmKV|`_1?R)g6{_(_D;u? zIY`0x%P}7r|4&@Ve7^aA;%PP?ivK4rwey4jC&sVC{}azJAJY7)$IO8Vz8_5fpSa|V zvf%%TtIsG2{-3yN=ZxV0IotL1)u{I#+j~oM@crcfi5Ko}3jUwCX-ixEUorVT_i1KQVqN{-2oqQ~WHKhi#s3qt{q}EX?zi}VYN!4){-3k?efWQI&OLv;e_rXPBJ+)gJCmP!=C*#$ zxf`ch9^!G%g{PI+{&#gQGrz%n8s}2GKbSwZPy5UDfd8k@r=C0hpSZ1F@iY5$eZ%Dc ziTV44|0gCd4F6Az|7U)juMhvv*6mzm^Y`Z0IZw5`FZ0)&slRR8^Qg9G;<9npzQ=ij z<&{`}=ZQAo$$#pfYk6$eo-NK0PCv5$5)W5)dRs273w#`S{zn%Gh z;Qy(8jOEGM`knFH?0U}8@g8gb9sZw~`nvdk;>`X2U!3v(#FOfVaQ>VpTD@R9zqx9M z?fg5BZWzM#;XJl!7}w7MHviDBFXs&N{p|X4&b9hu$L+~Y@ZYbT?u`HU)9b4eY}=Ax z{6B3Ue&9XttjPWB_f5h7%5Tbu_WbVD1mpjC|K<$y#ddr9DC1*3J;#~jd(J5rCirik zT|A}+Vf3y3mGybq$56=9)FhARw-xqfOcIN#KyT3b^n(u)Br|su` zEBrrkiTM-we`4~$@&DqC|0m}89se)R_b0Ic$$6gDbH)GD z{duPSy%_S>Y;SM2dc*ej$QeKFifskX_+(|RQ=F;ideFhsocVoVf8U&|ET3}C1treZ zV;=Z&*#Wle@A_vdeS2zce4(yWjWgp3N7mIjS6IDz{69USIphC{$x|f%PuyU>ApW12{`h}!#{UyH*z-F1f8u&O z{`h}ld_VlZIOG56`r`Y7{}*TcKQVc2_y%a5+RJi%5k-j|GwMR)}LShwln?~{-4^Z z|BL@8u3R`e8o%f}&eZoPz2p|>a{K#n$@p9I^!pROebINF>EF8NHs@*cMn|_+e9xCJ zwR#hueEdCcr@rtZz3z0T{xJTZwx`h-w*#!Jjec?;s1#l&%*x`lTVKS zr{DABKjQz1o6O()#+5&EuC~9w_r=kJ z)DJm2|7mCZQ2ambFO2^u#xKPG6Z888|4+>OtN4H7QhOeF>(&?ZG#m*PfWfa{-3yVL1xJR6Iaa74EcX?CjU=7bI#c4spda8 zH`((k{-5@zu69tgck>4c-o5HWKmWz`BcrRo^^tR#)yLWU+{eyU_I!)~r|YS*acuDa zG+tHGI6C-$;zINBR#bnUC(fxH6#PGppXXK$4*s9U7xDM-|Kg1Qr}1stSAFtzg7N<} zo?TjLd4-n$r}1o<{6BF?`KaLkiD#6J4E~?Ev~XnfpR*70{^e6gC+0&c3X*wNWqA{W z|EKxC#;m;H|B0z*iT|hhI_g>C|A`wibA$h<`C|M!{J%I;|2NL~e`0(){J%Kk|A|>2 z{$HH&|Kg1Qr|rT2!v7QF+u{F-t0uJhe{shDbGH8Ye`4w*i>$VFO2^ut}~jvxM?c#h@&;s1&80m=UpFDRH2^8dum*##m0FV6UXV)FIK{}bcS zlK&^hzr+6%-l z`(M6XdV4yj=KF33&#nuT^f#J8V% zqjBzhNV_Db<^OdtKPBG(fBAnMI&?_%Z{NOsg42D!9$h;o+Pik``hWP9k8f<9eBsl< z=j+m?OVnvulJWnjuZbVnr+cSR|5r@D8UCM^#~-BruNZ$2|4;q#^T_`bcd>e&_~^4h-c`z`-``e$8tjWfO<^?%hLKj)!6S9?44VZUg9fFtwU z@c-Uy|77t0$Zw?n?^!>4Jot9_Mb!Tlv;FvgV{ZO&@c*a>i~lDceZ=9x|GV_;9|iw! zxGj(WCmv>>kN+ng)A5Ml|7rOSJ-P?~Pu#KRQNjPy=XdCFRPg__y@z+}68yhW`A-G^ zuS>V~!T%F??0k6e|HShD#Pa{dha7Qm@c+adAN)V(BMyqXys@*@ev_qs`SRcM2ag#R z{J$-0?+gClv13LA|4$qpb5!vE#QnSX2>#!ttL_c{U!N}Bqhs&b*t+wyy{W5D`7Hm4 z?p>lg9^2p?wKreywe`+No6kl4Uu{o!yV|M$D-OPw`G0Z7|GT!sbHNA2-^BkDA7^=e z_9aVoXrQt{}WT68vjqs^@IN> z#t$U_Pu%P19>M<;AAM4<;Qxtx^gbaPeZ(^FKe$id=yCJY)Q%5`|94x{^T7uk)u&(Z z|HK&s1_l35to%PQJ|O;|c--Kj5&oZ!5B&KX+nmP_8yuCKx6Z#0nWKgW|4-NZkg>yq z|0h1Od&lVN(@ydJ)DORZ!|DW6|5x7!zMuGi`aZz+{OsRf&OiR2z8~`c;*9?nXZ$}g zJ|O;|nEMC*pBO(8|4)2))Gqjc;>hkl)c?&r@uuMWjj`u7^8dt56^+6F6Yn;kZ2Mc8 z-cEhkWd|ML75n`^^HpSWsGX7K;wjQ=NQ{0#q3>xc3G#HBVL|IyE%aArOT z|4+w<{0#g*ahAPodQ##QziLFUbo2pU&s> zrCHIPPd?)3x7hqI{J*U?EDJs$jQ_qPt5x8|HO>1*K&{}Yp!g8wJRf5ZQabMBK@`SB^W5C2b`W%Hq5jXyeNbHKsx z%P~K1+9%zd$6FpB{-4^jc2x!cZ{x3S4=%<^8duOmj7qI&tv~s)EIofa=ZTV|HKt` z{geME#_yv3ueiYOXVm`{S6aRt{$HHCz4!8CS+_O>|AzXLH@7_RJYmV0DC7O74)D_K z=<#JgcFtZ^7}b5S&pE^DJH5O7VdwFdcf0@{VEn&$fAfR9o%NYNfz!4iOZ~B82+D_ z_Y3g<#Q94z>7OGeFB1PxoEdzuZy)DGkS ziOCbh|BEyJpBO(8|1Zww568A=6!(_|+xc?tKWB9C|Fr!B=8m!Bb*Hxvv3zy>KefYl z|MSlqGe3j-V}kAe>72DFgZrybopR@T2_JUPo6>^L`NipST1+ z`<^Uk@>}u$)J|SI{-2oo$M}C@evjk-iR2l|C`}>Ihr*?kt;Qxuq&%^%{^L&o~C$6*SclG$N!B@?3ZJ8p6&j}QM({i*M;^{`vK9Ul+>Ps=kt zh5r|4{J%KAk-FWv&ipa_Keba&0{>4;{oh_C-*>Jv|2kvyUC#JxCAZ$4-~~V3>s)Q) zRrr5e--wl#M`-?^c#M6&@&Cm5*W~|+YwY=!{68`0`;YHG#s-S}vN=f1qpnemmJ>r;Nb=h^jH_hPFv*Tc%Mf8@;jpSy-V?mXB0 z##bMB+}Fo=;(PBr;XKQHLHs}MPxHzN!T%HUzEI1PPv=!{o*&*H#9!a>muH+APrBly z=MsEZ+4IhfU*Z30ebdZe#Q*d4+22$AKQTUF`{)(tX7l;*|FnFQ`F{9+;zoPk!2gRg z{-2ofW&FQ5LZTWxV8MT9>-hcdux0hE95B{IVx63MrMgQshuRJmB_zeAWLnbyNcaCrb1mQPPYd!j|AtTV`QH{glOJ~ck|p_?4<%{68_<)A^1q3C90ZJIj;* zC&q8X{}Z$Px6S_(vwiq~;#$iG!~csj{-2mUF#JDp`Pi|+{}ba6b-(Y7e9aHz-!)9w z<;?b7^>C8$|Fk^q_R|B3NM@&ClEAOBCE z&-I7@7iauGG4+e_|HSxO_?h!Ht&x82^0y%Q!a_B=?{55pO3SGS2DyPd(^( zd;0dJ*H@lekUSoF*~$Io`;}Oq`PXrto|EKs|1X`>`%@n@zP_&JN5%PY%Oi_(d&?_} zGx>CJ#%GIjNAvCC+_`Jg2Rynfz%5iF+JzSjhhq^LhAx z;vSYq_t%B=~<7Tkj42U*(AY z!T-DA;(LPsmp5@_@c+ao_3RY-K2Nsm}O&cWqne+_7D|XwUT*wEp6gr-R>z?{!koB;)_7y@R#m z|A~8=zdHMdbNzbZ_&;~d0Ul}fZSntfJq;W{6BGT%YWQ)x%qwjkJs_XA0Mr~)%?Ewe9}oLMN1x9>fGDv z0XIFf#JOL;eo^D#rM^CVK=S{VPJA}_fcTB%|2fv`;`VbP8qYn(e<9%aK9YrH@A&sYC+it~|&9vqc@u-aMv zpVlw`Pv3{bO(4Yo6Cc*DE&oq^h@F4@zc}0TyI=oYKlXf|V0->|#xJ(t2hQ#6`m^5; z&ZYwf|L^Ek-wys?uKj(({}az|m>2v%@tNkE;s1%{|B3PWsQ)WozWI#c|A|+apGN)P zIOG3`SK9hZ|B}(#u=j@4ic8+kr@rpQ;|?(Sc6|%SdOLnx#}#9oPq%jJ|7v}kwww{Y z^YAEd-)z3yOTQhNVEjMzryc(<&iH?E#{Uyj|Cs#0IOG3`sV9v87iauGvHZU{+ze&A!?&9F{t=Vy2bj3ZtcAmR!RmlHS`x;~vl1VsXi0W-U&ZSO*ybKA{<#FdwziI7{6O8|- zo2{NexAjanLfz$rHWjQ=NQ{u%!-&c&-9aAtfM|L>sVT7nPQWaE?gf8rVICI|md zT)I9d_p0f&CENU$@4g&&mGQXHeUPOd$&6?zPa(P+nkvn z>c8Q;&QsTAMXyf2)p^FIyl8v7Tb#=*PhjY?H#=9EANI40ZgM6M;mn2`ooj8rYRn1W zc4qmv-?`qo)aGNz|NHUlEx~8x_~8GEi`Ta0|B1;9x#VA0`|{=HGvfd0_~19<|HT>q zPv@)D{000!T^}=6Pl$S4eX(D^C8tb`&UyD6sT(h!7ks}O+kgB&G5Hnvf8t8>Bk}*l zOBr2ZrRpP2a`^8dul z2jTyT@$>Ni;*9?%o?$)~`G0Yy{;zoIwxZzwiKkh8U;IDa@2IbZ|EG2s|4&T4Ui?2X z^|tW;#C1DnM2y91f8pQ$Vs486XZ-G4`HeeEqJ#U+Og*q^cF6B*I-@kI|F|yo!*iR1 zzeoPvZ$79_ef2_9@YnFQMqFR%jPJLlrra4{@X13v;{;=2?A8_s|)0}C)qu*3# z^8fz!vjXQj<5zx`pV~5YX7CH)6VJ_cW+L83*4FCjU=dvSWJi|HS3HN~ouq`p>WGgYQSaAO4?s znjH`PKXIX5Z}@-WBCD5-|0l*5#QzhQnBRy0C+2#^{}WRm4*##PZ+%xc3G#Q3N9f8r85Uig1vd=vaXoj;Bz{$HH& z|Kg1QC(d0xG5CMt0{i=f|EKk{J@|j(T=U`Z|HR}O;{S>BZGQD{pLFs4z)Ni)-Y%%rHYdE5&seggxiP-g=qvM@x`FiGu9boh6?EB`7 zk7viq zFV6UX;$e;U_vquR6FlwY>l19}%bE4t{mGf_xBHhf{-OEJ&g2{7|LODaKk@(KjQyedoV}>c|5H1^H|+lH?Od;Re|P5h1pc4S7kQWXf8xSrlY{>!=KUA^Kk*EE zKL-C#jK7Ef7iauGZ4d4Ee`4OR!T)o%{5Sl+IOG3`$>+xZ6O+$v_bX?<@2`wH(wX}! z{-63!u{>Y=KXI=8UbFk3bJ^lC!T;0t!}xz<-mk;|6Ia>swC{^EzX$RE)Gq%|Twp%W zi3UR%i@qz5`uQR`2t@do5 zp6_7%KRqATn4gFLC&mxN{}bcy;s1$w{|Wz3OgKf`EvMwVtx~{6PFa zF}~K=mTx%YXLUU9o6h)r?|<(iXWmzR{Dq4XjQ^+gaeaOFqDvCj*RH*nI+xgZ!rWIc zbEe)l{-5@Lsl9(l{-4h0!c(UQ|4%&EwkPj{YrMV5@~H9u^!t*0H2l9fFaE{N&g8G* z|EZn)HT*v@^@j2P#Ix-Ci~lFa*Ter4H`;gx{+}3M4gW9B_M!T*ah{-1cR`JDKFamN1> z<9nXo?or=9_=-{coEO>o+3?TDy#GS;>7F<*%rCp4%|KePA)lLv5iMjvb|B1POKDp%u=Ndcz_&EL$N^_nw&Y4y23aVDQ{*#kdymj9>ygRkuTGjFFq{+~V% ze-HmpEdMXg_qZ6tPvh6sH6w!mC!Su_mj4&$D?V(O?_4r2_|KjX1QQhdJ`I?WNK5}r>?ad|mn%}RrdYG60eyKC{bn*W*-;EE5|0l+8!v7PK zKZgG&CjScmFV2=9lCSwh+HHQ(86U>#k2%wh|EK;n*=_!xn9s-m6XS#7|B1qed|4&Tb82+E;hihzm@c+c}|HK>*{68&^FNpsa zZ^!==vpoKvnC0>R#MB=p|4*E4d2{%GV$LW2pP2KF|EJH#kHY^GkFZ@3-{qg_A_*=ApgH^ zPrCm{USfQI(tW`6?MdI>bZ*X1uCH=x^7xe(Cfn2fJnFN@w`YdcFaK|x-ap;%!F7P|Ihi@UcvwSdh@>E|7A?J_sPuv z6O+$N{a)kLuks>hYV4ynnA=y@LOz&+FN&*Vy{n?qT$L`jv5jCKXG-&$l(8dapm6N z|IHXSF!+B@-+g!R{{|i3CHQ~h<2xT5{6F!)PVIyLH*fDi zuCIqrI=i)BkEer=cih2;2mepU>zHZPocBFA)DvpU?i{|B3M*@&BAH5Ae)$b~uk2J|g&kI=;mtMnv78+3NdO zG;}D>pME_>!~64o$^q_lXz>4ZeRKc7|BEyJpBR7Io{xQbd_401bbWGtGP@Ii~lDkfAFH_;ocwKdd9E= zZ2OP@=lzZG|Kg1Q7iauGF~^VmKk>?KXGQpbV)Fg)|HSxy_d|HN~bjSBu>pG)Tj|Bv|%{J#a}tKk0? zubCSBKQZrz;{S=utbXTVAHC+hXv6g2|7m>-PA!UNo%f2jH`{pAAx$qQ`0jx(IWM;H zSNuOM-(q=S_3#{bj$s%`up|4+>O zz^8V6!kPDl@&Br~&JR8y_2+(U{$HH&|8zV{Z2XV>KQZ%D_R)87iauGG4nkKHT}T3#PUE!_j$;9(t_0x>JbCfB2>)+H zYEke7$%_~_?tbSw%RB1x^}Wu_zju7XT>kz2;eTAP*SX6054HBUet&!Iro!ka$KU0Q zADVjSPG`pJ@3g!>?{B^j{@b;QxtB&3D58 z6O(U+|0k}rye|Ad@d9hd{}a!&`5XK{G5d%AC$2F6;DYa6=ZudqY3;QM{{6&nIg{Uq z|EJ~gNlzVmmG3{}v#&Q@;pd0(^5M5#=GOy$>&oZ%`1M(8zRh*rFG`&{aZd34@FDU4 z#2lZi@-9q~Ifs8%Wd7f-t`|5@vHX=4@0{n%{?$Ejt~2K^`M|V2U-Ch}eJm+-h*;~t_)W5enSDD|0 z|3?j7{J{$IoACd{)IY`l6PKS^8S?+cIlIb&|0m8nvm$DKVzu|DJ}~~D+F|@Z@f`C3 z2k%|#+cSGxnT`K0Onv_NtT2Cp??;wg@fi(m{+{`MxM$+o=HnecxiQ862M@n0f3DTP zy=;7)w}<+@Rdy^+ z@HLMYIkP{1*fPbL`nmXj+CJ)c9XU4Nw-3hud;0UnwtBn9_JJa-HrhY0((3oFdt!t$^*{geyP>{)_(Hi?4tB2ClppQ;;Q-&C zV!K`sU)RsM)V8l~a3AM9^A}&PJJF9{zTGd5>)6W~zYYIS$GgPlEAjut#ar^D!S^4P zvW%GE_f6lNXZ63jInOw)Aozc3FWWvf_#F#ewy9~J*kTx9L| zf8u=e1E0MqN?q`qn&9gd>?koG=%0^?OU>82Kj%y55}O~k`iaiXr>fBV>T18aisH^K5O@c+c4ZT=7cPfQ*u{-1dAqEW&BbDlpq_iyZC`4P^H&wPsn#{bj$@ip-O#9jG_qn&44JzV@hwHMj(#{bj)@%;h+ zFV6UX;wsDI#Qzh|Uzrm8Kk=N^(}Mq}^_Q%f9{fKs+r$5hv-xk%j1T`$?Q^W2FaDnx ze-HmJ&iH?E#{U!NueUsG^Z&#d_WT_GPn>4;r}j&lltG;s1&8`|$t7tPlS$&bGhKIhKDy{-4@2>ltrp zzQ!}b@(1z%#FOm#DE^E|%$1lVG6LbFJ|HawPA7}hB{68H( zd_eO5#BqPrPzxdGPZ#TD`?YzwVLHs|pFEJl5bKJRpeDDX4nR{LW|9$oO&iH^o zIsXFZM)U1%zU@Ni)tgG9Gk|ANbci_}ZoT*pve$}PU zynkeWf1Nr1@c(pvQ9m93PfR{B{-3zSes9nE#}&@)mjCwl{{6oHZ5wi@7MT$V(Ry@Vmn^= ze`@FW;s1#j+x$Iz-jm*cxz#Vm|I_lzPA-Z@<^RC@Q(ri1{STcN*xxh!Kdq1J5B^`A z@&Cj%rxXVNPt5Vd{}VUb-(&p0IOG3`Tg>Of{}VUc-vjdh#EUEs68}%!Zs#BVpO}0= z{68`IfcSrL-t*>*&dsZ{g8!#>@`v&N#N-d-|B2=QiR-N$|4+QszK`Soi5D;L%KsBL zAN2pkO;!)M*7EKnR>yQ7Z`)!q0FZlHd@5gv* z@c(o_tJ1!olK-ds<@ka4e{uf#nI9ME{y6KS{;%$T;~V1tiK|*Og8!%c+jZ?Z!T%H2 zx8+2iwtrEe``h!IGlKu8``0DLQ)+q?ii_%Jg!;eYIW@C_|0gb}NRQT!I@J4D6es!_ zWrh4cdt$Hthrh8sZ*`%b&*J;w|H%))mplFg%lkX%L%{fddVU96eXl}2A6#HQlhyxn zZp*iNs}t5bFU%{j@1yIS@oVt^v^>62_Veos_52c_>%fcaov9C8{OSg0{4c9-mcaJ> z)0zFj|I_+m{68_{$N!5n{-2ob;s1&8-SGd!_;dJwV*EM$KXF;+tlX4+%e~Lx0~-bX@4T;3_jP}sRuj%hD2U6`aEyPXT$%~`GD{C zZqs?r#g?~*|EKZHDJTs7pO`!}{68^yY50F){5t%srJA zC-ay2e@hAz^Y+^9dXlidB%d%j4=~xEYfP&DyC}(rYfJJ0ll`_Y%d{{6Ok6$Jdw4$;Ttv-{blgUp|?W_xFG8Us8S|{&;+S_(^d-Vc?PfU!3goCG(g0 zf63b?4=z5QWZ#hdJp8|jbDs$QAN~yfpP2f&_!)t)SvO-|B3O}@c*=a82|6;!#aci z*Qe*9!T%HYI+*{b{`h|PO}wfzdgVay`{4T@y0UZa_a6`b9P8Vhp2%-L{q@dYoby=l z{d${!_38S{JEw1cH28h++`nGtJbdu@;Qy&TE3Gj2f8x5dX~F*!7mOSd{6F!8u_pxo zPdsAifZ+d$$Dc4T_TY&-L?j@c3cD|I_(5W&FtC|A{Az9vYo?$JyQ=-*MRoXZ!ZY zSUzM)$vHm0!FGPX`1sk*$6I_T`G1-}{8#)x@sQ(=3I3n>gt0?H{a?*LO#YvEdE5&iC0;DU;IDuCgTftWpwtaxi0v8)Sun@t#oI6 zwIx4EbH-=G|5JbbH1hw%n|AC8{-5}ioqL1-C*ExR@&Cl~|Kg1QC*ErHZSns!UKsyR zO#UGLpZZhJ7ynO;kB9%K{xJTZc-QG&^?&1x|0h1#d^-HUIOG3`x9&PO_fvwU*b1{}*TcKQZ%7{-2ofkpCy%Zux`J<-?tKopEmTw}*#0Z{D{r_&BQ}dtj`D;0)IJ&BLr*p0O2>5@R|C|*m z!T%HITYV+`KOHaf8}R?)jQ`iPc1iI6=GpTd{6BH!vb2!@Cnhft|4&?O_p9*##53&q z68@h!!=Bfjckg}9PV0+EE<+W!DYP6;^)`|L?)HWx-D*9}oXeTx5*@C#GH@{+}4% z@4RJK`}*(!@&B~{_&4}}IzCmFCy4*2^8vr_in_1)`AWVP{$J^D7X<&0`fB)p;_B^o zKAQh`&d3G9|Ks@K|B1`(^Nar{X8ZVm;#%{q@c+8GB=~>g8uN4U|HKvB%7XtVo^Q{C ze*d$5-cJ21{6CGaVOK@)|HKO|Zw~)Y+-klS{-2n7z4(9sIUVF!{cGm|#ugSJ|^LN^u z@$0A+t9F>IIWhTuxP9X0z10!_7UTadKBJ~%;L~-%_mlr8u0OLn_xAL6l?3f*W=gJ)Cxt5># zL0Psl^I97gTqa=^)8YSV{)#QX5C2b`vok;Xdcg@D z4M)}mzc25!Ld)kk)_K|C_U? z%l{KsnvaS9CoZ=R03c#Toz4+5W!a|B1`Z*Tnx5lUIuW7iaUa z4wzFD{JwJg{LfzTwln#q_N@c+d4hWLM)|9or5 z{}XdP$Nv+PH;DfiXRB}OOn>vkoT*Q2eVvPK|M35`JmbUv6O->}{)RJtB>tb;v(29~ zzr>lmyI;S1g6~g`)uY7!)Bf@O0sl`-9v=Rmv(*>H{}azyZtvGy{+}2>h5SElAD@W) zKXKNIP_NlJb9ole-<>m7%nbgY`e%3fbKZ_0X#4AY&|mcJ^Zm@m^O(kyXZ1Ag_&QUc z*Y-Do?I#{iTKN2Mep-93nEkQw<@$J*k>~eY=RC_d!T(b`^@F$kH7!reS6SYl`EAa8 ze=}dr8UM$|*UfDy!T;0p(-uq#{$Dpw3jUuswQUOf>&s7CIE~}uJh^Rp@c%Tv^o1$G z{}bb<;s1%rufzWnlV6AbCr)df7W}_B?J4HRS)21T^ZW4sv_ItS z;s3>%{68^%9{!(rqCM}#{}WGbvic3?|HT>qFV6UX;*{p`%zrnVABg{__9^v~g8wHT zVRB|A}XsA86-~Gv~YgeQ?gT_mS-HhjYf_6#l+A=h)}f z&NpY?Kg0ji`eFP(G5J&Ye`4xM9*926*Y%(4^YqM&`g485|BEyJpSWVV{r$80zgk}Te`0({{J%Kk|B3N0@&ClR z?bM4N=A2@_CjOt=<^PE}e&qj&v$?*S|0gED5C2b`WxfOcpLnwQ_V|C|8RoO#|A{Nj z|H1zg<749giSae@|HP&C`w{<7O#MmxKQVcb_uwe`4Mb z!~csj{-3zT&IkOzINQIS$*VUvD}nL<^nHx`8~A@>@&NJw#QeS*b6cA;zmH%3Te~yA zhrc#`sdJsZZ(=^bGxc#le{iKU@6+7(pViI_?ECV%f_2X1;f*|NgERiy$d5Mq_~Dl_ zPI2b<_a!?vJJW98H=LX8`{L*S+2-78-#72e+v&XM^!d^HJ*PRh?%@5C-Oh`*7Dcc0 z*z3I9-aq;Ax6X84u&X?}>8X9rypL($hn#EdeL(y_%_sAP|EJ?sZTAQ8|Kg1QCvN0@ zQS<-ejQ=O5o-6)eobms}+@He#6XUDl|A{%i_I-N zFZh4rCi9u`|GGIR_R;(o%z=If8u((KH&d}@#Dz<6ECv-zUqhWEO>fttLOWz z`r}>B)MLi~Q~Sb`3xoeB=Kdr8pP1_h{-3ydOL6qd)Au?zTK(jI{_{TP8uLASk9@$H z?TwuOU;<~I_K-94U484r&hr1Xy=MFSg8wIOvFjcFpP2c$tL=buqa6?YKegje;{Sabs8hpSZ&OQT#t~ zrTOvre`59@|4+>RU2zhu+iDG3M243hV6s z?c3k}opa6d8NvTk|7!CA@&DqC|0k|F=>LhU+tP#oC$3#EBl_sxKYM=||4-*fb>qa~ z|B37D`!@ccxay$)r~73v{-0R&e|0|##{bj(aeP4hKXFx4N`(KX`{A{X(}Mq}=LPl6 zUH+fAt|>iwVCZKB;(GJ>$p6#*?v~c{;Q#4xs^wS;+lq;(F=d<=J|E0!T;0! z(CYcNzH<*L6jzkb2>zcqxn5@N?84~MpRFj=^H%c2$o~`5pZdRgK8IgN{$HGz^j}q| z=Y_Q6|A|BXn)!cXd>8ybF+LLhpBVoK|1Zw?e|mn8Z-W09XZ%00{68_{$Nv-K7g|1w zGky^MpSFjegZ~$2{68^16#k#MHZv#qf6i&y!T%H2XXHeihi>=n)mr<oH0H4f8wgNl;Hn~=giCq{-2mUFZ@3-`AYbI;_CG5kpCxcPR|Jb zpSUF>Gx&evxf$8P{}Z!*{68`KhyNF6{68_iB>tZmpAi2q&iH?E#{UzOkBI-L<4L|4 z{-2ofOnnZf^yGyb2Lyh!{%akb?|;{S=~&YBVYKQZ;Y@&7bFwom?FobmtSjQi$%agD8e{qwYU-9;2zcJbO zOXlR`@nxKRe3SjniJ7y}b=c=B_LqBY;W#K$+&KA#^= z?&h9H_K%La=n~&Q{7>_%o$>$d`s>^yI)v-9bDq^lx9hiab9Ghl|1^I!Wu?LY6Gs_S zga23hi#vn=7uo5%;PNv%2fb$*Kj(j3m|=b${-3y@SC{`c<-^;9|JU#6F8{Ci)7ygo z2UGudz;U+)|L=%ndPkohacbwkvu_E$U(}~Z@c+crhsFOBQ@aj$iHV zCyp5z{68HJ@(bU|TDMRtf7;&>y^n~#anugqfB3W>+nw?IT0h#Fz!`tu;*2ktv0}5&H@?**>qM_iS)x{)hKm z=j%)9)ib*Gvo+4W1`Lco`t3SDehqDlga3C;qCszKSn0!I<|HNw#`hVi}2mL>> z{6F!w?OpYM#ap(Y6+PT5#n*@bcT?)r1jheU|7|eNM>#6XW}BIDdri-zmG# zjhenc+D*W>?*x&Mj( z7iauGG4*or|HRxs$Nv-KyG5bm9a(kcke~x&xHI>U@c(qYVEn(k{{+}3M2>(x9ZuK$o z|HP#`ON0OCY|l$xoc#@NFS7gp_{-1cRZ4duX zTx0cn@&Cm2<^$pXiTS*c|0gD&4gXI($DaR?|0gar{}BIA%=54xfAdUde9o0`?Qy0) zamM+(ooj7*{6Fnqh1Hw7?8cqWRhCDwvUt05<(65&|0{2A4SwLPWfOw`CvIIcKKOs) zRa?_|{?_r@(bd7ns@hq^^Eu~wtJiAz9Ub5JQFZXa$QQJH59jhTE2BTXwXg$c@40VX zSy*lU;LPh=6PVgfYR4xeOHN#E^>A^|#PiJ0V_Vu@h2{JGd0&-t>%O{ZW?n@C@BX;V zx%SMO=$X4q6Zq&2bDUeuKWrN}+quE!@8;hXI5Ym;Z|8T6v<$*G#_lh~U%a$1uY;Pz z_;}Qpef7gx&Q-QP{J(GAP#1i`GRrH>|4)YVT+7$&9FXSy@o)P*o$8FQd&!$AzP%>% zZ(qJ@igU9)e{6kpqR$V0;&)CRpTPKkn!i@_4e|fPE!O}3{v&+<=9yplKR+3oz~$!* zcBY;#{-5R_#{Y{m`G0Z7{}Z>^{{H#)qx}3Kzh%bie$M5)y8J(#Z!r0PV)6wu#~t2b z&!~g%SG*;M{GyJ9w^RkcsCtX#k4%r8>vt65R~=A0d4=XjIFom3{)F>v8;|)F&V|+= z|4+*oostv$Kkm_ebH=l(3Kegj~Q2$pvwkuyMfj4J8 zec;*;D!cqW>;J`LPdMk<-`7iu9(N{hZP?QfB{2S~^y4iV> zC&mxN|BEyJ zpSWy8rsZiZbH)$E|5H1DpFN9q#_z-bi?`$diRJ%^GtIZb{}ZR1AM?Q9M)~+>tqPt5se zK9{dAZ4rK3i*weZ$@p~%Y~y#%Hs8(0^O(k$Wj-AKpLmv?pVr?w*L+w0Q#-z^wdaac zY&^ESGuyZIJLfIKFYKSE{#o|@4*yS_x!Cf%%>NVP`{4h@+1BrzZQHZ+**VMhpZdS* zPkmVG|B6%17qsy>4>897Q~R*?F8@#So4KIN{}X4J--rJvo@nj(f8r^NQiJ~|W_xyi zc{_~%r*`>&V(Js)|A|%qSL1{6|Kj|D`G4Y6^X>5e#DmS(!~YWxX_*lGKQZ}&_wb(Z1Dfoe`4LJ;QxsSHjE4YpZGY-FU0>7;~$d$C&n+t{}X3h zUZLfiCNTAX)t=itA>{vw$$KRKPb~jWEdNi;=f~=^d;f#iZ|CuLKH&eU|73gr$j%?< zS<7bz|4;4Yi{t-^=PjEW{6BH&V)7aP>h1ZfW(5CF?Q`tH3a; zhW{tVKg0hMlYexOJNSR%`8z73 zDU&jNdzI$nytOvld9J-5blq(^&c&PO*!h{~jK9)%VqpS5wPv<6zSL>A&T+1^N7t4Q z>dfy6{68NLzc0-H6Sr+G3I3lLpU?hYdV7Q2U%>xUJ8ZR&6Zq5R&Cd8@_V?GBdiAUS zw9uLH;Q#6S9lw9@|HSibzU}Y1_s`jyAC`Y$d;O8%KZnnICyZ$@Z+3$b+KV2VS{68`0H~wFo z@&Cm5TKIoDKVbYnG4&9DF`_Wc%&T_-~mP-I2iff9j7fV4}RcG{^N!3|IitK@x~#~IJ3To%YNj{`GNnZ?JqucPRRcg zbN>$iPfT7X{+}3s9{*2VZTXq_f8w?F_m%uV@hTfH{-2of;QxskFaDpH^ArD1%=_uo z{}od|1^+M3hu-s&?;rI~hQ9t=XYPll^?t<}pRXe0RcCy^<;z}kp1W#RblSzQCouk> zj(7EH^XJX~6Ia^%NKYL7rgMeW2gd)?_{x`Lhx|Wr)#A*E{6BHUqAveWT(z*v{}WfV zP7nT{K7Z8nCI3&1--rJvF0*{TzNzme@aV;VPvGpYzVAG@VXEC9`)7gfhbjM0_rvi4 z@&ELEpt^oa@c(o_yVkZx{-2oozW9IQhQ{epMeXO#&DMTp^Zyj+{&!P-iq+5h!nv}3 zdhq{rzq7nHC3G^g=K~eDk#PclQkNiI|ehB`b7#{}zPmFJZ{}*TcKlujo|Kg1QC&pJI z|1Zw?e`0(g{J%Kk|7m;V6XO4gSCy5A`oChvkN+peZz2Cr+&Ht#{}VUN$O`_SwpTa9 z-bXY4Ph6WiBlv&nUzwU3{68^ye)xZ4d_eO5#I%$DC(chx4gQ~aw&nNX|B3PM@c+cr z-zEP~OgFMe7=nFd*j6O9{2pedzRhMx#^Kdf*%+1 z_ujj%GiUQd!GFUKyk>nj)BeI6*L5~s`Ec;(dYG?sNn0XU{q|aKr(W;g{Oda}di~LZ zKF*;L^?x(-4g_DYm-%Vl{ z{w=}(Bfk*;Z^5dYg8z54>9FMgiOFA!#(kypC)+!MPukCp5B{I{@Iwv@`G4ZW%=g3p z)A=;$p#LY%oj5u8f8rCSObq^?_z26d%f9S9Uw-hh{X_j-uM?T;TZGUWe>rw$(({6BHZ zh*2T`Py2&ENc~^&as3Ab|4;LEynQ~3FWctxHSq8wqKE6G{(ei>$jn{P<|pLoNLF8@!wac7tRCqC7DK>R;3d3@ymiOJt1|4;J)lm92) zZR5}VWPRA^?`9t6AD0z87@cmZr*%JIeadvHK@c+c*K|Fcd z>)wBkJ&z>+@A6MtgYP$gX?nDJ=gS?xENKlsTD{%xXutb69qo5F2j7qTvG{-DCVL<5uDAQS_~?oZ+WiMij4|0gc9_2K`;8UIgQV}2R_pSaTQ-{Sv?@!RnK#Km^M8~;zt^CA2{ zaf$hUxBa@qx!j(I*57o%d7izW`OJU=9V1q@1ix~y`iECF* zkM2ADUgtL3|KF8Z{@=mvasQqCzlTn03w~gY5^EdaE~t|0l*@!v7ODS-oHUKXIe^eE5H2d?xb$#C2y@1^-Vxe{XH@|HN~) z%?qCno;^|4&Rl2L7M+ zufqIG{68`CkN+p8z8m>}x?W|N|3Lnqc_zN+YuLra~T%ulTBEOxH7UVmuGZP!x%rZ z(tN({mrZxZ|9i4L#hE<6*&8SO_~5UMpBUrP=-0m==ZwEQ^13n3_<`%2Mmg7*4~YNg z`)9r){-3zod`bL2apk_6;Qxus?Rew=i8=m_GX}=yvnu+=djp&~p7?({f5fDbH zym@bV@ad?J{c7)jI@j&6`MKmh=PG;tga4=HOV+0b|4*E=bbRpt#M9cw2meo;W`3ag zAHF>KWcYt-hw=Z!lk9oSoA>_2w?Dz!@&7d5$xEjN|4*E{y379)%l{Ln+w)8Ozc}On ziRq93C!Vx6HTZwxsTx>_V|EG5R zIQ&0nt0#&7r{kMz_14Vi^7b@)-e`W3bGkim#Q*dD_Pi4RFV6UX;@Osmh5r|4{68^y zTKIo)Hh;sJdY4zcGugLKJ!Skqjh{R~^8du_ulX;|)Z4}XQ#;RV@&ClMd*M`|HPTLzxaP* z<^RRm)}PRh|EG4=kN+oT`}lui#%JSk9>2IN|4;1`mUQ`lns4^su2=bD<_G^T&iH?E zw(}=n>!ZJ&U(T%0_Sd;9uP!fvssF3x@dGVu%^5!s|4;2R%y+~86Q`OFhyN!g9}xdf zJkj!0?0j*?C&d3#`?Q9M!T%Fasvi~nKk<~tF&tm-PrYIC|J0t+Fh2Ny;t@?_g8wHT z-8w$_f8vRjw}Sr{XZ$}g>&O2SlfQ`nCuaYs|0|wm{wn^TnDgPOHBTlm^?%hq)1IH> z|A`M?zn!O8Jz4xewNG2omH#Ksvif@D|HT>qPdvvy-{k*^iuT-}rxG>TlxziCZnt5C2bGzhXx4|1_SIC1XPUU-8t% zql5n^p1f#$@c+a!EHBhPzXjrqWtryt9OIn6G$Z(b`aJOW5C2a*#e8S{KP^9X<*eZU ziKnm03;v&2{-3ybV-eS9U!Ht1{6DqxJ`nz&nBOO_-7(P_AIv_F&MaRwIVFJ)TR+_y z|L^hJXE@i`?<4#CI+M?a|EKNEw>-9CPiOgj^Zn)5hvYbu*LO)#o-=;P+&u*ejQ{8B zv+w)(e`50Y@&ClUUxxpu`Q`mG`?vE#`+Z^Vm-8a~eS!a{{^ZZ&|B1;r$Nv-8+3!F6 zzc}OniTQnm{}<=s6Wg8nee>&eOA;9WPyN|G{$HH&|HO5hi-P|ruD1EY{}WePK0N-P zxW?{pj9h-Q&kz3OZ@;z4ne)T0htBx3^G0oRo@?{{#nK(l)JuKn#$C=;*59t5&iFhN zM(#=A_otuf+-Uh>_7CUVIpcrg|LOd}_r(8;Gyb2r-R^(j|Hav^|IV#;KH~qW9mf9?FShaH z|HT>qPfWhspkwy?`1w41F!L&B^8cP|xY`+?8UIiFyU3Qmr{A@{z6Iu6UOe?WXZ)&l zRo5pl{-1tt*B}{#6O)Jc z{WHE>aC6iUd^-3?w|~#M!hF8p{rdaP^X&bbk9*wXT)r+X_rC&quo{}Yoxi2o;UH-GdO zTYl`k#K!mMZ~nx2nO*O`c<$K*#{bj!$S1`A6E8BK7XMGY)Xq=*KQVcf+i&}YuaE1) z#V@{)z&A&~a>loOeCmtN4fg)|i><$QrvC4{=lsUG)cigCKkXmB-_(z-KJdZ$=l$nH zN4@M^w>&?3tv$RC|7m&of8w&$IU)Z~ykKR1@c+ck%W{JMCvI4r6}_DQ2VWoj z!MeAc8{0FZUi<&(Og-S&&;66nSM{Q_kpHLo!w2m5`@eLzTfN=UN511+Za&_uoWD8G ztDg|nt$EkE!rm8Id&PUsbM5;u{+~Y2F#ezJk5ON^=K~))Q(qYWPxr5>|2y`+e>>wN z?t1$Z=UU4H{Q2?!ajt3V^8fU_q1MLxyR-jW5NG^9-T%ff{N0kMP&~hGa`69j|FfWY zRPg`Ag>yy+|4&?!m*}_5o|PK>KRw^WZ^Hi*lV64Zr{{s>sgeIDt}QH%@c-mPl$$?C z{-3za@^SG0#P}lke`0(+{68^1ApT#Rvx+t(u+=AX=6Qax`G0yok8gti7iauGG5x9k ztM%jG;Qxu0|0l*5B>zv$^7wyo#{Y9RpNRUuV(R%)|5uD(bkrR?o$=?W|EqR z%KsBLrOycdpSaO{Km0#2>!<#&7=H=>FV6UXamN1>l&g9oM9eJs9Q+77>FP-^(y)y7?&Yb^4uj*!ezc0SH%;y6i zc)&TAJM;M_|4;K%Y4v#V|HR}glK&?rPc-gReHk|tBpHMk3qi zGod}1vlFj>jY-V$Nm$z)1Hu2p_rw1a_vzCo8vmDT6Bz$b%O82r zc2@mgZNHDr_cPC4;p4~uX`I*1hxR-qBL7eOOP(SApP2l=JMZ|q?;l5R?Sw?e|NH5p z`-2a7sMVjv|BEyJU!3v(#E0AV@c+a|9NsJVf8xO>4voJ5>c!rE$O$I~|4-wKEdOlZ zZ5R7^`&vF;|MA_7PI}#UzUuAd|Ka~>`QDb#hyN$0eregM7j}M-dtb-L6Av@l;?QX2 zKQ3@S+V*eXrfwc+oe%+ zkpH)E16w=A$J+6E{{0=ke9&Xf|2uraFa`y}(0;7?BLc|`F4 z#FOpwjsK_l=K4bZpZG+}-=qGoxc`aA2men@9w7doc;v{D(O=G5(Ye3(ZNcvxK74ra z|4#hcf#4@j88#yLf8q(2pZJGuXLO23T0Ld_KaGFzz(LUuuix&UXMAV;KYhMWFdrEI zPt4~R|4*N9@;mYW#K-jQ7yLgl>nHzDe8|xQga0Rv?EJp--c$T|;7{ZKX?$EC@c(o? zx&Gn*iOD0p=J1oef2LgzANqKM^Sq%$qu=~_z4O?yV}t*v^`Ct5$CWWYmESted5`&ajlW27 zKEv_|7k@g{S^l5KC;v}O-XH#-c>6*BPmEu<^0rCd4%hx-VmI4(@&D9+r{(eC|B3Pc zj-EH(S^i(y2m6D63FH688UIhr{^I||8UIhb-rDj1#2YN%5C2b$???S#@#a0}hx)(b zO?xkhZd&_h$GS_KgRggzEq_${@119x|F`RlH=GB|FOJ@R_I2kH^Udn^zvf(Fd4KqS zT3?mri`@6-OC9&lZw$U)d>) z&o2`As#l(O=6=@fJAUSj|M$+WpE`5@{>t*_61d>RXPvo!j{m3e;hSCl@Q=J5zbN;D zXPk@8Px@2K)6O-P?{n#dA3B$`PYnK_);Hc5|4%$|$>iYwiOVgo1phD2_9-+IrMCoyTo2 zjc$DD8_qNAdCE_3yxw_?`3d-c8c(_9^Wgu9%j|jkHP>9@T(YRk|5JNu`^@0~X?|;$ zObz~@xXqrAJiF;@9UTYigYQSa(`!Gzq~kw*>x171KXdKH&g3uP|EYbk)oaE76EEK} zH{}0`m)QMY{68_zx5)n!*W3H*_Z4v$PV;v1Gw}a3A9L;cMEze~f2u7n4F6ADYX09z&#dXd znZwtsTQ)ZMf2Ukj9{j)6+h+y;Pdv~3EBrrk-C5<2T^`az4OA&xe>LUwEmh+SrOR|amF1JH=D1?zr`(^XGQpb;?`4hg8wIO zw|qGKKk+Q{*RDLh$T{z<+UR##1p6_4YzWONoB&XxU_bP(F*SNPXs=Pbf zxq4S+w0~`;bD8?@T^kpKZrFSD9~z z|EKxn^ML;+uCV9H1E(InLp%=KZgIOcKk8?Kk+onPr(1v_ET0_{TTEA z#N_pn|0l-ZBmYl~???V$obms}GuGyW{J%Kk|HYa7zc}OniFtlV{-4In^F#bUG5dr6 z7iW9^>zr@jr||#Oo@?`k|0m8{mmd5-9e?r$@&D95b#-R&|HP^GJkR_kZ^yU8|MTU| z2Q>f5+sO|!KgyZ@_GW<2|#slopfr?ujjt@HMr z=BdH|Q+syfWacy0-c|os?bO>P|1Zw=`F750oe=y#wX;3^KQZI6>qj@YP73~?+VLI9 z{}YopiT@|gwd0NdCuaWe|HRbi#s3p?yzu|xjQ=O*{Sy4YINS9%U)MjDx9f8PH%xop znS8q+-2O}F61yJQ`Qz)$wfuPeKdnE{p5NpDiK(}3e_wq0e0%@N{{A>mU7i~JKaFSF z%9+9c6W3Tf{-3zk{5||XagF_6!~YXkny-%kC$3vGA^3md`K@EPUKMD3W0qRIyJ@|h zr9C-MK{jQ=N|YkB?nf8sLp zr||#8yib7tC&m}V|I>W){uutBnDOHOiOFNb{}WUH^NYudoEh)KpB6i_Kbx~kovSS0 z+_vr8pKrha&5iQ;$M3@b)BMBue`4-0;Qz%L|4&?P_b2fG;*9?%CZ7-gPfR^s{6A;= zJ&FG(UTW{3;Qxu&>}?GGpLq42hLHa!UU*tX@c-hB|0iy;_u=sW64?Ad9gq5*<-z}p zGyb2r#>R*LC&uT*{}bac;s1%7ZT|89#Q1CYe{shD6O(6$|EKZ6_k z#nlJ>KQZSk{+~F_^5F3Q#94Me;Qwj+wWrJu{-3zv)RN%;iSYsP|HO-|J~95Ec(vt6 z;{ShqwY4iWY%gx8a{}bcy;s0s;_DZ&2}<4fcJWiPA?{vSRy{-1cR zEsy^vF1O={|0iy=&olXdamN4Kep_wu|2V$*e`1a={-1b()n~{5i*x^J_c}M){gUwu z?@QqP^X_-XS8TfX0cU*0liqmHnf*Dp&%@4a5C2cwqdoijM+)XVTN8Xg+VTIym6ivN z|0k}o{L3eY9&qM-#{bj$;K_wgIJ3X_e`=Ti7iaSS#Q3-Pe`0)E{6BHcn)KlRiFv;l z|4&?F_pk8(#7it+5C2cR)b6Jo|H*UC?Q86Q;@F=#FSFx4xAu8w&d>JUKX>MOFz4By z`~Ksv4*AzFoU82p)(=Pg(wY24{6B3U#{Uy@yzu|T98df|@jSbKjsK_lFI$@t{68`E zfbsvti5rv%3T)90n4Ei?Fk;$q9w!~YZG*Wv$(>nz_7 z|4&T4-w&HVDA4^g@&fVybib_H{6hS{I3Ii8zY26en>;`KKi$u6YMv4NKXK#2^x*%+ zd2GdJ-oM`J8RP%y{&#up#AwSy|KnU^z90Ud?tfR;PKqY~r<=+D+j>P0Z=Y8@HtLvm zh;wPd%xG8bp@q6%UXV2W`m?|0k})w=(}v%Txaq|1Zw?e{shD z)AHrncK^lvKWFn*$o~`Lcj5nu@$vBg;*9?%#wWx7i!=V8nEW#QKe7BjvHU+V^?=F$ z6Sv#)C?b=9BzCt#4s^R`CDC^8ezD|0iaC@c-hB|0ia?Hs6xSXHP!g+nGQ7KlSH$ z;s1%*AN)Ttz9ashnEbfxKV9Ja1LObc{J{^y{}c0hApcLy{Nw+L8`9E)|0kv$|4&T* zBmSS5d`0{}G4o~qNum4_)@Oc-bCcC)#{W})^6l{d;*9?%#$Uz%6XS2;|HT>q&*#JZ zK>R;3`F;3*amN1>EB`OfabF8RFwV(7;Fq&P!T8$NO6 z;68nW|F`?W2ZR3?_Rsvk0q;E2@y__(MKJzfobmtS{LcMXcWQmqw|yzKn+MtaK6BSq z-rmD}o`2`;_x(G>_7DG0<0t=b@yTEB?9qI0@b$?5yX)P{o$-V4|J0xQpbM|K!q<=A zXMV7=HRBIE8wUSR>!%(q{-3k?cldweL(H$k{}baMlK&^}XZd;fe{m-NPvfIM{-2ob z;s1&87xDj`?Q~3S_=>O3;sK*GUbv{6ZT$FuE3)qi{vYeZ{}Yp6i2oO7{J#q;ZVvt* zd1?56V$L7@KQZUe(xY~F=8wN6_+`f&b4;{)#m>&xTW<<}+pzw9qJ>*`I3HslC;UGx zZ{?_?Xmc7ed^Sy5&oan4^#g) z&M&O%=B)9fqoTLY^7ct542o|4)5gwAM%>nM&J+JBoHB4g^ug41K7T`OK1y=eI+M?N zb@>|SUIUJd-fda!jDK0QdX;m3%Qw7Y>q_UL=Ck4d>G%vAHZ01!Y`OE8p~IrfzPZeK z^pK&^+uvR4j315vr};YJ=wpKar_VEafM5IA>iHhL9`rFE^Jnj#>WqJi|EKnzeUA+O zpE#}GF`@pi)|c7;*y!GtO@6&N*4k66PH{f+urB{k^Nrs}{a-PDGyb2L^A-P3OgsLc z_DBAoc&6p0;{S<n!ujR)(8Kr((Yg2{~htSy5Rp+FSYwy zpZ~g}B)2a3efR-$fBK>`?`z}#sh#)5@&CjXc7GNBPh4yFGx7i8jQ=N|Z_fkp|HRey zya4}C%>8rxKQZ-x@&Cl+$Nl9mKX&GRKmMQExu1{!C+7YT{-3zO>JQ@oiL>qb+pK>- zMDYJKKPguK>8tyn@OGZRWv=dY&amg5__iiuTz5rb{f;jGPfYz){6F#hJ*C0_6H`BW%x!JnUSs|i{-4^(Kg9owGyb2L z`snz7;tHz=h5simvG?Qg|HQ?1zZ?HgO#UjaS)BQ|xY(}Ok{M%FSp5^V;yUL@-HfA|j?I??$|8a)*FS5@&{-2hI@&ClL%~!+! z6Bpa(8UIhr=Ntb|j4z7+C$8CP`6=fAiEDSw3I3nB-uyxG|HNDm@c+d4d((=B`uNK% ze+K_g`=4*0cl^INB5AzG0 z=h=Ah|I}W+qbT@);u_2EG=HJPo^c1iZ?Vmf`3(oeJdefy6BnGE74rYY`6p!t|4*E? zH24+XA0Gt&PwhF&EFa1IKXI<*$>RTsv&}ch|I_$pt<1&$aK;bA|5H0Y7ye(I@&B|w z`s4qJr(51F{+~G2{CWI8arUY%|4%&2d=vaXG20{mPmI5Y|0kv$|4+>J@&Cj*wtoCS zjTgrMi!=V87~ci|PfUOOzc}OniRn-NpUw{$|4;4H*3Jn2pE%u)C;p!p{{;U}%ftA8 zYM1{f=I?{`_5S4d;s0s*4D)gD|HSx*)c+NynE#0Xr}Z&^_&ul&u*yhLipkL>V zzh>i4U^|~5(|EhuFLh@9)<1!{r=$L?-`aD<%KsDN58C>@{a~J8p4!JONyVpe9%uDK z@&D95)#|Mth)&Pb{J~>RzSJ3i3;$3389)A?n0EX>ak@RT3#9cpV|wSq}zOc z=FIiNj&Hu&VcTD4zF*tQDV-{68`Eit+!%_;2`sakhUu7nl!7{-4_OE&mSx zPmDiE{$HH&|HRZUCjT$a_;|HOR$@c%Sk{$Ak!iE}pQ2meo; zX}{m_|HRq${mRaNXY%Lq|I|)iHU6Kjr{wdJ|0k}p@5ki-sXzI=)c+NeuZRC9=JyHy zpSaS#U*P|V@ze1C;*9?%uC;ow_PyP$45Sz zWve-Je**tc^G`k({+}2>5&tjF_yI=3;2mQZI+I_%Y~>a z|8%@sEf1UgKXHrYW#j*e>+Sm|{-2oqc>F(cz5V{f{}Z#n_T% zg1NQT!S8Fg@m*bam-8|^U-19b&V2po{qGiBzIA@^>$snHD>ujyXhWh z?yuqhX?^%}_Lm2Y58V5e)xZ4d`R;D z#N6M-{}WfOoDuv#af5yT?)%YCeEm)K_xTUQpL3=j^JC>db#7jt8(qHjXU^1r-tf)m z6Bz$b`;YI3|0m{r#s3pG*!lci#jl+4MZdG{MdyVZ3!>dO{@S_K{MLr&e&bAiXZ$~{ zuioBwBL7d^WWQhW|HKW;vV;F8roIaPpSWgum;WbT*q#>rKXFs*wBY}VD;G=({-3zs zzOVgo#~*xsZB`HX8{dA*d7@sKMHjJtlHjR8TG(F6S)2Dj|z0Zyvpup zZusNJ1-ido*OnSRaqK6~O-tx*uL$KQ^kqG%6IA)lLuopYD$rl}`-$f4cuYw=gaEf8wH9iS;V+tMLEi3*ckn z|B3Ob@c+c}|HR}y;s1%rFB^CNszUh&PP`}Qy&=rPwi!yUH)I3ssAeu{?&`? z6Bz$b?ImeeU)B7-IOG3`=VoMw{6CGa)ciF3Kk@90tlni>2*t*>@kdhq|mnN|;&{68`4$Nv-0 zPE8B`U!3v(oNfQ^{N=g6J@%LSzuG>>hx)%_{JzbL&UfZ~y#IIIjGy%H_kB<3>weM zx0z30+bPEXdOYpA&VPOT{@??`uYB)XXMCGaCUrBu4*s8($6v(%6Zf>dyX=nrzWvB} z*8D3wUv0Q2_>7VD$Nv*k9~A#Dqvr15|H1fwV*Ek;KlNvQpIiN3G5*^H1>KAfc--Tc zdAsR-(RXGg@{EVR=It!sk)Fs^_g?Dl_;xQ(Ph{%<#S4=)3^?$|qge$8OxzF0OI_n1AW`5Iu3wxTNx9Z(}&V4PP@QH`d>|8bO z){cKq{JfCk{ak)GQ9sZCr%xFeDMFoLxvp}{6Fytg9irxPdxlYW6S^BGwk8u z|BV~j<^PE%jv5mDKk;Pq0rCIDBPMkDf8sGyQiA`d^-rEWIrx9#loY$4ZT_D)Cp9Jb zf8wz={*HoeozsrKtK-RMdlZcx)IS=0=6av6fp)p+fAKnJ&iBKvUF+QYsD9BWx2$od z9{IcXt#%$baA5HNG~Y)LIWhQu;(^141piMwcP#Le{+~YoL+tqB|B3m$<({^sv(K*{2!1f*fB586opbvQ3jUwkGkf+A{-2n9 zK>R=PQ9XNw{6EbnpKts>@!@@X1^-XX^%Vb4JkWgR(N_OgoZhQf$p6#vO|j1#{-1c% zh_TUu%Vu>xF!=J|>+RTfTJ+;bvz@n^KlZD)vYb!avO9XcUpJq!d2jURj7)Eb@&B~G z?WgVu{-1cqmM;HKym`mI;Qz%L|4%IcFV6UX;$`Lo;{S=4n?HyDC*EfHd-#8G#{UzO zABg`qMzJK=kgm&`(;_Jiz z6Yo0c|NZMLUl0Bt`GNR<;**TY|BEyEe`5K6alZGTqdGU&T+y+k<9CJlfO}8q=94Y& zFZ&yR=s4~`UGV)j?KA(-^8dsQD_2Lgr~R&@p?_WQ`_fj{M32sW!+BJFezYy+wT|JL zwZZSJTR1Zs`PnPZ^=+2_ZT_Fy%NJR`oB4kWFQ^Ir-@LXN!T-DJmFnRC)h(VJ{6Fy$ z^NsNT#N1!S{}a!(`@i^qV(w?+|B1PuiT@|AvirCAe`0(<{6BI1cJour|BEyJpP2eK z_^~{srzR;d$s;$!T-~ImYgy-_xu2>lkv^qt4{H%`vxJ#~a@9tw;QP zVEg!g75nRh4_IhE<*_N-A^~8e-yyBtJx(hCoZo%Hu!(y>D5Dm|0kYVH$3=%V(!oFe)=lkexp5a#{W}0e#IBB zUE$l$vU)T4e>XJDPw@ZZjQ=ODHeUq)PrT6Ti{k%@@u%?r;*9?%mj5S~|0m}7;{U}t zHMRk40IM1{C*Vq1Nq;t9TfBWp=&Se`iga4=bgYp03Y|rO?yp>k}+@9Y% z&$j0`_I$s?YS0CrugIRy*zm6XUm#{}*TcKQTTF{+}411^-W+XTAvjpE$?Hi~lDke+vIk#|t0L{2gy+`}Vxn z8Gj!CPyN|G{-3zZhda-i{44xFeLi9QKlLv#w&(HAbIjkv|MPbHK488;0-Jx3z~uj_ zf4+TxvuC}|>2|)GU*$Z*zCYprX*?6mZ#N&r+b6B<^8d6x_6Pq@%>LT>@66vX{6DqB z_T0)smQ~CTj&#>o}_B zF?pf*f8sp5-r)a<`8`7ZU!3jp>s)R=g#CR;VEjMz=Y1ypKQZq+;s1$Qp8CJy(zRXw zpO|+1KXHZm82Eo;)`$Nmrv5DcpSWO4MezT`vn_8A|4+xOerILy|HO4WDuVwfE;s)P z|4+>OEO!1om)iGV{6DqNvG2>PPa5Q0Zh6|nzk6H)E!T%GNn=gm|C&ur?|BEyJpXQVLviN^u@`#&9 zWfgo>S=`Zn>E(sIKQ^F!mNS3f@c+~we*^zdjK6{ZC(d4Pc~<8CiF57y75<-?d?@@s zjjzh`sPO;9?C-)`suI}#UOLYYV4;_w{|N8l3t5j{m3i@%iO+j;RBb@o2YInFhw*F?ELKR1ER&vst0yDs>D z+J2kmC*uE!Tee%h0rUUjjQ^+er)_I#@c-hB|0m}D6#k#M*81cBIotgZ{6DRq`y=>& zV*EDzKlO+4|KePH@s-{m{|*07%P+FuU-*Aw#*6d3}6E|2sI{u%y-NujqCthIh z-{Sv?EA8{Xpo@)>HGv}TETEDC>Yq`R;_CCGL zdC$Ji{oIqLEkK7g;@f{6BHYGV^uK{}ba6;{S;o%@@S~6EC#)pZI^``Ny{U zf8rVTz6}3QJl)m@|4%$)$<*Ng#hLs+@htm&i2oO7^8ds$?fIJgKXJ4D-XQ<4ji(0x zPrSgk5C2a*e{oLm|HL!rrv?8{++fe=)!%;N{cG*}k6}YTbEaM}{-3Tl{5||XaZ~-6 zXxBA=Nn-pzU9Z&Z-S*2boSDAv;lH(A-ZPmKRW{+}4X3;$1yPxYAje{shD6XTEJ|HT>qFV3%gu{w$I|Fpi7Z2si` ziBl|p5C2ch`h47JecSZL$9CV~O#NB>KlO+4|FrzfN%lRI`F~=3I{ZKNhw=Z!xl>#7 z|HSx-_zFlD=xMC9P1+ivp@0w#GIex|B3NqKfm;>T=^j!@A-$H z?acZ5>J@EVZ~kLZ-*ddZY06aUM>=zTS$#=o{5A7WobmVY|Fk@OTk}_(@fpo;ai$&r zPwPuN{+}3M3;$1y--Z9D{SV{+iShIB|HSxn_yn`C9mYt1h^wwH~nT zAN)Tt)8qe%@e%R=G(GiY@&CjJbZGVev_6s5L&g8=QE_Lh|7VQ{~KrgKkX0N@&Cl~|Kg1Qml*c5B>zv` z)qJYQ*PQC@9Dn@33)623J|OzUp@U{IeZyW?3ckNo(H;P)NUt6TKKDQ7y9 zSBL+n_F?@8g#16T{6De$KQZ-R$^R3N7%?Im-q^-tM~n>qpVn`}XnUV+{+~E~^vK}< ziAS4{moWeD{lk79{6F&ZcD=l=C9T(<#IOVQ$?LM8yce84weTi>$V$Bq9d?q*j4y$?wG+NqjguLIiI@eZ1w-d8%}7=|BEyJ zpO|{U_CKne&q4t|B1=_BmeLDw=W9*A3h`gpLnVHj`)A# zV=Ye*|4+Q!nEbyuf+%4kw1w4CqC)aGozC}{4g=C* z68}%r^ZhpdpP2Cj{68`EWAXpQybm3);W?il-w$^xe%6`#dH8?oPdz#OKQVbC^`q;8A6R1Jd-#81>i=EPbf0svjlVq7|6XUlhyL`BcRM#)z15!g z-sQ}AN6yweof~ZY0{?HxZ|j0jShv^z6O#vr|L1Ie5dL4B@&Cl+W#IqC8UIgQY2zn9 zdFdu!KK$#;Z*;~7{KwHZI5*h%#(;6xJ6G8FM8!APIcKcM3I3n<4|yy2f8r7K!=e|b zU+p}tvS0B3v_7d7eS`le9#K0u_{(ly7%}Pc++rKQJNxzHoyoUb@&4Mx;65dZeaGz1 z&9U>p?5kCYE1oDyygzhTZvN8A!T5|8gde(&~dblV4}~A>vC;t$)t)R{u|&b?n68|A`qt#s3qhTfHLu zKXKOb-00|vMwtr|pID|HMV+PvZZH^UT-7{}X4M&xrpgCNGWrzc^dHN?#t=AO4@# z7q;>H#1l*NgWp5`AO4@1`hGV4@67s`AK+YI>vPZFJ11-mJNSOo56Ax#k2jwk|4)ox zf&VAYvimdne`50D@c+d4CFK8!saI-#gfspU^?%i#ws1=D|Kg1QC&o{~{}Ye2d?fro zG5!<&pP2h4{-1c{f>!@eJj&*W|0l*j!v7PGw|oWsKQVqH`G4YRi(2#l#Q1jje`0(* z{6De$zc}OniSf_y|HPS##|QsUO#NZ=bG)5=K>RNcZs+Ht+Fu+${6BG~`K0)NV*EDzKTWUvKXHor zQ22jw#{UzO4~G9I&bB-~{68_iAO2sQZT*uN|1Y`y0_RpAuzM2QPduxs+IoM$FSPk( zCi4Z(jVE!%=Ll)r~O0z8vb9L@&Cm5dH8=~{8s!wG5#+8pIG^S zS{`}P_Kv!6H_19&M#-`8RP${J!78TFD(C0oMwI={-2n9 zK=S|MjQ=N|I(wqsuNG!&``~}~T;`0Q`R;-1lGygAGxxVwzCSgI@&7bG+VTIyDRU>{ ze>ih~*!>}i$^Y~IcK+i3i6`6r4*yTg{TcsHoMFcw|4&R_&)SqbvNL<+1)mE3!=8Jb z@rUvM)IZmrhw%Tz^8duSR=@p@olp7n z6Bpa_9R8n}=TrPYah>^T_@uGPs|5d$Tj!WApszE(pYi`RJ&gYsXY&8VR-Mr zE%<+8^2DsK_n&CL*UTk!p0qO8&fg+u{yyUWY5NLnd+`6nJU`?AiCJI#KQYgD_Sx!@@$GA{Jihtw&r4$bKlSJL8vdVnhJDY5 z|0kZgxi0vB;@Mjpg8wI;x1}cdf8seORR#Y~+-!ay`G4YBTWf; zA7%N5`EAADw=MGxduT*I(&;l)YcW|I_>z+Vb)L#C)HM|EKqTHJ1O3|EKo}jf-0SKmDF> zw)a=~fBOAiW8a_R|B36(f5QJudA6)I&(HGR@c+ck_I_;0q}y_i>sJ>1I_@Vw%)Z^3 z_fNmseup#u<861`>5Tul^GeoZGROneao5o^}pzC=jk^6*AKtre3bdD z_L26(iCI4WpLm9?@64lr@6+SQPCWMm=O+7mhX1GjbM1R5^8duM?e`}6f8u6) zKE(eMPq*)B@c+aORv#GuPuExN%t^uj6E|2rVEjLEZQYoV|EKGPva$m2noykY+T=I=`^TN!K|EKreP4n$|Z2B%o++fek zPwe^Lx!%6-!T;0v2K9l5e)!)c#{bj%?~3NhQJ+!!IOkT54E2BYKD?x0Y}D!54!LoT z`w!%Ik^fh-*GGWy|HSwo_X=yeiHs)obmtU7m(ja{+}2>iu^w@ei{B>obms} z73QPi|B0!Oi~kpA{J%Kk|B1;j#Q%%)^nV@aoI81H^v?HdoblP_cUb3)Z-)P;>4TqU z{-2n7uAlch-nn|*_~8GkJ$wAv;Qxv72~Qfe$@{asXyS>^tPlBr+Mnbb;{S=sFU0>7 zOiJ3q7f6h}{{XcPTN~`}TX8rL0w0^l0#|QsUOnqqlKQZ&i{}bcC;s0rV@L@f- zJEu*Z6#PH+&zRQg|B3TbCr86y*zWU#@&DA$_Wj|%+jHexz|E)ba86H6iJsl}3}@zV z^?95*{&#fR>CE{v_?$K_OtJ4fyPoOo1(T)(|4+-OKmMPX^B4b5>%;!R{}Z!+@c+at zAOBC>VAl`+pP1_j|4)n$i2vt2H9h!$;`(Ws!T%Fee;fZV&gQ>3bNyOAmh*J;)6Ac7 zrrs?6pN=2-bNGK^`F~>he`50d$o~_!&+}{V`?crxeqMVYaAr6P7*5xM8?|=D)?ftj*`GVa4;`h_`K3;oY@P9G+s`2@?Uw(UEkNn1X|LW9< zNn9{BIq#MGd%S=9`Tzgr_P$?xKCoA^Z?{j^M}6We zmS5E(?!14i|EK;P&8Nfvi!=V8=8vyeZ2q5^da(F^VthgTzfU*c75qOK|1Zw?e`0(? z{69@^`d{$>;!OQtF@6~Jf3pP2cZ|LoJl_qPi%*e zd{&F>2Xl-|1^DvgIoPSG3VzmFF4ufzklZr(QmKV>fHB${iDxs*y230=fT1Md;h_E zTK&Hx`UL+^Odj3s=bzQ`&4>2}-|x`=eS`le?$-OT;QxuI9@6Uni8Fd19{fKsd4Saa z6^|I)H{}0`M-Cbs{J%Kk|A{9I85aCMtsngDHK(=w_r|+}4>xl3kSO(tHXb%&VDSIW z?|Vz|{|*^&ShOpDLyMUE3I5+_{ca9EU@xmbUi{V?=RS7*9D-`-J>IUGL*Nw$}d@rqPkh{_R{t-~kD zi!=FuV)=h@#{Y9RzmNLAamN4C`W&}qNAUmRO#NT=CvOn{FV6UXasK1(q0ZzLzTPs# znY=^%zw1X_82rFRd;LH0^36Mf|0iCt<&04OSA62uGotRjK2H2MuPXR{CtJN={6Fz= z+qOmzcqW%iV)^Uc3Yba=8N_^xf^SP|0k|nUlaU4arK(Y;Qxv7`SAb5#VfLc z|0k|Ap9cR=TxNM(Q{H&Qxz5J7@&9yuN@tG@{+~E~!LaE2_aF53!etYpwWSaG`B1$i zBkKK|2mE}guzFeBue;xw@xX`oy+85fpR0l&SaGz~qkZ{4=P8TLf4uTu=Zxi(ga7wk zqB{73jW%A0|0kYj#{>UQTyO7V@&Dqyy!4JF-gWTp&W+~t{qo&gov9c4`At7}uC({F z_L1i2o-p zvHZBV{&h~` zqSqa}bBoPy`OS|Tobh8;nE!X&3x&b|!;i%O`(#r=@c**yeKPrf17FS${$GaG52gO^ zoMHLF|EpU(A^3mPz{USN+O`M(4<`=)FXyC+2>(xD= z`S1T7?#%wkd~B$5v7Jx&f7*ZKCF1{y(=8vS*SGz=|EQHyqxttA={&}KDf~YzkNsi! zJc%wNbA#^(5 z;s1#TSiMgCKe7BjvHU+V{tNkkVxA}P|HSx5_zv0e`fV9 zAJhJaEg#Mqzl{7p^@s8Q#Q1{ve`4x|n}3tU_~=8ylU^`U+){-1cf zjfdg?iFrQ3{}Xe);s1%r-^BkDQ%?;4Pt5%h|1Zwwhxz(&|8E>$lf?Lc>d*Cw|0gb7 znTmhq%=wQ0r*;_sPn>7ZANYT9w)5Ya{e}Ohb{PLp`>V+6kKzA`3+;IY|4*ELOsoH= z>3QBG|4)p+iT@|gK8F0h3!HgA#s5<~jQ=O*c;o-Y+1B5g>j(c&?deBTANT_2z4dOB zn0FrP&-rWf%M|mxZPO<){$Fx?_bf5%XFg4q_6LmrCuV){|Kg1Q=WOG1_Q3;!?9_d)~wuka>s$N&59!+V^0KD~L@ z?b(lx&Q4Suba8IA-Ou`TzQ>vSVe_B|yg&Tx<&QY?dnvQWnHzD%-{b@ zHooZnOU&;(;EPwC`MtMk$#0#>d;9b6-f`yl9R8oS55ME(=RfxL2K#$nQ20k@e3bhh z{@i)KeLprL2gLu={N?|NE6iuX z{}Yp+H)i$39GxH3r~Jd76lcCyx%!hS&O9&T|EWKW{}<wTctDkjCMb9CV#xk z$~xyl^U0pv)8I_L{Fcv}oXMBB`;T+8<(dEW=vmH6W3e5xZSUu z@%>(&b+q#=%j-LH_hM)2_mcmo;|JUGfiwOc`G0DM$^R4M0}grNIG^9_6DzqNI+O2r zY3YU}uG+EDx#6UeX#XcSC9&N<+t~cZjX7JBc*2%boSUrupTFCd#CE@RuD9PqxAi&Q zxo(ry=Y8^YKmL55cK(Oko%ue^?$6$z>%ZTwoz8RYeu4j|{XN&7zw!UX^X&N>|4&SP zUi`l}b^MN*N5*v#~pNG5+6AFB4_F+d|G;O6661Ae)!94I$h>m zXTK-#|I|Ly{8s$GIOG3`saK2tCthHF82+Ca{|x_6=L3xYC$2j#KN@uIHO{5>_XGb= z?-yn*o*MH1^m`x1|I_b%{J*6|dvf&qzG`uL@c+c*L05LXH7D_Gaq#_8&8Ncu6O$*1 z|0kYqei{CsnEi|YC$3&!6#PGD%g3A7;T~_VF#juc?7hzTSKXWMbDm@CkN>CX@v-p# z#N@%@|B3M($^R42GT#jUPh7Y>FZh4r@->#%X#Ss=d`0{}ajAX3hyN$W_rw2-Gyb2L z{e%A}t}{Ok|4&?R-;;iN?NiRx^T$SsXPDJj>t1{}Wd(v+wuJ{}Y!TlNJ0wajkt%jsGXEUfk;cIot0G z{J%Kk|A}jsWCi~(&iH>~eqZ7LiFuyE{}bc;;s1%}Tizu8pLoSmdp`NYyUt7P{oKvn z-g9oSJj`ur?>jeIK05xNrssUe{}c1R_Q3l;bZ%IZ8T>!(Zy5hi+;miCg#Rb5w|u}A z^FD2x-tzPccYfwvZ+U=kZ2D7Mf6MQ?{f0j~S2vA~Zh!7`zdmcNUhuEJ{;PAn3Xhj8WsFMUGFpPeP-$({*j~i@A!Mwhy2TVx}8t>e|q2DWbZo{Zv57HhJC+>|EKrc zm6jKX|0gaspRxD5KR8#Urf+&iFyQuRGegF*_^jd-Eb^e3$EP zU+k>>Kh3Xc?D*jSiR(v=3I3mWn$>&5{}ZQ=vwF#nv@#FCS#MIx#{}WRm7ynOw2EHNwU!2b?+~WP~ZU6MF*qX$b*PWcieP^8F+-P}p zua4j59Huw_Ps^`0f06pX;_~sW`F~=3O#DAF?R{I?nC)FqaJsiMKl1<7zsa_b{68^1 zAO4@1`nULhamN3Xk0Jk0JbCKG;QxtJ(^~yMG3N{ZpP2Ir|4)p6ivK63zH!G3+nD2h zV$ZX@o#Ti9r~c$O;{S>97xDkZ{^Yyi|B1x9{Jc@sr}~cR-h9f3JNWVEcN&9op3k-mhzN{$Kn0z=w8E&iiZc|Mlq6BWZoe zKZ~#5fP)VT{$FCo?ZN+3{$JnH+dTiT%U`c**_?W7@c$06`k45C;vSa&cl>@=w!D_{ z^KkuA-}Q;pu5doU3bN*Ze1-SNZ#!`Ml`We80peVZp@dF3tU)iGd!LKWL{&H_8 zZ!jurV=GS_J@(XYZ|`F5oAcY)^swmGmoH0NKKXxIf7S>8PmDiD{aZ)bk^f0`eR|0iaC_|Kf8vhaTKzvUd4TwTV)8BV|HOxM>m2+)@xUVw5B}d3*W4BS zzlnYN2menzx!<7R|4n}C?j-*&&gB1z2OrrtxkG&)Kz=OJU ziVpmEZHstF*H-^eJiJ?%;QwiV47Pg0<3>mKI? z|8Il&fcSsnH5*#}Kk+dew+8=De60C;_R=Py1n^-amN1>Z!+JI z{68%p#{Ux^Z+;*7e{shD)ASp+w)%f!^7!!o#H-97#Qzho*z5m^mz}gd_f8f0I&HHr}DRncRno%zF)C1 z{-3yTQAY6p#JLMnga0QUZS~2>{}WHK_bd2+V)7*L|HQ>sj{^TsT(!C+_>)B@$hvt?9zp31OmBOo@amHW4|5JbRnehL_jECU=i5V}#{}Y$n_uIQ?J?UIw z-$$Q1`U&R-s}Dl{pY~U+eGg3iUom+L_-0oeZS(`|-)iFyU*6zM z9^mSSuXnDo@s_uD{M5P1#yg7YuXD~`o)z8M_gd$|rMc0Of4tgxLgSd=|7rO{EYA=B zPdv)%&*A@x$pgf|EJ?W*8Cju z|8zY}oHH)?f8s35XZqXV^AfeYi-Yec|4&?hQc>{##Ef6z|B1<`!~YY@|BEyJpBVpY z{l@Kyv%V|}eqWi5zs{{V-I=_T`z|>(@mjy4R=>~q-D9`4v0Xon*KbX9-B=jj|5w=c zi~m>hQbF+l$k)XGJ8gJD@c*c9i~lEP{2Kr7(UbFo{|Dp$O`MPy{J->LTm8S~J9C5o zmumhA{@+dZiuR%Ym*rNQ|N6uIixa<}mJ|HHg(u_%{|^Ta|F6`>r||#8Wi}p$|0kCJ zC&u@~{}VGlh5sk6-|PR0nf~nG*Lyqs`qj10%n$!h{W(7Pf8r{;{_y|AmF6$v|A{$1 z_>#m4{e|HRb$rT(wxH__^g z(xSNuP5&bln>BRUt@^<-_%Ip!0Zf91^b%?EK#v+LXZ66Y~C-e5stq*yE_T%=yLt)Sv6o+B3ymuQt6i z%d`0>vGvbVfAVYb|HQ5RXCyKHpW3q*Or#Q1OaZ)f~P{6DqB_~TP zJ$`*g;)gvK<&wwv@}S$D@d1l2zT27ObHUd8eR{aVR}VXrAH8vLi!;{;`G4Afd{06C zpP0Y@_DU{Ij`Dzjwwz!~auzgWaF-|HL!QcftP?lYh5% z_TPMc$*=q5#eX{2+4QsW|DD7y-uIs*9(d?JIokjHUVEo{-y~k~{-2J2y&Yftzc}0d*_rycW&L(K~)(`(r z%=;4jKdm46gZO`9>doT+iMihK|HRy1@&Cj#&CkaFi!=V87{BbwUtZH`-A@{=JzH3pBSGD|1Zwu|B1<$!~YW(nm>>KC#JqC{-3zco*(f4#Etg6 zfd40Muf&75qPO-Lcuh{}VUc z-&_2@IOG3`>+Sam{-2odiShr$wdRB2|B0(-PY(W{n0heyf8t8}KK!_T&p7k`7ynP~ zF#eyI=L!5japAI7|4&T*9{!(L`F~=*Psjfg*O*_o=D}Bdf7RIWDgW@*Bp%fHb>}+k z|6R&&oO!?f`kXhMtL^(D{6EdV-s+{`|B2=QiD%gPkN+p0fAo~#|HT>qPdvl+$Kxly z=gXUJzh|$w{(WcOr{n*rKj$Om0pbpR*t>+PwA~=ebrd_@e8+b>{jz=*{nP z^gg`I@&}LZ_=9t;`H06I^xqu4|Ey^mAN)VP|1O(uzi+OOa>W^?BZB{@_uc6^6GQ%= z-e+g#r3C*^+&&MgDtB7&|1{o>&w>9Zt~Y-L|4)q1ga0SSpCbQHTsCH6@c+c6qbCIa zPdstV*x>((@!#5u;>W`6j8V)Ebc|HP^0 z%i;ft(*5f8x1W z_WgwUf8v=ofAed6|2OAm1piOx8+m~Ee`5K6V)Fj*|HN!h+^4F}OZL^;-*4LcfbHwk zR^}x8Z8iDH`FN~fe0lA;F(H>;hGI6E_WecStc?ft*@zF+(NzxF<1d;bp~ zIllhwnfpz=JtsZ6-Y~}_-j1&s=l`{S?eiMj_y1qp-`@9Y&z%lU_VGG&OU~=-VZKRx zeY=^T73T<{E#`yn*VzhS#`u7q?dl63l3YI+Unk!G|KT3V{SWEZDfoZKm);uuKk64# z|F@_4eCO{zAdmXP_b=VmQas^?kRL`~;YWYE%z3{9_KBYBdPU2P!*5P}J#xQ1^7lSF z_wpp(@1QouKbw1s<@HUuCHR7Y-@m-&uCaT9UkLwkP8-Yr)B1E^|Cs+5XZ$~LH_PL~ z{}XpLKj(yhT)!q5LT_h!{6F=FANcZuB*y>K{Mn!Qe`0*g zZHvzL{_MZizdz5J{dZ^j`7LiY-4^^S_TP*5otMOanb5{8AOEk%#%qKB2jl;V**^R~ zaVN`n#Qzf?(Dk6`$bW5X*=P23!B^|ly<4dNt9J6~@c-gW{oftG_(`b$JIH)1>i>#I zAJI4Xf77?$5&XZRenW!)C(b^sZ}9()``Mkr{~OTzh>-s$#_yYR&CV9}?>}-_^z7kn zJb3J=kpHLtQ|)^X^8dsWhYk<YknL4pZ0HO^Cj{B#Q4J{k1S8(J5M;)_c#9E z)2A+V=KfM$u%u<+#n%Kskb1zstX}Ml4>)bsBIhCfdk6n-;}us2UyyvnbDx{<#|wY* zgSX~6kM4g&H086o&ZCYzEckyq9|s@WJ>>t1$u~Xi<>UPP>}`3eiKkaPkFgUN|L^Y` zZx24@2)kR}mbcoO^Ly0PRnDCcJRthnsFlu{R;_C(dij51`G4XS<_F^ciK*vH{-2oo!imoYCo%qC-IM1AA8@((hxmVS#{Uzau;t9) z|E;^BB=~>pH*F98pLp`t4Z;7r^*_bI|BK3Uga0SaGam^5Ph4T&8{+?o`JV8a^WIK; zI-@xFe)9jsMfN@l|L^uQi<105G4ChH{}WF)ABy}xagL4u;{S>9{qX<9ysyLm6XT2E z|B0*2@7X!*g~X>H6$ZZ#Uh~a!ZEWu|@&DA$cnAKUxW@9p@c%TwYO805|0kv$|1Zw? ze`5S1{68_{8Tfxf+%4i5Wk^|GRZvY4HCtkGA)b>GwI$m@_DP zYX5tkmsq|a{@ z|BEyJpEz%QM)3c{1;=Lv|4&RF2mW82@&Cm5fcSq}Ul{*SOnus`CtvT|M}68((NCRo zPAHGozi_Sd7#r`#|I_rD_C68+Pdu`ASaim{KXD#rd4FG>e3f&Wz2BZ!aiw#r#}wEBC-4}Z7QnY@VWUpga+&%S<# zGkFX6f0~~9M&~3>OALM{zt#6MerM>ZiMfOGTm3$}KI;3NlDKS3Uhw-EAHC+8EzXtp zz8n8f?U{Bxn@&CTOA}jcR~d_eraIOG3`$#2B}6LbFK|HT>qFV6UXV)9+^ z|HOMD@&Cj;Z{Yv=@vwUL_Ph4(3 zJ^r7TUuxsW_rC&pjK{}YpMYGc99nU=?k|EKme`+JH1C!S`$G5()8-M*JF zUnPm{{CDR1!TBGFKW%J2x%p|%Y4-QT{59uP^C9hcIj7k3 zrTK5p)IT;K!I``*+ds}cZ{q)H`IY9c*!nx;|JwRIqV~y_kB0vz#xJ%0No+qMBehds z-P$vg`2y!$8;`X4J2T#G{j=1c^B4aw&bI!}jDO?*sh#gl%sSvH>gN#2b~jQ^+U$$!NEi!=V8 z7=QDj4)-VV`1KDvQ~&pdj}uA!=Qp49_06z)^Ybg8aprmKwZsd~Twf(AuO{)sH@)G^ z^TW6!-f`x8lL>o^)4w=ZSe_vMpU#h}wHd+x6O+e> z|0gcA`QiVG$=}8Q6XOr!|A}kNN3`=fN9Qx`_kWSi|4&T+3H=8+SC~JD|EG4g|MiYT ze17CXpI11{neQv`|I{D0>(SfEZ^Zx8_To3<|B1`(c?ADYTx{RB;s1#zEVJ(^3a9w? zPg*g>eAHBD?pL<&oynK9>%EQ5U&8;>{P;b)adB>2yB$ybKOMhv`@M(%C$6%;ANYT9 z#{Y|R?;RD+{C;^YQRQ4?z8U_Xme21U{68^y-S~fT#{U!Z`vCth&iH@g2K)XB|4&SR z{6BH6<@w?NiR%ZCRZ{zjSW`AFP z!OOmV91r|I?XPn4&G7%kC9@_(_PyOr6|NG}V ze{!yF9v{89-(Q?-nnniyZ`R)Te|62Hga4=ZgY`2;2menz+rBr!|I_9&%Y!ukPds7Tl;Hn~ z@!|0Q;*9?%uAMR^`tjeV=gJ4+c&**C-I?{r|5H0m{a-QlSE>IS=Tjfwkt_cMA8Sg% z8P51lpFP>et++1<~z@j~1F#Z_l{`>ZsppZ!uBlfQ=l zr}dd(d4BkRV%7)$PfUGX{68_vBmYm_oR=H?Kk*E^e(?X|jQ^+gpOu#%{6F!W0-onD zXlpm05dTldV@6&k{*7~UZeH;JbpFjLDh~O7;_AZU;Qxusa_o6B=4bscKdrs5*1rF& zoMgXmzHM)O{`I!}|BIUo3XUYU6`Cb&THo`Z8}nwB!EK=;PbC=l=T! z|4-ACABg`aMkmDo6XU1h|HT>qPb~j0&iH>~rpNz_GydNvgKrLgBklNq+P^UVpR@T# z_Ykzf!A{x#^h;yuFLnQ(afs z#@)>~waS)l?Y4vP|Fk^(K>R;3eqiNy=eKlUep~SCSl%P++nDvi|I0l4>fi(78{+?o zsqc*cCnk@M{6BHeo;`#ACqArukKq4_$)Cgj8~@ss!T%e4@S(x~6Q>Ls8vH-4ANh0L zQ_k}B9eMa6!T-DM%-e(i*XfAEqR)q(>FwPI_6z=>rpMRA{}YcLJ2v=#nm%RZkl_D` zCk`JJ{6F!S;RB=X|Jm--Q!n_WpP%0H`GQ-6k2cWi6F)e#jr$+oJNSQEUf*7ah5Enh z-}~U6A^%U@)9UBm+x1kR-$C6vM*lwQ6hB`3Sbit|->MbY1ix~>13L!)Pb~j0&fh<| z%=`E2-Z}Vx+W-A~bcxD#`mfwf}*LlxRf*&~Y@IKM4i;s4mIACz_ z|8%^_1H}ImbG-2X#Oa5(`hPnA(hlnt{6F!?9$ka~C+=^)HU6Ktx1FEgKe8%`r`@yC zxzm0fq7ApKaPHQ*Q*_rg%bhFDPyOqq%bW{re)xYM{BUOQ|5EIH#{U!73~u%R#4}2o zga0Q!ZSASS{~Pp+vx5J(e(l!a|Hb*egQm5J<^PH0|B08F4~YL4XZ$}gJ|F&HobmtS zjQ=NId%~%~{}U_!PfY$F{-2n7!1#X)SDhXFKm0!YKQTTa^?$|qbohU9#{Y{m{-1c` zNvDPSzj3a6Wu&*u|5LmCzc^F>H_qh$iShmL|Kg1QCuaHhe{nwTx&bXm%sMl%Hv64i zmVfK>{he9<8(;Tx-n8|s;Q#$PrzrS;$8Fda{6BH=%4356_v4j?!T%drnjic>G2`#} zf8uf*|HA(h^Zg|LU-~x%!T;m^4EcXz@+0v7P90qk{6CodKXHNif%t#oVjC~Q{}YoJ zf&V8iw(%nTKXLgos~30bONj^1$Pa#BrM+Lgrtw8*d_DX>wbz+{g8wJ3+3Wws8UIgA zJ-jiie(g+N!lAjpa+d$6^?~vK#P}@ue{shD6Ei>jKQYV0{}baQW?h|duCei+;j15W zCSRd@?xRVJ|EK+5Y4v9C|HKuR=Y#(zF0=71{6BHI&F`k$AMoQ#eH-%sbiORG_ub_G ziDz#p5B}e_F2%wBE3x-+_7B*F2dq9JC-{Hj zX7dB^|9;$D(poQgZ~mXSW`pIooBtPQ{68^%Ao+jd2HPLx|A}jDd zq2<@^_5b3Wvh)UD|El9Hf5QAfZC~Aqt^S|5`lPDh|B16~yc+*c^J9D%|4*Dcb5!vE z#N%d-2>zcq&A!LR{}Yq{ga4=b=iBvi*spf^@oBX0-|_!+yk^?>`1pUie$$ub1^-Xy z+ZfCHB>zw6Kkq|3)}5dD`$u`f_p7$?Zu0-c_yhZ#a!z7&ZeH;F8mxZOpBm0~F5X%a z{6DqB_f2Dti<1L-jz%JQT)H?+l=7x}LpSac-|4&RkFZ@68bgKu3{}*TcKQZHN_i?Mkr{z(99RE*D{ww~U7+=`(c@q7eo)-K**z$XvtIY4h|5H2r z-~1itJi8w7|I`lS|B3T${0{$5oMq#M_UE&!1#Y+d=~t_IOG3`<^RPQ|1Zw?e{r_;_vPa|+4?-9^@Z{O z)SvUw`X{y93pi?Aw&u@;{@pXxpXtrd%Tzn#+ctmaOgrCgepzbg{I}zg#O9Ycg=^J0qOX8L{k8$StZqI|qIn)1=D>gZk-dTuChEJ{6F6xcK^ixi!=UTobms}_<;C-V*J4a&bTex zzWKBFMHl75TmF8RGkzlepZen`;{S=MpN;<~&NH9>@TMo7Ils<*>etSkU;9jb!I|@O z<4vzPXW9AumtJo;bNwwm<89|$`}_OG*Y7#w16C~k$eG_iEpLA6Tx|J&Q_B95#Csn6 z(wRKd{-gex#Ft$0t#gJwzjW;UALlIleUkH7l%wtC_t&O>b#P|+c0T9me1>a&*)fSb zeSe^H;fB26|EYhG{T{*p6VJ5gDf~Y%{?L~n_H<_Z_8i&E8Gmi@^uwL`zT=DDeR6bt z!nZW_b)Ig|6ALfw?~HF~_h)DJ5B{H~&$aEr{}WSRwB(c#&h@sxCJ!0q%dawD>92Fg zIG3%?wR+Rzoby)|L^u)UPnxgn%=bTYf3?uL*8IC((IV$Y z^Y30xUy{V;HzzUvpSGuYYgO?7#QZ+N|BEyJpLmA(hWLMR#{YA+-zV2}JRynApLXW^ zCj3A3hw=Z!3pSNUJH9x@dA|8;_({jU zf8rYZz7PLTOui=mpSa4tC&B;I`pvfM4gXI(&wd}^|A{$&@c-hB|0iB(d6xKp;sy47 z3jUv%`o_LkYh)ALNzs+{2eiL34Rm_3hqd!zaKFATmV zN5Ajk8!PuXQ?K^q4L^4#FR=OQTb&zMWkwTzb(?d8`No~TyxqCp>H*;YY5uiV4+H;C zT)J>fbjh;2ovSUcnfyP!pQzmH|HT>qPt5yL{6BG(`GEL;;->jl57zuYEw6E2TJZnG z_q$iHptuBL7cZHGO>W|HPG+4@dr=nE8|cCoZw~Q}};k@&)n#;*9?%CZ7=h zPuoX6A^xAZbXKeX7iauGasKoX!T%HIGz<;?pE$K~Saj?5-+KRy8Ka^dx4-FJX3LxR z+qaT9^~blJYps4R^?!YRjq(39|H|3pga0Qkwf#r_pLkl+@ZkT6vuBSD{+}3sa!9|A zyg%m`{-2gtyq&-?Seu=#)DvgUEY{}WfwFyHInpXca( z9z1pE7tZ*9|El?0j^6*_|NW}$?>TzE*kE~+_zq+(`6y$)b1p6#5dC)C4>@}OSy<37>VE8hbM!uZO#Z-V$>l#LG5(+4 zpJrwai*nxBCs*%ROG+n3$FA<+JgYDx`p4HtuZBoepi!=V8v-xiL ze`0(%{6BHwG|S7(-t3HzhySPcvS}H?{}Y!?O$+{?v#lTgpO|{I_#{6BHS z)QsT&iHj`{ZTEwxdOJ-0U$wJ7_TU~C-eWrGqUr8|0gcZ%ntrvoGX95 z)BBTWhX1E_{4o4K@to}3;Qxu6ZGYhZIotI3f8tp-J^r5{4+O5VQq+`fN% z->-dMVta1yM>c0C=MA>^{qR%c+t=RzJFrW#@7I0*4$1x7@qy;6#pj2A5@-CV|BHKe zNpAmN+~dH`!T}-L+?zx5MX+O6FyIF7tN$zY{v`YB_tr4Xu75 ze%;Q?oV(fn!2dgL_>I92?BBIV@c+d94(cBKKk>eu4-EdFII`j1r~NDc&)Jrb|EJ@@`r!YG*2kcKp$6rnGVIL%K%4yW;|HhmRc9#`vVO zZ#duEyB)Z1bVa{5X8v#PKF`}>{J&$axhnX7F#ewy-w^*#+@(vG;Qxuq`@40=Dc&ys zPwn_-)c+L^>Sq4l4O^V23>p>uzvpXz9{fb|_3;11oqBc;{@)*$-x~bCeS3Bb{-4?p z9%%J`E&os4Z^Y2x|B3q!9}=ZqbcVMN9Xd4lf12OGfdivn+jn^TpguuG(J^t{vmS@e^Jv+ZsUhnR`qW7n^@nKyL3I3nj zsh>P$=E>f_bLY;{#pkVVnRN6uiO=h!Jle}HS>=omc=GraEjy08I`Pv!KjyN(?|$Lf zmbbS2B=~~|ckU7`ePgLJ_nUt2ACtrfT({Vd2kU#}&lfq57&s`Jbl=g=rGxDIw9N}! z{@HS6@C6I|4T!qzT;PoVx9#Hj&hr1XeFOR&8r?K=wO=ospQqNXa!xb<5&uv9%MLp< z!v7PG>SsQs`G4ZE1A9eZPFUvC&+FeOdVa*Q&UFWO4gTNM`klf5%eA~f{6Fz(`#z%l zxOC^EYGwxiPwm^+ZVvumYR5B!|F>rS$-(~kz$q1DTK+r#tdOqjYT8UIgQZ{sQW ze`5SK{6BGxjZfhJ#Toxk`=5L}{68^y7WjW+>R00biAz^b3I3msFaBihmizs9<2T~} z>HNVDS##HY&Y4#Kx6jGjxaHWm!;{S=MPf7k?zmme>|52Zk{68^y zV_DDK;ap?i-`{e{?asVkKXk!u&U~+r|2LyYQSb$qSUv;(pZI8de~$krW<2VveQx&k zVZ3VIOE)<)zV_=YZ**pS4gXK;Uuk|M{-2of7xMqa%KsCm+4uPGU4D(X^Zj`FlB=CF z?R_8lf7<@>vqlB~PdsVv*x>((%jb*@{-5UGVD%;O|8#uF@4^2QlLvzTr{gdvg~@r|I_sZm<7|4%$}TTS%& zvYm-v_RS7{U+LCL^J&jWV*Ed~S8S<_&e?Q&;=7Zwg6~&i^_=kk#EggH|4n*3Gx&du zmtLK7a$?1_%;5K>nUC<7FE%?*G=B;IPwhF2#zwE6xG{0VWf{TugYo~wY~Q^Htxdf9 zkM!XCQJ)Y0PfUH&OK)D0IHV!HwH~nfOZb1=yQS^*|623^9$7hUum6`H{6CyF{J*MA zmIr74pSbaq(vbfruCaPtKOZ_fF=kY1@Z0LQRZ(BkxnWyv@c+~w#{Uzu|M36B)1Q|HMp>|0k}n@kRVUG4;#H|BEyJpSaw7QT)F+v=}Kg%<7roJ-%pZZtt_5Z|-*W&+) zso#bFC(gC|CH`NW@&Ck=?E1j}6OS|B4F6A@Yk52Pf8q@DWAXpQ_owMxzi~pzTVf;UF?&))jpmVYL59X^l7uofV|L5~N zAwT$kakhM}M>T)ym0RAIbD90U$Ny9RQhOdVKP`#PUvnnE)BHAP>K&W^=FIhDew=f* zJulh*aUNqnv-x$-W9|D6{68%pKNSB@oN9SEHh$y~1m+*KvF#tLC+mz4)Ti@3&KZ^; zW_fQ(Z24`@_^oz)oTr)3Z^zG>dWrXr+duo1=OzcguhH@pukO~(S^l5e)9n6*|0k|6 z{|En1Tw=d3@c+bU2!@10yE~Uk;z{ zUmvVa;*TCW!I^qyOUt)8A|~ zZ?1Gsn`1s+-nGt?Ebph!?KdQ`cL&@b)S8Jhbfjhn%UG z{QGGMXP%duZ+yaer0xF~di>g%`rZXwpLZT<`A-l1>E$Gz(EJSeWMbvrr1n0`*%ej8r*#17-zICp! z`J3zH^Q$zU3I9*?FF!6X_aukruH{NBg^6H}iR|4+>G9sXY%+xV0Df8tv6tMLDv?fGW??`JrZPdDy}+0N8= z#s5?PIW~X%KXIi!Z{q)ntL*sU|A~42#Q%#k{-1b;o$vU6;+f_TlK&?r-yQ!?Jj?o< z5ADZmru}~S_-|{SXW9AJf7FIHw*L5k@#*pZ#4I2GPfWewj-9vq^z&`~^9xQ%V#`}i z>i?gKrzJ7|pXNs%A^u;SEuYnye8aUjo{_{gzuf8Eyrnw$f0};QDRsgB6VKRM7yLhQ z!zQlxbA5WQAN)VHToL@5{dh4NEa`gMYrfyL1|MY&K&hqH+|HL)+z61YHO#NN_KXJ{x ziNXJiGyb2L{Brz1alUoO2gvL`9F>>zr-%9{T;^KIclyEBpGO`<<)p`@xr{ zKH$7?aZd36G=G@IMeF0lK&^pZ5kc?KXIPbW4&z4 zbk`oD}>& zwZqi^6?4Ah|A`wckB|I6alIXX^8duu=1b!L#rZ$QA3N8~weMF}{~?L-|J0xN`}lw2 zGCQCCKg#X{InQyI^?|s(FTKt|fyTl^*bAMfwN zmY(^4y&dJ;8uJg^UL^Al;s5ykUUf^jGot!a>lXRF%&?uG`S^Wdh5R1pk6XU*@%u)+ zKEAr?OY2&BeZl|n`%3&i8UBx5*pj6Fj~$mkL;WAS#y`cG(fS`deOdZAC;8}qt*2&B zbjlz6pLK|MLHIv@f12kDQ~$^BSIdjz)&H><<>z?(M2E~j!~8!UUoVyUX7GP(%tyoe zzdSwNyRa2AB|6_MmR;vGFmzI>P|6}`ox$6Je zn8yYG$A$-k|6{`k!vC=`j}88h4Sxpz$A-Vd{699(_lT+3Iv9W)c|HsZvh*ST^#`?qXf9{6=V`s+p ztpCf#^B?}PtyH~b$P^8w-i_;|y=Vg4T*=ZF7eWB=g) z*zj%ef9`gBtl)Wf!5*$MXue%_@I1dD?^jot?|HvkRN(b%{uM>=6S8ssCdSIjx`iKQ{Is{*R6QhyP<^|Kb1K4gbf+`QiWE4gXhj`pq`~@8)!G zWBwoS@1b&j_&<9*xS#qz zHs(3P|FOr5UxNQ*Pab!=`aky638U2iu`|Wv!T+&S#p}WUu_wy&1^&<7@P8NIf2I1r z3F1lN|JdVYeOCBCHs}Ab>HpZ{M-A2af9$a`9~1tM4gdH2%CqhIQ|ClEga2}tb>xi6 z>i>=;->x2Ts?4w3edk%-?0zE$s{dn;ojF1MAA8P>N$UUDSkD&z&wA=K=O;sYd-jy6 z>i@VM>kDVb9kTsFWBwoSuh8)m)c?5~{*OI=e9!zp_PBB5)c^7MF?RF>^?&SfV}d5uMZF6*rDD5w3oPV1<7vz!gDEVRZv z#p}0r+4W<6VE8}2ez5*8{2x1M&>*M1WR0~?ZeME7YU`x&gPk#HtE^Ke4a4Vmdwn)c zlzEhoEwe5f(og;0Ikz76%>QGrliwr2|FIX=x2ykS@7}OO{a<2tw)NKShn=x0v+VIi`#NV@ zV}DnkGsF7KJ!d(`9++;ubMJm9@Xj>r=J_4Yu*~-Yx4-UF?-$ltqyCRQr9NNh|FN-N z0sNo4zdHF=;Jsv@dO!T$6#kE0DBmZ*|FNT6!qoqTuFF>c2fqaW#}4U?R{zHiJLUh_ zn70J~=Wh7Fj+e63|7FVhjqrbL{|cGMCI0WSm@M^w@Kx}C>`GaW4E~Qz|HrNpzXbos zhUbI-W0%PKLGXWU__)+nzqGEFgb%PwQExh4zPseV2%(_bcDgEd79<}?gQjUNB`o2f3Yvgz~ z{2w1LH0J;D@rL(<|6>;}iBtc#VT)fqY0|i^h@3qsWYv1>YHJ%#f71MDRmQk*j; z-Dh1U_Xqsnmw(7n|A&VEW8?lhBlVs@RCbQ~!Rj;foVQQA+qy=)N8xYpw62oxm+!si zr`DMNH+AJ5p2pusyF595y|&>t+aH{M;_O?k8}WU)toO_Puao2XYfs)}jrk%I&%Mza z^Z$O)a)UM2M_dzny)}-X!~gO6;V0q$*a`JB)&KGKkCEROWBp(DWchtB=KryMEs^T~ zc>Z$vJuLj6?XS$sf&XJSiZ_7&V6-FaT% zg$pv(`^7YcsQ+X8#0Oo|eRg2fvl;69Qst|jUtW5ab&ecQf&b(7$~|T3|Jc>y+m_sP zC{Q{tL%ko4kHG)2D>fE7zkg?cVBgX7o_T-bSLYS)3q0~+ntH#|bt&rq*qDz9|Ht+% zOHlvE#`<>ffBz~@Q~!r~Ht>J!1o?g*{%_vxsW$Hq>;Ensl&anj-~VI&-{mV(bpD@D zd;t94OV1^%|0`b_t@Ho-hbOE5>yWRiu>LP**unq7d%^#)tK|4w*OK-CjNAUpj`=HO zo)`QdyJl~h`agE#zH%r1)<)ajAlvsZt+%d~`y2j`myd@3vzFsm@PF(&@kj7~Y|QU~ z|8qC|9~*+<885|H=Zg-{1 zM}+@lm&@^X_&@GX?bbr|f9%SQx$6IVTYfJp{*R60!I=NY#=IW*KX!?DHTXX^-Y?<* z+ztQ7P8RPC|Hn>|?v0N$FAI4qW+IvwXanD9~-BK|6`Z#>G6N;@_ohX|JWsa%GLk58~%@7Ebq7Qf9{s` z{p|j$-&3OgkN1DwZt*PQ|Jaq{6XE~d4gbe3+f@W_aZ-$#dOtM$9~*uI{*PTOuYdSI zHr5}8|6{{bieIzF{VSfv)9`;hJsvOkKQ`w7i9fT>k-zuwf81Z6eExy|W5fHw|G69f z&suyD{2x0*JztY`wD=_1=4tppo*sTs_UCc#ALjMR@qO!b`Fkd}*VFh8i>Jr=WqT(3 z)cLKk|8n`(@OkimJbkYCJMlDG@;~);`SN}uzReo1N10b=jrpxIf6f}73jWV7PfjoE z!`gQESef@`ohQG4koj%an2#p&*sM$B^O($6v&Q;?@PFLD2ATH_|HsCBxQCaI&))TU zoO-(yS>OHUoEg@+(icq%v(8!+BYrK;I<7NTyjr?-!lHQbX?fOZGM^`JceyqET5MB; zb%v}zJ~g(()9`=XpNxeu>i^hTU2)>aw%K<4`w9M!+wt!w_&+x0pEk@s+j^c{-}4uo zZw=3v^Ph{YQ|0#~@P9l%w!{Ciu^s-8P5&T86=cbTHt>FXV|9JUva{cgs?Ah~U)c>(V+GExKu`&Pf+vwle<;BT7 z*)uMG)f($#fAsyE*16(UI+y>!x>P=|!~gN}%H{P~o%Vrkhv$0shQE2*Klq>4mGbYc zhc|p~T_v9vV&3}Nx>n|S-J16wPcJWZe7rvRqnq~jwVp5jN}kU?K7X;k<|j)BTGz|( z3Bs-$Y~8f8O#L5UUybs4M4tb)eW{%O&7zUki{$b~?;UN8&r1~#kM*?7%j|9OS5MBH zWL>wXLgqzIv2Nd4>7*W?W)1%*zP7i;YrV5|mfgMvdB2`~cZl^uS)YC8_E0 zYu4H->r(mm{MK7*tg-#RKh{~7$vj4Rf40W_z|g8@Ys{bPJkn}iwl@PBOl zdjkHC4IkLjwbdFvQ2riSckL*1UU+$jr{VwH=ZF7eH_PpV|KtAP^5Os74gbf+{=omS zvA^(tZ0ryGAG=L{9|ix%ZkPK9^Z(q9`G3~(dk)P1V|U2sDfmD3Qu+7AzR%CI{a+&A zC&=Gl>jm=sdo1EY>vsA6vZp87v_yZrmU^P=l)d(HY1 zC;Oi3txJ~Y;PaSueP@RA_1|u^&aa7ZZn*MhA3x7#h&Q|MPj~qE@BNgLS?d4z{Xuro zMD>5{f=cm0;{Vw2YncDX&Y7R2^Z(dbe-{3aowqnm{U00am%{(CE4otE|FN_7 zRz7dQ|FIW#C93~pcPxxo|HrOqja2{VZumcTiTFLt|6>=)?ScPe=Zbg3`oC;{U9|c? zc3O3)`agHW|G69f&)x8U?DU#>&dVjwSf^Iab?(^kthKLfhI8<$=d80zWc{nBer26f zHdXx}zyC?An6CcMx@@-kKX(U~y=3Q4lkJ%Q$NfQL{vSKGvd90i-{f z7Y_*k$EN>dV}0Wg@qg}y|6^l*BK#k_xGhfS|FJQ@5dP2I@PF(w@qB5c|7Kk(^9Dy} z{@oh;5C6x<2fe%H6KnX}rUU=9ZjjHrA8h}ZkKYGk-oTuneD34-i`8A}PS&emSmX6S z?6+U}`2A#cdyoI)_w8jhbJYK_{e_d%|FH`SLe&4Uv$CeB|6_-zPf-8Ij?0)|(#3Cy|6{|K!T+(V z#QVYjvCCp()&IF0{*R6Mdhmbj@{DZte{6Ud_&;`w_!sy;Hhc{HAG=<>82q2LcsKYz zc8$!xga2duWxZj{|6}LL{1nXpV>ih>J@`L%qjr@uhI z^1@zE|6#>GYxqL=Kb{`*4&ndU@Oton?uP$k7pJ7F|6`Y?Wvc&Uh5dM#z1dlJ~|FJQz5B|^HnE%Jd>EZv_SWg)KkB#-I;s4lJ{~G?!-SB^GJpS;1 zYS;|NWF3bzaweS#LJti{5T4%u)Zx(>Kd{yzqZ)%=?4?W7p>8sQ+Vk zh!?~9zijxwpS|7Nn9sJT;{w~>oSWl}d$+ecWj>At*R zj~6^2@5g)|-rwAp7u>jj@K9?rcT4gc3L;N~9x zC-cBC|L-6DZ&LpUj|KntROEH)|Hh0MqW+JK+Xw&0rvGEp|8+!O>+yeV*%@b6%4OZw z;@w_)=u%I^|MBv${x1BVyYC%vS@(vC*Z0f^6i@l$;Y+RIWy51) z{vR9b)x!U=2gv%i@PBOjKX=3bvElRJ|J)7#cclM~9{cKeqjJ*?;&yJ|4s6 z^5Fj-8*q#Izk#vP!RUe4P{699l-R!F`?#`WZThBZ^ z@md#+?QP8W`{DeHY&$&Qx`Dl2I%cHvhkX~?_Wa>Pbp2mm9{d;9|7Byn*zixzx5oOc z@P8+sxk5eQTsc4d9~<-Ku>LQ5+=!m}e{9bGb2t1S8}sx2bMUNg-XB>1chV0>dt26< zEm?4u-5;T2#ydxTchnlU_vyOco<3=ebJ~kXZ2P=PW1YO>-kvjll(X;2!?qps{NVq1 z`>|f{{~kPK+p)ec{2w0=%mXZb>45DYdTD8I!w16u@$_8(myPS&d~CmMhyTO+zuZ20 z)+`=Nd4ci?N_P)!}|f||FJP|@Q34TtdmDga2~pDwRPOE(azdi zR$1fy0sim4>yNAd!}{Xzf9x^+2Rdhey2N^9-+t=<`1s8jHdg%~J9&15`akyg@KE)C z?6ESBal({NyS#a`r#df&EVRbsDf6@K{VYlRsLa>4PL$_++Dj{~!^RE8?{hr8u5OvV zKC{LTan7z>Y8@|cw^;x8-ER-7|BI8?FXsQTHx?DC|6_NwE>-`>-m+o0`oFF_4|)6_ zd)i^h_H}7^nOit-$W8NS9AA6a2J@`NN@-z3V|9ijvuzJB2XYSScf9{6= zW3StJNc|rlKQ#Owd#hX@{2zPQ?jHZg-o1Ob=k?dn(BM?=eK(NwdZzk4{C@MBs&}mO zS`wU_rvK3z-yf9!^KDPV|MC3zeJuPRyHV!#P1x~f;G5Gk)%#^H%U1u#&Rd%uje>i@VM z^UvV_*hS*^;Q!b)E7NuUpS$7z*q9%3!<1(N*QBJYcS4{2=`XG8W!?z)6#$_=ltg${5{2wn5 z9uWSIjo({OD0tKw-`DmT|A;lb+XDw4w#N(o_Lzt5@ho4Rtp4x68?)4l<}HeHzAJk$ zz|QClRsZ+Q$ZYk1Im@Ed|FP@j^zeV|7V(+ze{39ohW~qhlTZC08vc)6A;&+~AGq62 zk9m8OYVNYe`p8dByVJT%j=!(}_zvsrwJFY|M{l>rJe;SF{KOi+Z-@Wm{-ELi*jOJ1 z{*R5{$HV`zF+UOhkKH8e7sCIs)8%*-{2x0?)}Na2<+awBH}~X|*H}kXPjnuLzb4T4 zjcoOf{p%(<)4#vU`t#Y9f3Oj$Ztak(d$LoVI zS?d4z`kmMquKthD->ka1>i^i8wetB!{2yNr+0`?hEq^~J(6u2=ylKar`bgmTtEuYy=I*X{vR*iB9k#DY{U5id?5=k1A9yhEQgW(#zd5V3)&H^c zm&U388*n^D{a^ON2=#w#%;!lPw=) zm$ZhL+x20Cr=Pl`&bn6S@BM0StzABP)L*Nt8|C@gc3Xut=6Bq*tjxMijyL~3w8Ya1 z9~N4}`|bEizNde&Jl7iQaSaXgd%FIkENdK}hX3RJfrkHMSBa;^tOwp7XdK&NW8Mt@ zo1Lc~E5^D^=DETDaeKA+EBHTlq3l2WAG>T{rFgBm){QdH?}jTwtgE*aiQk%K4WAY} zeTJvu|9E+r-+}pmY|O91{6991kHP=3D`j3K{2x1Vb)5P?cJx|#zKQ>1=g9jr{2x1a zO^UAn%Z``z*5Uuy$@2aN|HsDr0sJ4kRQ?`*bF@z&a$THyKlmc}KX#$a&x8MCr-<)^ z|6^y!-=BF2pIPI0Kl~rJV}1$zAG=r@{*R6Mdhma2{QZOfb2t1SJ5BC?_&;~U|FJQz z3I30_FI(nK!vC@11u_4R4NnOF$1aiA3;Z9uT>KmSAG<`JKk$F-a`ATXe{A?&_&;{l z?w}v7PnE%IaIa;s&j}0G<^?%tFG7l8~k6k4m5cB`o^#?1kKAqkElKquf@6HD~%?yf#=D%kgdaKi+?sKZ^N(?w0vOCuL1W^?cYa^Nc(#KEfLF|KR_4`T}|X zl4IM}W#VVx|F|9VK*g7wl$lTJ(cu5Yt5_F{rx5>QT_~S_#M4+8$n#J9*a@B=^B={R zS!4dA_%myK-jMlpCwTpS%=;U1zcuFniEp#+@pBhgpPG+n4c{;Kk9D%lmy+A-Y4LZ~ zIpUGv|9JgA@k(-h|8d)Y`FtU_*VFh8i>JryQ?_UF^f|KLy`0}VRs65qUh6dRzjFF4 zo*whh#70$L-S>hN=H!CyD2S|6?bJ z_Y*&49VdU!;s0#A{Jn?&V`F|D{2x16JRAHU8}s$x|JWI_9sbYVnE%Jd>EZv_@Nv`c z+?%~^dW?EI^g!Ps>lpd>75pDhA1yu({*R4$eDHs4cs=+(c8VOI?I^j*E)V_Mz1LZX zNmop|**a485B`t)6F)yr{hzzx|J)7#=Wh5vcHI1EXYzR`tz*P1T=M0U*0b88oxvT? zSi}GAfBJcAoIhjZOWF7Aiw-;N|FO##hpYc%S1yf|$MXlf2! z@qV>4eym*|-p|C#_O|@{>9cDmTKmQKM!z=M8vp*ga@SPb|FTs{^8A@@T_gSy{*Sk( zYI%bCKQ{KS;r+R`yaY^wDl@ra)u zNwDtRS|T1b$r|$&mw%e#X?eZd^ByT18-pLN5Ia_5~Xxz_NSG9T0$^9$?F zE3}4RJnxsq*7J8%ssH2Uw{5Rf|HsY~zXt!u)_K6<|JWsR{qTS6GMOg_|HrPB`Hb*? z?Akpw>i^iQ<=;>6f9#dwIpP1<`1~<4w$r-)K$WbQy~w(JU#)Za`X$z-d#dIAdYN^D ztoQrv=_{?9W&U_l$!hEQGVgBPzO~k^yQ|dy@%rii+ztQdZumcTlYG8{|6?zg+XMf{ zUMlmsn?rZmd^2duF^@#Uiqd0N(Iw}$`wZRrtD zf3ozbb%*?(YUqKptlS{- z|FIk7^Edn-yIwwD!~gN~!$O&l3IE6L+EgI(LNBv!kjp!gcDbjQG+tqi-(TizJZ_Ek zg{NP5WpB&8OZY#2ek_*n$Ke0i&GPSg%>QGz%4jM0KQ_L>4*rjwR~4fEkDXjOPyHV|v3#!jKX+sPpS$7z*f>A@pS$7z*eO+E>i^sg|Hp>U zg#Tlwm4&GPW2cwTagzS=ylqb{o$U-C_kwk%c+S6OzvyZBKb}8X<^jV0u@g&XsQ+V6 zE1jnE|JbvuW~={W=T^>9|Hm$@4b%C5?5w(;`G0KsKX$%&O87r_!~e1Ids_HEc1BaA z`agEAtf!0lf9!(RIQ4(*a{0a<{*PVJnyB;t*zkQJ;{V(Y|Hsag^?Km{*g387>i^jJ zEwSqV+ztQ7_BF?-|6^y#JVf|EHqQU|#UFbb{*T}9VLSXEyHM5>hX3RDh4?)T{2#w> zEMAbT{*PTI>tEOZ@TF}pmF*$_``X9vD_dp0V@AX`)=d@j)c^7O@fvx)WB#AJG5?R9 zTRcnsA3NPYN&O!?J7c!z_)1RpTu&EgB&h%6@%5tgc=dm5%y+~5KX=3b(L=yz!T+)I z661CLA3G{BLH!>)J}p)K9~+)UjxXBzv0kVgf3z<2=d1tY>5Fpk6kbG*WmxyMOo?U|Jd+$@PBN~tAqbzWBwcF|FIW}H-!IVFA(1b|HpPcxBGh=`+rT+0oz`XnBr7F9Y@y*xEV{U5tk{4M++dx^{sg#TkNm-%q;f4qMe z%k78%W8?mS|6{|e!T+%_FA)CE-EL3OB-`EHknQzst>Piw+k-oJ{n-|I{kl(&>;J!X zu)hmluQqslu+RIk%U_!7-Ty^0pVGZQKX!e={tx%J`}}x*x;xn01$({!XWu8!NB89i z&-ZJV^{U<5vA(vu;b+~A^}*deTs)S$hxY65Y0S@aZyzz(yM4$&8K~#-hC_o+KRC$q z1$XegzhLi&d3o;3N5lUO`}zj;e`xr>_rJMb{U7@6fme4A8-1PnxiPYSCg%U8L|&sF zaHOn%3;)Na|6|ktjflD04^$3s8!{H4|d<@Pj`^fq|rpPoKu+j09a|Bsi4+Xw&0h7W}Q zb2t1SuMelk{697>5B`tM`G0&o(C~kWU)-qv5B?GUkKK3R0QG=lV&u8^E=KsO}aXY*g{2v=$3;vId?eKqW%=?4?b9ec77g%GyAN(J;V;&&5w{*R6IW~Y3$uY1~km#ZHeIdY`4b$f5a|K0STy|x`bt)*XYhm0Pl z{*U)Z^wb&Z|JX4T$Ep8&?X;WKM@EbtrT&jSZ2TDYf9w%*diX!~^a&Hy|FPlo;Q!e0 zechS84bKPv$L%399}xbJJ$L#H^?$wlH&y)~J91o)|KsUrjU1!v|FWkJ9ije@4L=G0 z$HscR@PBN~-^2R9ynMVrUHgai-9Kx)GB9^QpB%g%zI<<;^{C;)obnIWT1Uuw$v6LP zjWs;ycb}}b#{1dapRVlQdFXi0JVAN?YAIjd{lZmO==?xjAN(I5Uo__b@$tv|C+7dL zaera{A3HRxXa1kN;s1Dfm=6g5$Hu(IZO<>U_Y?TP8C@&w^%gU(OkjP9-f zJD|RAVaH16O_LKW<;LX_v15>u${dV=vm&`|a2lVcRjU5B{%r`vIN*$Hw}+nE&T)_&+x1|GE2D$L84n z!SiAMANL=P`G4%qI}hmkzjl6U_utdqGB5Db)LC|Y`(^&$BiH^pP&+b1z1Ff_XEfxw)($c-!>^wYtbHe?$M3C5cRsxSSJnk9<@alwp7S*PpZomqe>{K5id6M~Y+OG4 zA5UK?9ufYJjrB|5|Jc3 zJU!Omh5uvI|FKKucoX~|8{QB8kB#-0;s4l}mjnOD&Xwc!@PF(kxjgtkcC$Rc;Q!c# zvi>ss9~<5X{*R6IKjHt_dE#y0|JXR*2>-{PS2M|3bK%w2Q>uIXAMc+~IsOg*$IfY* zt^SYaua$W>@PF(I@kSqyzsw#V`aeE?srbEm`X%;whspPmnE%J;S9X1<`ad>2Ap9Sn z|M-14{NH_3Qq=#UG5?P}w`Pj^KX!(AJ@~&5_a>|V%U+$M{*Rrt%CG*9oxj?z{%_h} zlGOkCW&RlE|FPp`-X!M#HIyW&|4UyM>3qCsci^165^bIz{2v?h{^0-E^ndJlc|U{y z>mHe?{txee|IIif@bAqD>itsNVx5a-tqnx}K3?bjVLjxPzLkOFH^%jNKUsen{*R60 zrSN|*^^f!TKdey;|A+Zi@PF(QdH%rvVTK+2ALetw|FJQjL*{PR;v7Sikd6_m^6?$njA4KkgqI{*R60XYhaS zhW}&J|G69fkB#H4ulJQ%kEd=gj-O6@T5PCwk@`P&g?L5yKQ_D&j`g@3|INmHG59}r z$tnNGE|UF+|6^lb8vGv{$A97f*tOf>w`N&m{WSPLZb!rav8%jX`|-|BsFJL+4};veTni|IptWf4}a3 z>NHQo|MB?+KfhP}AG`bvpZY&`itIo9A3IfUAN(J?W__;uKX=3bvCCy?82CRnjvvDR zu`wSI{?Fa;e{8Jx4gbf+df@PX>|}X8&HCXvPs_YF>vWk%lR5GU>rC-!zdHW7b-6r$ znr1z0jrn~tAI`d5=C#28@&1O-ga30k{GYoq|BsFNdhmbj#(ia&uVR;vd4IBAn{~N( zI`}`H9^2vn*fj^r)&KGK*UEfQ_&;~U|FP-++%5BcPX6TbX!U*d;sIs7K85`2C1@HR~FAy~_Ss!vo4ZIqPEiyuR!6d#%&t@4d`>vrg)Y z5qKGv}d;?@80`r+Z=|Jd;|&kp{N9l8MCZM=23%U8e{6U`_&+w*yX{=wo-Jm{{9bk1QcuJG@$}e#_&;`ntj`Aj z$Md7%|Jd+&@P9l#8vc(B@3(H-#ddo12k%~H4L=9}$IC;*|5?lD8TdbU!~d~k2Iw+uJg~1^&;rOTV-8k?f6Ck?QrLTVtH&_fA+x$@bqCJZTMoSbE3Po_=!p z^VSh^f5HFp@^Jg%|JX6I|IwLmdiu8O-?qkl!WsSE^Yrl*f3Xg03wK7n_>pzA_`q}G zKe0|(80+-A{4-C(|MB)>9wg@fu`w?a{*Rq5>(Rmgxf}kEk6)&&2RZQ{1FZeavgGj| zY+bNCOMag?)Ed7pk>|g4^|EBA|I?>i*DOyF4?4;k^LpX`czs#RGSvUEbC+d0v&K%e z{qxDc2Rce7TjwrLa(?~KDL&rcIg1jVfwQJt=gE56BR`mFr$<*z3b8H~uXtAFTqhZfFN`d2MMqTgerRDv{x=HqT)pGAuX!%Oyi`lh`HtlMRO;QzS4X!t)i{U00i|KR`F3wGD4 z|6_OTs!{*PZrxt0{?Fa;e{9VEyKB>Vwm+EvC-48(3&qQRbjJnO9rAro|EDjsULfBG z&3^A9>vnm4$a?X1`SWEx?AWW1S$A&6ywFRno8|Mts#h=b^wCc*x5n>JZy9>r)9`=% ze1!Re-`#nYr{8?;YU>vHzU;vduJQE6eXp}_6(6{M#`V@sEA;c2b;I&}^?&^Qn%fZP zygKk^A3LoiO4tA8_XSfTPgnoPo*FX3`ET3ZK7QYT#{55Scfy9N|Fe!Bt^UtCWrq4c z_G#(zeT=OC%f|Yl@PF)SzDer;*l~HY)c>(#a%QOiV~6EVQvb(}$e*JAkDXUESN$J5 z(?4DPA3HI7y81tMT3(O;WBW?O)c>)wibK`^v7^LC!T+%%%VfPI@qg@uGVxR5|Jd=R za~$|THcpTEe{5VH{2$v_8Lj@$-I)K!&J?c&|Hn>~%ZLAC)Bmxv#0SFvvEc{d|Jd+@ znE%HPshq9;j~!YwSN$IwzVW++*X;CY%>U!|%$jJO|Hsafd4ZV!$Ih#tr~Z#!)Euen z|FRS1^AP+WJ4rq-Vg4Vx@YMW2c9Er?B(mMAB1 z%V$1*e^@5}9=PH+pIc)-Ap9S{kHmV#t0TX*u5OgikK+IM{bgx&xKrEwt#z6BRQNxB zAC89qV^_-a59|N3ONwW!|6}{JXX^YvcCLT6&i`Wlz*Pt=~kH_2Lso?+En7;=9 zM-PGR@PBN0K+OMRCnxpH|6`|!2b1-~Yo0SLXEiKX#R@ z{|W!cu8?_P@PBN~H-!IVW4__>?d$yX1@Jk0_N=!qOG96ZAs{tW()=ZAlT|6{|? z!T+)0=ivX?ST7g;kB$2W{*R5zga2d0+rj^_^AnQQ|FPle;Q!d1|Hp0+?+5?K=K8;E zTt56CZ$Eq>{2#kEK0*B-8{Q87kFEPB{*Rsm4gcqE_&+xGAO6qX@PBOFKk$ES+&}Pt z?E2IM^?$tnnxt6uf836Fi12@G_#^l~HvAp@pS$7z*qHbC)tV!I`WQ6)ADjM27W|*P;s4mxX$k88*cHjK&SzhqW7~26ytd_BYk0tizwYhY z@JQ#XZRgqcg|eRUo^N`)-j}ZakGHo`p8xQF?1kbPpXW4gbf>$LYTh>up>f{9p5^t9#}F zN`Kt1w{d#-zkhvpjru<{{GYqw|J)7#=Wh5v-XHLO@PF=x|8qC|AJ31|!~eM({*R6O z2lM~7woe~C5bJHr3*^mx9&|G69fj}6ZU|Hp>+ga2d07sCI!8~%?yM*QE>f9&r*>lc@* z??XRvMsH((;QzQC>;J<4vEc#X|J?nDL1)|jfq8hC|Hu0W^YSqNj}5Pux}&$J$?LW8 zt0T4@UUKspy**au`(5(!VcQPhckeQ9zx1a=wmp2}6!m|<`Ns|F3!|n?SO3R`_k;gq zM}*AL^?%uMb3%3fU-sNdQ*{0xd%CPwoHFTvogecSG5?R-$BFNICwZUk&zSxLbp2o6 z{z0{C%2r+s0kavweDd;g;Rb)V$>Gqc`o-d4uTUHA&V>Wc^Gn3W(RdhzF|6^Bm#j5{f*DQ`# z|HrP7<9+ad*+-Jp|23@2R{zJ&6W;~@$Ig}cY>yN_Yh5ezli>fjy+P))VE!K)>*K=z z@%n1ycm@0)yL!D}{U5tVz7K`}W5YMX|FPj2;s4n1AejHht`P5l`G4$X;sxRV+`a6z zN3EOW`{AmeJYqe6XSw`6df0lY{2m)n7J}gdU+bc1 z^?!W+;QojIV>inBk(2lQJg`C5Q*9n`t-pA6O3(Vgr@BJCAN(J;!^6P;-90c}{U6pt zhW}%CZp>Hz$J4j3lX+?4|JV)dvUL6*8}s_$|JX%xyc_Dpi2YWrU) z$5)Dv-(rpRu0CIOvvs|Ee|~lHP1eP7{HUnkjn-J7^IxxAZ`~yG8n3$XI%^zHFF4~` z>-3d5>i@Vuv+Kgu|FQkGAr9vM@%|`i3RC~b&TXEf{*R}xmGy*m{ohmfcluhH=Og}) zj}IF2|Jd|@e7(~D@%cpm$M!ddssH2iAM4}5|2fYjs{c!@ny3DcomnVxv{*PUzVtB8nJ{|CRf;GK>D zj2gTj8vc(Bj~9PqOW={OBh~w%;s4n1H}HRK%nO76V`Dy7#r@UR6|&xxtk-Fc%lmys zxpke)C!6&{i8YSDEq|)W)3Uy&HGJPA-{#r=qJMZi$J0f7e4f4_C(F7@))#~S0z z@PBN~cZ2_9W4&ScKX$pSH{5yAbh|wC?G00{F~97e6DM0^ep&J#C-k=X8Tdc$AJ*4| z|6{`!!~eM({*MihbjAI{tl^dZxOIp%{2u%tPY>@7|Hsak`L*zW?uP$kV|~TF;{Vv` zGQSA(|Jc#XWgda}KX#J%CHOx!{+?p~A3IjTUBv%M|z zD*w3k9P8Qx)$0Fv`quqb>i^iyGVf2k+R0DaBh~kn?w9rJ+Rm^pm-&G*-{+*P$*8`p zVP6&I1zBT#Nbv_JWoDE5x?SQpB6@m1FOa({`xvWCwUpJfgICw|Ks zuNU!M*6@JhU#xL_T0D()!=^&`u@l_CR9W8<{*Rp^>&=QkvrdxNpUkH_!P^@zpTA^& zoi)6k%(wHj_&V$O4Oy5+WF04;Z{YuUd9mW};Q!dsI^S=Eb&9m?&*R*`Wchmm|HsC5 zxxLnDa(VbaZpVBu*`CS9?;qs+*8bIrxO`8`>9ctHoMj1kJgogob-tZ-seImp|KsUP z#P7-FTW5A+-rn`rX&rOb|MB$r`waibhEIe4W7Ge!@%I?>|JeBZ4gbf6=ac>KZSi{W zf83t5C{_I*J4G7)kDV;u5B`sx+m)vNkL{OvBJh9gm_;cvkFG3RjFS4k=&od0f41Hl z`vd>S?P&NvHum2?SQarpb$;C5n76iC)BkaMyv#p=|6{|u?YZqNPk%k)d~3`Dg#Y8| z(eQt4+~4qj?uP$kr;9g)|6`}f@z-zvc3XDJ)bIf2?IpIvI2)_(v`%P_c0RuUXVwu- z5zdkc4|p2>kLOQlj#B^UZumboJRtm^yFWYltL#7C9v0XZxX=$jxaNZwtz%^#;Ri*p zSkIQ@!3%GH!#YGf9{e9K59=kv|G69fkB#|>@PF)NS#KErj|~qB|L5-A-+g6`=fhVE zzO%;jW&Km%TjTd7Umok@bDw{pub+?iH-2A|w{d`{_uMwf(~rG1#5!5-udhc8xAx1t z!}$Eut@C6a;<|04tg-!$JI7dOH_w&l$2eVLkMED|?T&fQ zybt27YdZ0KOtQxO`5Q`8tlQ-GIPibmAI#@|w^T ziyyz_>MkGO|LRtyIxoJw*t%N&eF^`^?OiJp)&H?q$=}1hn^)O(%zJ+Hr)#X+MD{_`(8t*drc%IkBFoxWQ9;p;p0S=a2Tl-KKi>m@R;@NXdp?fN^#cgp*- zHP#cJ({k9;c^i*dx5<3R&hw617=O%q(at*Y!k1b% z$-K%dD=xFH+al{BFTdOxpTAx^aD_F#A9-@#l|FvnX_obU-_5_ux@ldmtS^4GHRki^g&$s^VO zv6GWd*ZF_!^t3VR|Jc}m*{&z-`evlbdR*fFxIHX)qWV8}T<%o$f9%*CIesMmk3Ft% ziuynHgyL!H|Jdn8J?sCn{W1>_{?EF+$N#Z?WudzMFCVW0@rQT(^F@0+i^OZe|MB!C za(VE7?9xhEuSEPGJF6;G{U1BKTK*mmdDXV(%lBFEf836S|6}`WBh>$~bL!;#Qt^Lm z`agD={GI{x|Jcd0-Y)zfJ4NR8!T+)0_b~sDP5;NPk@bV&|J)7#$A%xo{6BZY|FM(h z@-hF9ohYZj=ZX)kG2amWkJ~eABOUlZHs%|`|G69f&)x8U?tbdLe^}?pyuhm;{KV7n ze|&uX@_7{gkKZ4n;s1I&&RO@}7uH#g(dz&B{UrP%{2#x+#Cpu|f9{6=i^iqIrG&2v4j0zNsg?KB>s=b+gsB!)&H@ZQqr7-r!Teb zSpOCNk3ItP?%@B}`QnkV{;#{?|Jd+snE&T)%>QE-%Js|oWY$G8Z%x)O>us6e2mi;@ z>-w$Y|Jd+j@PF*;#2EE|^aZua^6wY%f9{6=W5d6}|MC3jnDaN<_ImMtV=md`>2ELJ zY>jz>@P9l%yc+zUyW#)XI6eFy+m{rt{*R6A@PBOhJIw!cH~b$PryumxZrdMR-ul|z zejcC2yvElW_E^K0Wwh+I#=N=TM(?xs#fpa(|HtzuM8~NAV<*SO>-;}9{hzzx|JaxZ z2>-{%`pWQs><+BAoO#H)P1Xy>`oG+c`Hk>@>=K#3R{r-xetH-9w3yY0t()cfH0mF{ zjd^PDe>^=J{*PTOo(=Q=*d^khF#nGY9|!-(#{Oge9~+kk|L1P_KQ??I=Krzbwc!8Q zSWgxH&)x8U?D?{P@PF)f*+2L{c9lQd>Dqq2rwhL8ZTMICKi+@noqz7_>fC%MX30gi zy-vLCpFZgAMdEG6_t^FYL0+si$iubxyj~5Dm-~2dS&rA!1)sh-+w0+iJzDVkyTM*C z*!Kl{xnK{7^_$)M*Bs>SFkjKVy)9_|UGVz3|Ihs+*B`vU!MEqf{9o{T!NKzou^zPh z_AQX-ySsz0FSxOOtNZlhgVy7n73A+`4EB1!VE;E11L$0y5bM{vd(a@S=LqhyM%x=qiu@V`Kj|Bwc2=9}WMepBOAGf37|JazH z`E|t^-QCrf2cCSsPYzyhFIBI%hS$5TZk;te-=4;`);NDt%NkGr^y`(~Bi3A|o)FLP zV-GIxZo2wX^?+#jKR%v)Wquy~AA5kT7YzT$h8KnZW5Z8k{vR9O@AciC-M2k_OnqTk zM2Px7c5dhl=b6omZ2uA_jC8_YTx9PrVg33z`(Ns^4wbjx-~Xo5dW775_&>hiU^Vt( zzE11@P9ODu@qgK;{;#p7R{dXo{$BNetCw$5|Ht0AZio86r4{?s|IJ^&P5mFcb90aX zV=vyaOa0%YpX^ruw`6ON|6{M-v|IfjPmhNGodgn6|Ri+H2fdWkL~b(JU{&(d&B0vI{%NS$9DKXcfchc!0>Z(k%l7@c{x5r__`#2^m}8f>O6Co|+8ttz`GoGj zpId^w-`-t^o#DTEKk!{yviiQ2%hr2N?_W7z{U5i7*5s-GV`F|F*8h$9d6N3S9Qpk} z{2#kOe$Nm8=WfjZW7Ge!3s(Bn|FPi<;Q!cpD`dXb1Fr_&dOATpA1=S<=quJavffr& z+soEiuL=H-r_Yl4b44{T1x}Ai=$YpyzxRus^P+W0TY~yOo*u_1;Qx5~j3sI6|JbE+ zXb%35U9>tw{U4kDkKHWCcj5oom_N7Ssi!>Mdc`lS@%!q$)lXWtiC>HGKVgmIw`0b1 zTUW_^g#Y~Yq&4Or!T<60z^lRku{*_+!T+%rZp?My|JYa$82*oq-)qDFvD;+-XI4IB zUA?r&|84jxQGI5a9KSp|=fMEGT#j$X{QLoXJaK&ZcL#oM4If$c(f#&(#QM0H|M&Et zlhp%OZR+uV?1~M3XYz+Xv+dO~ujiK!++&U72bllI(>IHsg#Tk#h@ZszzwU!EI&U;Q7uOFR$!AG<>y5BNVe<_E$5vGe3m1^gcy^Ksz+ z*jVow{*PU{u2lUW_a|1qufqI4HoiZE|2uR;iu%ahx={6hY+p;y`oBDVwH%Lv|6>=( z@9VMtFFRM}U&8PTSLgrn`H|YtGyjjBF8&bn|M>imm-R~E|7y;N zSN|7NAEy3~9akNq{*N7AGFAQG;orrn{~K94Mg1RpeDy5#f9z3pVe0=L&52Y0H?Ap4 z{U000gW>-^y**a_U%VVoh5wr~Dpvg;UjOia?uP$kz9IY{yGr`n50dQsm=E}uI})tn{owz&KlFcW+`l;X<8J&n8$PgT?>y@= zIsSNl{#@&F+5YOl5NoVgI{Af})|f{K|HsRt|6{`&!~eM({*PTI?+5UIY`nk2|FO%& zFTwx08~)E)JQVyNyGZ7n!T+%{R;Q}}b2t1SJAFl_`agEs@(f-7mz})4XZ{~MX<4fJ zKX#bR8-o91N3Y3L|Hp>^hyQao{2x1WS(^GkcABgg4*$o-<-`B6<7NIB{GYWPZ-)P4 zCyT#^|6`}h@l^Ofc8VNNmGxdv%9^w4-?HWL+q$IN+9&?B?`Mx$V|`%wKb{|c4gQaf z*B|_!yW#)X@Nn>d?w&0EkKH8ahyQao{2#kf=J&z>xf}kEUAwo(|FP@D>s@;EuvbtTAs>Zm%`g!QS$d;A|8z7PJ7P5;Nnd^q?&cf+Cyx zlc(YTxE($Z{?Fa;f9{6=b2t2-b#tt9aN&vUnP-Ofc)pf6=YLN;;puI&pSF&Y)5HJq z^q4;g|HqDNOH%*Gj%rU(|HqD$0cqGdDcJO~} zyq@6y*zf^=Z69Li$Kw@p;V@4xd~$@R;s1DkoF4wq-SB^GUrVI=KXz7AxO4uANp^Yh zGT$2W|G582ZISB#*x3Jq`kB4kJCfx2G}}5;Ztuy5=UC(YM9%B#c=dn0yfk@!!vC@1 zA>jYq4gcqE_&;{~f+Y2SZ1`UIKX!rqe({~1Y1UOslbp%-WLU%NHNTf-T`cnwkB#@IHZ0GRX#nw3s)7AfRe=si+{*Rq5o-|`)m38W( z3}@RdHP&g1WuDI)b=Fyn<#^_xMr*u3MQ1i!$4jqT+iIOC`*+**^R4lI`2Ncso}SUK z)7mGO-=4C_I#=dX9$&G<)tSy~S1q$H60bGt#TC}2@_DWDhgF_FCw{GUp3uK%7q7R* zzX$qVzQG#v{&Jq%WQ~7c!2j|7!taMR9o**Q>mLpO$EN>dSI9g@_&=V%Qa&HT|FNsY zZqrG8gZ62&i`!w z+15D!U)#^I#`b<&&$X_T-xGygc%C)-WO{vGMy?_&;{b8u@*u z_&+w*1BU|Jao>4;B88T`b>c!vC=wn^M*P@$+#);#lWryYKe# z`-^emgVg`=`v&xDhwkyQM@9~H?z-n^)?;H&cMkvVUTgTjj=uL>PfZ%i^iY)5oj-V~1u>R{zJ2%bcwKj~$;iMg1Qe+p+#H zJ1TX&`agDJ>IC(F?uP$k_strk{*OJZXqx&z_5|^LnE%I~STt4rA3L;gy81u%ocyWk z|Jak|`yZ_T%bqFU|G@vT6J`BY%>QF2RE4YmL|Ht!Z zRfehmWBcmk)c?5~{*PTC9t{4E4etj3$Hw+M54~ZH?eKrxo+s<$V*Ot>*6)S?WBXg9 z)c>(_=l9J2W7Ge!>HpZJP4f3r{2v?h_~8H8nT%RD~#KX$sDAO4S> zDZUZ@kDVs|5&n-2KMDWmZumcTUe#P(|Cf#Rli~l^C3W-E|FO$t{So*-KAvUb5eL5U zFKgVscYpZIx}tHO`agcZh%TP{m5*Io7vUUi{i^jAdzk-6Ur-tsq5h9unI!k0_&+xMT5%e>D6b8}s4d|J*$%u*-9P z_&@Fs_8-)n0u`!_puj2pM z@PP1tZ1_0%KQ??E{2v>>3;vId^=;w**jRrS{?G0|@q+MwZ2CWTZGNHpKX$7>U;Q6D zcz#^)`oF>ELb)@`%luUe6co=YrSQZOZV@ziUYI z&Qq<+^lq=u^1k0T23=o6(EBl-KkoexzJB;@_jasD?e5^y2hUq<3R?d+*h>cAKf(QD zo)JF8y+5Oa=KaA}xwi**@Or+%-VeUZeg5F>nE&S99(;QE9ryMDefy~YOL+P!^?&d< z@PE&|e5Lw7H2mKk|GT1R{-1Q%k*loX-Q=~^ojv3V^?+#jKQ{aj{NMTEm#hDS4}$+= zWB=j*QHK@qquUd*nLxfbfFwf837sq~ZVE4gbgH{6F@nVT08FvEl!YFFW5(5C50^*um}- zn~$jv8$NuvGxG3(?x%0NM12_61HLb3fA{ETE>_Ql^=&JDxzBpsh|`_x&pOb(zVTA^ zYIDaMk-oN1g*qP(UIoEIPveQqPHC_E5pD)wq&2cXMW2ZfzN5fk8dGdA(|HtIu1;552^oSuitq@{okU?cc>@aD%;`z*qCnz|Ht05rU}} z$DRqZ?vm@f?$deJi+3G#emb$Ym+U^|Jdhh|+js0b^kb{9eeh9dj7&LUH`Z0qXhMUfY{_kL2g8Dyr zFZe$;zCUjt_;#S+ig@*4d5hAW!r%SgI!C^L!~8!xz03ogu;WeJj^mG5|Ci^-d=dD+ zJ6Ff4|AQZc|6^mm2>c%#^D;Vi{U-44>#^$naJ&Zok6k3k8{q%gdGh_rgl~RrozN1l z{*T*n`~vI$vTHkKJu2~k>^AW`nE%Jd@m0+KW4DXXfd6BcZz@v%=Wh5v_R_6#d|dn= zd-3KH^?&RdS>vCeyGBkA|HsDq zitvAI%o~LNV^@kteD%=>16%vV>-QhcOX8dp=RRQFE}nD4S3kGMvrIf0{2w2G^ufCO ztxM(j_%{#T7vS@)QoP1Zhwrt@WNuyIP)q@PF)DnU8?^f84){&bjLU*yT%N)c>(7md2|8W2ebH3HU#@ zPv&pI|FNFRwp#V~_u1kCF8-9*Dmt(3+m4-mhG~4~73@7nMy_|Hn?L zo2m2vc>Y?Me+d7_4wvym>jGAFT5d2{U1A}Hr)AS##w>a4#}FVGVd>@be8%*c2vbw^?&TRnwieI zafbqfK8;rIH%Go7yno<9>v@e4>i@VM^JU=wvRk9o|E0?9yVkeI8uMM?|28}o)iV!J zj<>`AS&JWp|6|9>yqWtBZ4CVWib$RJ=Wpoof5ZDms{hNEc{uQYTiys)|Cieqq5h9u zvoc-%-yJ#O>i-JXC9D7Y!%xH1|5b0t`lbs5FlX?6nD=+f#18A40~PB3xEUi%nRJQ#BW_I4gbgeMgQt}rZs%t$c}Vt%u{Qc zm1+$y2>-|Pqv8M9_2Tv5|J;rFe{7r{{?FYw7R1K-uJ~^@_6Potjd_Idf9{6=V{`r= z8y*nz|JYdn7ygf3C9i+@KQ`8XhW~Rn{2v=03jWXC@PBN~7li+FH~b$PejM}v*rnpZ z;s4k<;>9ulkL{QDTg?As7mL5f{6BVy%x}T`KX%cET=jqKLOH&N`G4$kS&t0KV;iW4^%mmhum-7bg0hx$>n!jHy*5Y z5<~8=E|&RvPyFl_>r$DoC-Y0JF<(!Phn}3dJybnjy}W*9eKqU41GSE<*XC*QXV&%m zbv-%jx_#AHpU%_1ll!c3dhuK*8{VI*eyntVHRkbH=gRSC_&;t>l=XYz|Jcbge-QqU z9Vf46_&;`}cvkp7cFBe$^?&T5_3F)Rd+{3izJC9_lQJVp{a%60J9_Qj>DHK!Bwocj zcS#gHoOSu)aP@yYe`(h|^?&TLMPcgy*hLHGsQ+W9FPw|{bSJofXj#A3I=&+UzRfzW zJskecdWOuOg8$?BXD$fC{bQZJAX@z&x2MdHfWNct$+BHM+~eFIH2fbM=ZF7e`!l&cO#L5wy3Fr}|6}9xJp3OUeh&VR9l0b`{U1Ae8Ri=f&*t^{m!_%z zWBcUv^8Cr>>64aZ;Q3{pB7Oz_kK3!nx4{3g>HpZ69|-@)P7=?B`G4%Fu0(j6Y%xyi z=^|x*ocI{)aPbK6e>^?r(TQKN?eKi!QLN$h#FtoO{+)OcYj`~PKVBYA5C7+G_&;`} ztT%W5i7V~=nAZpY$Nfda|FLm;_&;m;dhR=ilb2t2-y9a;&aQ5QjIqLo34dMUX z4gbfE77qyj$Bt=@SO3S(k%s?c`{epD|BpRej+bNppS$7z+ztQ7hDU|}V`Kl||J)7# z$HwX5|J)7#$A&M2|6}9vh5uvY_bKpyynpa`#y@kKHGJRNZ~A-srxAm!aenweo*xbW z=Wh5vHZK3_FGgD9`SQEDV>~^!Wt?@k{ClJJoC(%G@e1&Nyu2{+d+>kk2zmZv{vR8! zfA~Ll!~e0<<@qiDZ4KWi7R$%`2YygywOPYIUiJG3YuvvrL!zzc%IzPQ8EYLiKgoGz zb-brB|Bu%Xe*yo;#=If;KX$%6|Kb1K4gbf+{=@&Vv&HMd|FPr58^Zswaeu)7u`}fN ziSU2!#{55ag7`uBKQ??G{GWAan)*L?!~e1I{sjN$ZumcTQdheAKX=3bS+*P^q`dMuEch<^W=iL7-wf3(mkk``+>y&l*>i>BD)b$0rs`TfCX^#`o6-ZK0jZx1{n{2#k!ceVOIcFV3x^?z)v z4-NmvhBt)&W7o)hz$4$EZP$nGAB;cO)9`;heVwdN4gbfkm&=F$>+K5lf9{6=tgx+&u7;j_wnyBeoq1a$IrJ| z{{jAw-H7!Z#Q(8tS7oaI&73u2#*tO#SG5^n6ye|BoyW#)Xm7RIcpD(%DIyP^P z`agbu5f?kec~<8A@%xIX$N}pA_#}0`drv8sTC3=|pKlY6Hkvjj6-%o_c z_00ccMA9Hah^otiXO{U19zrDy&hJ2q{+`af&&gRS>I=3^&hPgVcNPLlP8 z;s4l}7x;cez&gV}RsA2gmsCdR{6F@r>L~Sp?69Up^?&Se@n!IT?3lJ>^?&S=mK61W z?BeER^?z*4n}h#jCx~Z*|6}9*9sZ9U-JY!ekM}oxIOhMcQ|0#n@PF)rW?8RO{NMi} z?LMI7tn2-cKY{dKHrd{HXM68$W_#}~J)30Hdk7?f6haD}B=n}B2uKl;UNZ|wQLhwH zL{I_cf+AP|MaB02e!k1+yU)!3e=g^qzvtX@d7o#>GtZQr%)I9NkyX99u z3fK<+=iUzg=Wh5vHvAp@9~)i`{*R6IY~lad_;HCyR17!{hzzx|J)7#$1ZG3aNz&g4UG}%|J)7#$1ZIMRsY8>uA8s^kN00;?OgSL z>^$Er^?&S=%DL+Q`1~!dn4|uWohkD&;s5x2M`QjUKi{0!EbDiO|6@n@j`}}-{$1HM z>i^hP-TCVO*jQg2{*RqkldS%aU0W{m)NdW<;LlfeX?FK{2#kn=E1@L zvEjAg|Jd+d51hHxE)VPZ!vFF58j1_m|FPlo;Qy@U^5Fm2xW2nmclziT;B97Qo?(r7 zY-i={vZnvz`RV`M4gbf+{=omS;q`Xidv-v>|MB+G|G69fkLSmB_&;~U|8f7}2{HfA z-SB_xuAE%;f9}ToKXz-5%nOzEf7w`X80-JCu^sFGvKuop)c>)wQq$D`v2)Th)c>(@ zd6@slhTp{eKQ{vR8@5&n;j`HAp< zY&^a&|BsEw7yKU^^C98?*n{F3;s4n1W$=G&crExpc3Wk+`agHW|FLm;_&;~U|FPi* z;s4wX|Hp2T`H1j;Jf4_$2>-|K^4945KQ`7s7QZvLy|!BYAGdeb1g?+!|J%V{aA9># z!0S=)`oF-(|}_JYA3eE#v1WdNRQUf*Py*X8bD?}znH-P?ob`2{!D-*ulJ z9>v}8b^lXOlJ#QU+i`K2|M$BGue14oXP&%axf}lP)U(&x{6qLZZpZO}|8w_0pSmKTWqt5~#`?eR)5HI< z;rV7Cy~2+F>EgTK|9F2)7C#677kbi?$7<7wTGt{6G>%^TGFq2d47@OSWkY|P(- z|NHH=H>wxJ>EZv_6J$M8_&+utUs(T_Jz>fOCo=7XUEa(|lbt2sI3CdOe>^?bpPh2| zrMABz6DK*Tp0URH8^3;uZAZiZZ8>nc`ae7$R#uKR*8jc4f7rIe{}oI+G7`J=3iW;q zX3bXr$Hx3W_&*-MxLI@6|FJ`7&r$!!;~5hgrv8r|8xf-Zk4^u_j*5y>|HsDsKFt4P z=Ow48|KssbiHuhN$Hx3XtpCdnnKi{}dg-v8f8NCL>i>9ov*h^+|HsC>KKMW0o~d$r z_&;lT{J{V5@e3~q|HsDq^|*Mw=y`mHHJ)#GKCwNZ z$DP_X*7EYR)W0>L;s1F5z!y$jvB?^~aM6F(+x_dvJi+gr?&=BSokyNuGg5H>Nn1a7 zTsE{VPZa zQ~$?~n>E4dJTPSY3qJ|}$K!*S--};eVLfr2{GLzzpZ`DSsQ>F}U#0#p`DbUV{~H?G zs{W6?ef#M8zw8y;&sP7(9@=q^`akw+ndb-pcikm>)&H%L^?2d`*qir^`ahl?>*>P( zaXbB=yRrVSyRrT+dz<(_tpCg2z3&3`f9}ToziGZb>Ie58yg>aQ8y*n;&rW~#G4+3J zct7|*_P&D`ssCf2Exr!^kG)+kAO6qX@PF)02hUgk=Wh5v_I}w8|Hp<0#QMMNt^1Fu z|6^}EaDKqw%i!L5=%Rq_hYlVL=tYBr>i=#zmaF~`^Zi$C`IX<@9p}F7|LMm$>irsI zJs$W!cH>a4b4Kwm{0qu*)cg5X<*WZ=*T_5$_&;{z+A?SBC$IZkZp&6L*1ECE8GQDq z)*Ukc#COeW)=e^h1paUToNV=fm_G*p=Wh5vHs)Kv|J{2aOZ{KAtS1Ej$HwpF;s4kr zGCvUhkB#+>G5?R9u{>M-AG>~qNBtkWdsDvpKX$v!V}bu;_wVwl|6_NEr@;I_c9+bH zga2b={aW}x_Ubbm)c>&u&S_Eq$L-|K7B2$-=Wh5vcE5by{lMzSt+C$hSBf9A zUb(l!IX3lC>p}TEe(PHgTf_Se-2aeuyL{db|Hu0i-VOeb-7D(_-M0Jz>o%E}2>-{& z5B(n->qo->@$pyxh5uu>i}!2qzt^^R$nk~$|}Xq}SI^EXv~FZ<5Tms=-cyU!#FJ~at8F%g_*7-6|ZVSTgP>V zs{iBmgzj+le}iAmQ2&?M<5B;|PL}zCSpS!e&oANsE}oL1{x4trFZ>@H->-i7hke#q z&+hlT&$08T%IB>Sx1Qzy_*ZE{ND zyG_my|Hoc*ut)tLd*Oj@^?z)vp9TNN?%dy|{*R6APo`Jdb~OAS_aFWc{*R6IisAp< z4gbf+>EZv_n1=}e$Hw}~@PF)H@rm$%Z1_X?KQ_D}EE${rj}1Qv|L5+u$~e0{m}hqR zX))GVkL>mDMOrTt4;6DFJfPwKczKv7cxU8%+ukDU6aVp7bFDFtuK14G)|K-2W&gIB z*6_s76iyH5$^V#Qjn^CaKVDyje4h#b$Hsc7@PF*m-J|}Gjn`lJKQ>-(;s4m>(wP6p z_KN3&|6{kyyuE+D|KTY<9?%!<`i*t{{s#4bJbjZq{%^VTE!z&inic-0^+NG&kKgv1 zb(74aga6~@qsJBf@YH+NN$Tku4mCNKKKp`o%h5K>d$S%o-0ghhU4KAl?|R(2PrTn_ zr#&3dvOcW!#={-X%klSEuakLrOYXbFdWqbg_o{ETUVKmkNbytP4fNz6Jlu8lfjdS_p#2B z?>q57ZqE}B1OI2|*S^de?|(7>kJpd))0qFqhHruYb2t1SoBoeY|HuB~_}J+)#be3w zv&Qvd{vY=*Oa6TU|Hn>Qt@n?0+8SB^N&FwT)BmwE#rw(atzws~DaPX?pyB_xJx~69 z0{_R(mw8_Be{B4|3I2~=y>fK^9~<+%;Q!d1|HsDsLij)4A87bLHs;g8|MB!__&;u^ z|8qC|A3JABrusiNey;)l$IHX-o8bT44gbf6?}Pv2`BVE-)&E(`dTH=~Y`i~&|6}9# z9q@ndhW~Rn{2v=W5dQC*3lh}-!JonZxf}kE4Q~kl$Ig`R!!iGlohRR?!~e1I{Wbg_ zJ5l@^{2x0>zF&v`W5>w*J@`L&!~d~ydiXzg!~e09<@c0sV^=I6o&U$iyhP0ZV^@j4g#Tmv zq~ZVE4gbf+>lfz#xf}k^-SB^G%oBwFV`IJ==KrzVWS%PgACEWYA;SN$v7Q6`AKNFs zaKg|gYs?RX|Ks)=St=d=k6pc{QvDwrpD)4xv76UdsQ+U(iWh|cb2t1S8}p~(|JaQ? z>ec_Tv7P|@AA4}SPyHVo>kq*Hv6qS$?A~(38te1kbM$CHPygyM>s9jmmCX;GZ@prV z{Ql|13#i^jIeJT7O-yigEDRX8$ zcD?mN@tavcxxsqb)*7evk2hK`l>4jXy03cqez<3Y&*^{gChM+sRqFrve!peIsQ+VQ z{cZR^cK@(f{U5u$CCS-8=i6R>o{?V}?Ywa3x4ry4BPn~9`agaik(x74{U6(tHAnp) zJ0y3S`agDP!A$jk{Cpz1C{*YFv7-tXsQ+UpOMf=~VJ|zScy#_B+fzDQ=l`+OD(0#G zV;A`%)&H>zy%FmF#(LEMu}fsVUid$Dfz0cBvTww?vMX8rAGhaqC#nBqm&p5x#+RP4 z)5BB4|8YCK8`l42H_7KOKWcv7x*~XF{vW%#I$Zr9+bcc~^Z$7Ni_uspOQXT{U3W)ZkW#hN!_xUwNCC)`1Ypt;!@V4G{*3HGE{*R|`EgkiL?4FVeCwA3FJAHR?xify()KL@4gbf>!*=*THr5ly`oC=KAN(I1w-5f0jqUJ%{C>EvQ2u_1|6_OO z6|4VaR~6(sZ|0wA+tHZ+XO~x)@4)}D;RE6Sti>O~|G9h7gXdVo3wj^hXASQM|HsqU z$>mS!+;7*9^?u?1xPM&#*WK`c?3V1&^?%v$c<_I0tQQRb$HwKs|FJQDF=WkoK6(?J z|8M_2*2S5l{*R|eWBwnT{*R6Qf&XJ;o*?`mFCX&;G5?QUlUtzk|Jb2K&U|d4s_n>=k>e z0)2RJ2m8N?Q-jvqoiZh0e}m`!1$Xc~zc2HDPSAY6;D%pwA1}15ojsCt`js}n5B|^H z@PBOKIlBI@yJaoRk)5emsPBUh`su|J`!yHR>w)Xl|IH1Vq5jX^@PBNqj|>0Do;zcb`afRY{3+wr z|GE46=;L;MA(JLJ$uD1G`w!0+(l*x4WLY8gg^O+bIGJ|`{}*xo3H5)|WW8+oKQ=tz z3&)O(yu9+HdcS!yr>g&RH|GDb=gNG+oHx$5CpTYm}_Q31G|5?lPkBxbz@PBMvAN-%Y;s4wX|L1P_Ki)r>KMDWmZumdm-*~-)|6}9z5dQCLr;e-t z3!O66f&cscuP;;o7dvOJ`agDfXp}Q^{;-`tGCW58A1^O1E>8WQyF(IW{oXGgf7uDq z&KA#5K*RrWf8j$thgMk6o;Jbx_u=K%5vNa8|F`AFJ?j5Fvlcin`6@@)PPnWmB=i4% zv}d<^!09RS`^@{wtS1!LssH2l*)^T&|JZZtI@JGtH|H$%e`xqWc4$+V&i~`-Bis7a z|8cvgdr;^9u`>piI`Dt&?15zt{GYqw|Ew3SaHem}wf!wvKCJWq9{SBL^?x19)~f$w zcMok)|Ht!puic^kkKMce4E2BPMcekM|6?!SzE}Mpd+40=)c>(p?mMjW|Jdtgo*(A_ zu{VhCga2c1KX63-AA9S*^VI*b*B%b^eCv)}9PsyY<9UI->F^~1+Yg<)KcE*5_No8- zYeKgAKYTs||Hp2W&-3B`(k{ie4I``Dv#Z&+jf9QZ$OUnuM8UNiHj{?11-)b}lv`D_P&^%LuUna>9Q$L%d!%GLj| zn>Ux~{6BX6`bu5@mt80G1*bYM+xfBm(^p@#ZkFGZ!~Y#h&QLE{AfF$?|FMfV*Q)eWv&T}^|E0?3sqlYn%tL|yW8?eI(won=PFy7OKg9o4U6Z2z zFKKax`oA6HQ`G;}h>!f~b6fqBx|033-*}a;QC=T6+`q|RaVkl@pLaOZ`TH&F{aZ7V z)cdvVC=<^#?1veH@2lHc<}5h5%DV0B8lC^g?eI77f9xjlX7GP(c(Pq@FZ55?ouIz2 zQ`X~s{I&sWcs=+(Zf_NT2mi;0$E)1h>A!n&f_f!KlXCjU-&oM#8ZSwbG#X|utzR9|KW2X8)US9L6Bw26t4%^-}9PdQj^9}2c zRk847)`ctM@O`Lt!BDLFKkiTL%1HHp?5O2o>i^hzE27l@vGa$b9r!a5C7+G@n>T#UQ2wMHP&;L z`E>ye|HtEp?c%R&dzN@HIiA+J!&qOq&l>(gZm)HftTzk)$Nk9>F9H9@&R$)t{!dJe z`o9#J2L=DfP7*JO|FJQjOSV_ITlTMlmxuX!a{1QqY4Cr%J^20<{*PTR|2}~KW5Y*c z{vR7Y66^o6>HpYSGA|AOkB#%g|8ajx<@UkIOhMcQ#Vzq|6^l2*8gQE$^1X~ zKX#_9UkU%mPM3LD@PF*I)jD6&I$hQahX3Pstj`Mn=WeY3>u#CXRmJ0r^;^Z?Si@(+ z|8aY^eE$po$HqK3S?|&s^UJXQFE1bS<*@#*yRrT+J8e;(uK&wUmG@Kde{7$8KMeoJ zu9Sc8!T+)0$Ke0CKdG|*8Rq}7;pgE0+ztQdZumcU!~eM({?Fa;e;>RTtNst~58?mV zDKZ}#{*R6A@PF=x|8qC|9~4`)A@hw#GVxOf9&xCN$UUD6Bl~a|M7UG$h>X%KX=3bv7>rD>i^iW18M62 z*f@Uhe{38d_&;`n+6V`{egL@PBL^U-&;Z-rvLju`7Es)&IF0{*Tv(^$X$u z*kxU*>i^gYy=m(I*ol4Vy8bV_s7L&!_&;~U|FP5M`r-fBDP3vm|JdQZ$?E^u(XzfW z=KrzF<=;b?|HsDqikSb$uIlrs|6_aQ-#_qw>@t~$4*$n4mB%Oi9~-~Vg8y?j{2$vR z|DLRdd3hc&i0)t?d26Ly_xjmOtBU*BzAD}TSvdu6XR{3-k& zuOI#t^Z(fGOY+qJxf}EU*q!44;s4lO^7j<}kKG}@AO4TsCVwB{|Jd;V@PF)b`TGa| z$HwKs|FJvd?*ZojvHRuy3;Z8@*@hDJf9z)Ql<~ee!vY|Kv$K zefybB&g0Xsu*XC9-Zpu?xYD{qyx?EGR|Ry)qN}ajWqpf+o!3~m>}rzr#IN)6@6X`& zYR8*>z4gK!HO}(p8?4uCZgKXlzR`N+`UYpi)USH^{-IswO~U{2{dL>MYW#l2x=GeI zxa^~^S>yA-yC>gbT_^9yoT=aT^7D-%dHrd*?b}{{e$~(z?_A}**UQg03X5htUyHcc z%g- zQRn}$vt|Fjx#CeTJF`Ak{U5ueE>`^?yRdq6{vW%lK1%2Ru^T&*)&H>z+LP4(v9p_E z)&H?8i^iKZL#YA*adB)>;JOL;k;Q!c_^7je; zkB#>?nE%Jd^Bew;jrXtbSG{Q6BJamB|BuIi@ld(?KlZ}qrRx9Ktumi=+BL7*>6@42 ztN-KWcgXd@|FJt|UM>6|8{QB8kKHEk&*A^rSU>&d$e(%n`BUxsDxLqw#{R+ov3nNg ztN&wTULgD*8=vRH|FN^B;s4l}--r2s>?Ha7hxvcppLqHEg86@J`agGL{vR9jBeDK3 zJEtr}{U5uec#ir%c2VIh^?z*4*Zke^hjxC<*TnokZqHAfr2dbc;~DR~clMv``8PLh zqWV8RA7{$~S=YY&iEU3yoT&bf+tZUKIh!*+^YZh^lxX=rR{S43K6Ik`KR(~bg^hP& z7yrXv4^9i8p#G1q53}P>SO3QjO`WR#k6oWOP5mFcvtYjZKX!h8lKMZs{!~;1`oGGu z!1XJ!KJXjf)jocI53lC08xCmrKW@i-H26Pv!~e0HipzBVpSv;tj}31J|L1P_KX=3b zvEdKl|Jd+e@PBN0F!(=qX=$nYKX!?D8TdaoE)V|C-B|zE-B|yZU6og${*T`$=M~8B zeZ>E<3yMblA5RZ22mi;0--G{ST2mi;*gRg}DV|V1|tN&xeBf|f&dy7Z? zAG^CSNBtig>rcb~u`!Pg{*PT#S*8Aujd_;ve{A?t_&+x0?ZN-CmrBF`u?I^>{U5up zxLEz4yW#)b4gbf6?}GnxH~b$Pmk0mHhF66D-{1|APN>H|GDj8~)GTZco)x z8aR(GxP$#!@cOjv)q$R`vo_HCtqj_}!doq$K0S3V|1a44E%XL@xi6b980`ImJ9r*n z@VvejU!W(1ujIbr{|9@&U=N6SjPBFp@#Jo-f9-C}Cv|u5@%^$6_I>cH?#shG$^WT? zPao{{g6I8V{+j#pf_uue!1a5BJJ|m@U(&qggyX*Rq zcT-NP=fmZ#N*`;SzUr>)Y&#nMkEch&|G69fkB!TN|8qC|pS$7z+ztQd?yD}iI$(dr z_6GEe$F8!b|KsiB{68^!0rUUZ@PP1tY}}rl`>qrc(9^gk=fi2r?JN(~dS3=#Qa(6|AvOIRS$@U|6@mn%vb-%4xc+u{U0w6^YdPO@G{#U z___~s#v1ed;QzS)==*+f;fSn}tlkXIhkrK*HvFG_h8-~f&)x8U=dL@h{%^MUFUc0%kt^?&ZZ;=^Nh`i$5RC+(V}c6sSB z^PB~9#~SMiM~xh|`+LUZ)0{Ue#(I|A->H2^?DA&H((godd9W6w#= zR{zJInQ#;j~$j#i<@p+@b!jq^VQ=AG@->PyHWH-_+T! z{*T?(yGZ>XyHh+O*8gSqh&ROiKlZ?~)$0G)OIEE{|Htkh-lG1Gy>!zq^?&TG+jpz~ zWAEH`j`~0Lu04kW{yv^1>leHKUT)kUI1h01!3zVnpMB0AXU5C#`dgpMQ192>)2aTC zjn7Zu|Je2Nc?taAf!qxBfB5_a{_lzX>FWQgXZF++L>skKHZnp~C;U8~%^ox~)w8pSv;tkKMSrQ2iep>&0RIU-yft z>igik4%0qod5mrSr4u&c9!1sg7u;erRx89 z`d;yD@PF(+`8*Z=j}6ZT|HsDqH1L1yj;&Sd|J;4|OMd^;7p16wYLw&k<6BQzH}9-) zo{l-|P zqv8K}ygTLgeDcWy)|eOg=5zO3!vh}Ax!)cSnDXrkoAgNpSs(c{x7^cQ#~MV|4qy9wCz2+ed_;s{=U66 z>i^io;sxRV*vqz8ssCd)tpO_&?qrJbvN-*eT8Pou|{Ux1Q88S^Xckr)?hfe{Ad@{2wnrQ+~gV z^?%vXU2%@@!7Hre`;weLe|Ey|&m#Fg6YKx-@qqqQ!e!Q(@_iZnA0I!t^7;Y)$H#kx ztPcbK$1drS@9$*(A0Pj5J<;m_*fCv^&YD|}+V&(_{}}84e)@NhdO(lNC&c_eHa`DM zk@yKUiE(wvPP`V_Y)5Y|Htm#SFiq$&GmoX4gbgP zl=*V-f0#Lk^?iE}wyXbR!{@>Ou{*@8!T+%_pAP;HX6>JMUhZp?^*!PLti_+f|G69f zk3Ask+4f%AU_B`F=tBGJtQVfsxXWmumZihPA_r!+3#DBBlE#d#zEpq(f|JW(6#ohT$8I{< z;!JpMmj4^ovFg*>WZsF7aXGt>NEpIrlW{ zewl~2zQwWLa9)qI(DTnzy#6%@I-D!7|Jy0<-{5&|PE6XLtrs2XaPEBckJd|$bvuR4 z9|rWu>+f4Hmi=#C|7+`oa{FHU?3dP?WWCyz=f7dSPQ2-d^Ix-GB#)=ZK6u&oZ=uZB zt3B{v*1ZQCogdDA!MbZ7)~9{O8uLux|9Jc0=i&d@SicPZkL?@Q`DWH7%hH{R=YPw( zcxjsYKb{`*T-(FHaY{^*db>*XZ8up*$oIeUeW-Pm_%iW3*5NYmPJB;5i~q5%5RY{5 z_6q}A{E#(#n)srChX3RKB&;e{|HqCO4+a0nhOdMFbGP_|Q({2Wr@>E&XRwBkg8$>` zG2agJ|J)7#XDuEL{?Fa=-_}@P74!eNJ!^F#{FgO69{eA-!?zvy{4Y;(|M30$bsPRW zpdb9{tJXL@{2$Lx|HsDd|H*f5vh8U2Kie+zmEix_C2K3x|FLUVm#P0_W4;{x9~<+u z;s4lPnIDMxf8764S#J{lk6k354*z54$$Iwif9{6=yCM{s?IJ zKR$jr|BsE!lYgt)b~M)i<#wDN{*R6MRq}kZ_KDAvd4$&GYb)j7+wWUf%6gN(e(bN- zHS&8OdA+LQ<#}cP6xRP`=gIMd|Ksh+mA}XG-_|&O^7sm9_&=T=`wRcaE*yeatg&t$ z(s^A~JiZO`{V)6<8}s+z|JX$`ZxQ~FoiFQ`!vC=`uMz%_*N68X@PF=x|Fag~CC~4G zhX3Ps%rArgW0&-1i0``EuFoUe;s1F3$+8{(kDb(;qW+H!-v%aZxpIe8BuZtc3j&Ij_tx0I@z;DD z(DM3XjniZPANLQJhxvc(c`~05^Z(eh`cl;Y@p!@a!T+&iWPTs~ADjM<9VhSK<@s*g zv3@fAAGc#ZAp9RYUFQG8|G69fkB!G8{2x14ydV4@oBofD-_yu{+xED{nd<+zJ$?y1 zX@YHsw}SuU_6qTd@P9lW@E@4}$A%Y!|6`}i@qzziXUOq`|6}9+#{55bAOA{$b-Z|p zwik=6<77Rufpy zn^Trr2eBl4s z*?rmS|JXS)&kFvJ?d{7||HrQC&2ixW*y*zVCHx;dL;MW<6Nc|u8$J<|^{*PTb zP@w+L-SB_xdO1J*AG=o05C6w5l=V>I|JVfs`Rf1J=>vu8|JWIFdGLSi5?L=5{*PU@ ztVI1E8-G9H|JbGSe8v1fcJ|^l^?&TLHHGT`*sb#Z2=o8gE%JT`{*T=$J_-JhkEd>V z{{sKVu3uB3{?Fa;e{9TSg#Tl=$oxL|KmI-H+fc9mkKMnqLH!@QcTSvQN1d~5gDtuasXpO@caT_he9{*RwuHgsmH z|KsNy`4!)w+Tzv!v7=iP)c>)gTH@9JxjUif3ERIo@qKx3JYkm)--q>odHSMGkNQ8h zM?4tj|FM%~e%saipR$e>&sWs`j9q?0XM*}ao<6fJS^Xb7qcutWAKTLquJixc`8~<% z|Jazv3jfE(yjJ)>wojhV@PF)@#f9qs*zkAof9wuQBvyu9w^#p?gqm?sGT$8KIx>U{KHuX*`-QtL`tFZI)(TDPq#SO3TD%_~Zr z$1nJqchQ^4{?jwA^(~Wm-&cP74eLSqyb1IFc={H3{{sKVZj$vt;Q!e0i_t9k?5JF{*RrRI_m$}sp1d6 zceCSTPby4wUMn7F9a59)yz}B%mz3uQe4kTX7PvkzyvO~2S>@yRrRcD~ueOGtI{43F z>(+`gC+F$)KKcRp6|DbDUx0@HV`DvE_&+v0AN(KNS5Tz$|Jd|@Z2CVo){BMzW8?gL zW477;;rwsKZ?`ThEOP3TcUYGf73=&z-rfpX&lU6k*w~Ksf7unKh3fyA7F{2#9$^X{H}VxN!x zqdX(cIecorwKpeA{U1*czxPVkAv-_(-D}UBYo~`Ng#Y8^!SBKUv9Ujx|HsDsGx$Gt zS82ZbKXzwHp87vFd>;HCyGQ&a{2v?hDB=IuIDYVdY`D)bvv2pqEf9wI7ms#ey*hk-k`)~Q} zfqkCm659^{dF$Yn7Z{{2%Y{HgB=|KlVazsroqko;S^JD)WJa{so-QN!f&yNdktdH$JeXySk?oMBzhl8JVpFem#+(k04(7ipl z2fcy5aG|d*;Pk=Q7u>=77u><~{_y(e-k)HP7kqqzJza1IUtVwrd&)(=z~hDajqd#k z?vCof`G)Pj|Jefu-=E{AO%AyH;QrrwzezH0&Aq>v59e+tXgyzeHTU-5hBtC=pDy0* zj`SNw22zfj_k;g)H~b$Pmk0mnZumcU!~e12>EQp|4gcqE_&;~U|FLm>@PBOhLHNIE z|2%G95&qBJ@PF>!^XXM1Vtmz~Ij4`mjmtj~cg={*OblJ8qX37apPhkNXoJ5$TlnU26M3IW*j<{q$lxp5tcERsYB1kM(=u z|Jd+@e>{A2BxlQ|>iaP7Z|V5JhX1qeGpDHkW8?V&|Hp<;ga6~@&yf39=I2^t9_G&5 z&$s=>JjtPivBvznj+>6zc3j@O%}4F_z^{G%xg*w?cQ{l#)-z=Y zCOY4~aH*X>HckA7%>PS!WV?F6m{gDYKX#(L-~8nprM5j;-jBlnh40;_{x2u9Nc|r> zBURSVl=*+`=2Tg~MEoCnu()3RAKO>ip#G0tSKXrikKIt)rvA^}@PBM?ZL9h}c6zq_ zUg(?IwmnHaV*e{y*7M_1)c^7HArVRH|JajfhN=H!kDE4M{U6&IH%~T}3ssCe-pFY$1=k{bf-V^6V1^j)S8JQH&X));m-Phdj#6R_( zfBT1N>Yd64Th#yEB>t}clCStm2b!JF-~N^Vm6uc1_qECAiMQVSj&YkEU;8qT`agD$tS-sISzGuSI)~(yU&e6Y(SaRPad2PF@)&H@Z#kax#@%rJz$40#Xgw&WcblrU$KTC%-?g5J>Ib1@&|8z%YQs3 zRXu9U)>7xyyYIGc+g|P*$i3ShuPr;PoD}CSYj{ccKRzE?&l>fAY^AG8OJN5_j|G2$Xyy=Zaw^+mHops=AcKvnYW8we!d@5g`uj~Kv{B=9z--ojP zFT3&!|HrP9`|tW0H`;cOc(S@*TyH&HeBSTxy3V?(YqoRk+1FYxUX|d~G+$%gDc_&N z|MBwMWnRwH8?UtetC#O5vHmZQcX>y=`aeG3E5zHu|MB^ZhW}${^e3tRf{*R6C2gf~p z$j{D~^}%`~&b8+Hzq=xm)CZ!EzOdJS+og&6`774n`_b9E0~+i9PTHBE{;xzX5B~3l z7vj|aRmtba@PGfhJ68Q)tE^vm(WG_$l_z7=`wfWSobL?#u_i3MUX%F0WzVm)hX1?e z(iPUNXV*Kw>0K7kS>a2p;nCp#czNg#=MVT{&eZdX-}^MS*S}$EwE8ftC;Qk3UDlnl zKJ0-9I;=a+su3U6X5Dgz%vWk^3FsfrZn9n~&%cvz)>|*$Tr8fW)_OqvcEq;ofPTBg zYhARf%DHu1rFEq||FU;kzexo@~c| zvop?Wka=zq)=l#I{_$7C0{W5l3#=P=d7XWEA=VAD{#W%s=2&O!Yf%5k%g@~3sQ!#)Y=)b)42kXW&E9L#w@2so06~p^jH*YO+uDJ160Ued|OY3&={)|mdC6AV`r|2Q~&2~_&+v$AN-%YG5?QUy(ASr z<`j=--SQ0aM&GoqkoDo=|G2$Y<_n7_vrd-zCh&jUp0=$){U1A1<{88Pv9q?+z@J%T z-V6L6w>QZ5x$u8%%%6b&bGNKNdP-(Gncowi6wvU0Jbj70AAPxAbQ;sr7Pj}6}l|L1P_KWn*t@PBOhI?VrLV}7jMUTd#>e+U1^ z?X|rL>i^i@&KP{Z|HSsAk^VjY6TXDLIO*xu$%BdV?*Yf*c6b^1Ki(e9R}w#Hjd{0n zd#y8MJNzH7Z-LCeh5uuR%RF%SKR&(-mt^StKX=3bv2pqEe{6Um_&>H!d=UH}yGGUr zhW}&Z_{0CPvlnHm|6^Clzdzvr*cCF*O7_2s`#X1Goccd^%j3tkmk%bZ|Ks*Dna2kI z$4-%!^+2n5{F3_;;Crkwe+%>fxV=K=*TDa=i~Ew*|FKKu{)Yc!XURM>_&+w@|G@w8 z`orY?6#O4MTpl0rf9y2*z8wCKjrTk7f9yP2uMhsu-SB_Bz6J983HU#E!~e0dz8~iQ zv2(i;)&H?^eVG5}Zumc5ANCLakK0q^{P2J5>D@8v|JXBofkDVy<(%}F2 z_{QbK|G69fkEe$Rg#TkF$b4(~KlYTqMD>5{>4P5ie{A?Z_&+v0A^aa3_aFQp8}Db~ z|Jd+r@PFLDa+$XW|HsDqyzqbQY~c9h z{2#ki{yhu-$Hw}+@PF)V@!0TxZ1^JhKQ??3{2v=0TK?O*Q08Zf^|4MA&nvU!tmB3X z)&KGQ*gyC`Hr5-5|Kst%zdzvr*bVahhyP<^JNzHJMtmgv9~*|Hp=Jg#Tlgf8qbwCEZ!-|Jb;G_&;{4_#yZ|HvAyw|8ajR>l{5RjuUS{EmU+Ve`MPzneEtdl$ImzF zWgaNz|MByT+=>wOfBgKxTRb}dkL@cN^?&S~(oz4%E~|}K|Hsa3mG^H?JmBT$6Gig( z2L6u?KP#WldF}M_`^cAy9p;CSBf{p`oHX|t`zlu zY|Lkc|6_aQ`49ic#=JZDKQ`9G#r!{Zz5Koc{*T=#zdwTiDQfj*|wv1Jo<_? z)=$U!zdV1n{2mJakKHj;qW+KFF6*_!|FJ8?_rd@1^QEfcO7(y2a+xoP`G4$e@!#-& z{QRjw-Y>!bvFqgXH~2rEzDd^0h5utW)Gko}$Ig@O@PF(a*$)55#^V|OkNXS12mi-T zD4eeTj~$&eN&O!?D|3?iKXzK`>FWR3A*qwp|FJ_ermFvA$EA<@KX)Hk^n1I1uzm3G zAFSgurmO$s=Y{d9^VI*j8}t9zS!vVN|MBxjcs%$&c6LgL`agDV+5+c>BY(5)sVVc- z|MB^s;t5gz$F5GBrT&kv7tML0>i^gcIdgUXA3HD7QUAw|i9B8XAG@M7PW>OdxF{pw z`D@PGV%6b=8!hDU+_b2t1SzyGEGWcXx|FmVhyi0H*%{r{U7&_{*PTEz6k!0UFxk?|Hm$o`CjmU?1G9? z^?z)5EX@C7!^gn?vAt#G_kh_6Pot4PS)$e?0x#vQqVb?3IND>i>B9uEIj~f9ziIiSU1H>>vCe8}rZL z|Jd+OnE&T)%>QG<@4^4Ed*u4y|Ja!C2mi;0M}z-kFO>D6;s4l+#FN7RvHMF4)c>&u z$_jPr1)Jwhz`+Iw|{(+x4SmU#wR));fRK zf5LiIQ=R%h?l0!w!T+)Gcz1g$93OY%{&Y9)FL(FLQ{acmwC}1<(7#^TB<2!Co)e_XT^vuAt)=eE#4L z_J_gq3WK}5Ch+zyt_}2oi{$a)-v8j^6Fi>~Udw&@;Q4=FwjKV)eg5G7viX0(-tYg_ zbH8)_$hCEssL#Rnk=(I{f7^23b+#Sz>_YR$8h#M|Po8t?1>pzb|Jb-Z_&+xN9~<-c z;Q!nW|HsDlFS+QN5t->}zHiUuz=r>GZ-@VLcludZkKFt7%hdbf^6q~5>XG&L99Lh3 zejru$Z`VoneYkzHc4|Pw|GBrr|FPk>es|h6BVz7G=kZCy|GBrr|GB&9(krdun=t>6 z+u_CF|Jay+hWUSNJYGK9H`efR@PE91H2fbM>;1z2vEifO|Jd+;{ogxb9WgJ&Iiqf@ z;r~whkK1i@1ic|v{Vf{<|af4o01zpeJR^X>kg zC-c$nY&&L;H>}SK|M&LJi`4_7;s4lSGCvdZ|Jd^;ou>Ye4L`Z%)+2WLxWDA@r#(L4 z{owz&zwm(Ye{4K{;s4wX|Hs<{j|cz9hS!7tb2t1S8>ff=W8?7#|L1Ob|6z|;`ad48 zsS_ut|6}9v0{_RyJB}axA3JaI4E2BP%+n`3@PF*cDW|Fbb2t1SFF$mWc;MUi*z;w+ zyd25uKU6KdRYg_eZA81H7$ft96>3f2d}Q^@Itd z{*SLuc>K?QZi78OF#i$$kM}n`Df}OMa%7nLKlY5cXy*?*hiyCj-}7g#woZ*taBkYO z$~q-3-r0T5N^5L~|KsK5#3!o%b2sMyv2l9L|6^w+djek1Jsyv9{v}IndvbEJ^QX#X zcKag|lI8o?nvqW~+~Xgf{aasja;j7PShaP2T8Z<=pZcr|(o3D2{_M3*%`9}<=Zfjt!r@>ZLSz=@qLpnD!2C4wK)%duXv>K;a&b;pYz|o^4fMM zt)0nJb^af>I}<0X|8ut| zF2ye25kEMm*%Q$4f81Y3UY~z^ZIbo42@{=J!@u!=`ng9vpCgaYJ)gYq|L*xI>iy=( zdf)JW?5z4?^?y9Qcc4lAU($Au`ak?W5&nrr8^?$Zq=J~<@xf}kEjrCJ8|1W1-qWZs9nOB1Of9$3eMe6_9x_*TC zKX#kUYk~h8`gMZ(KQ#Ow8}q;5|JV)dOV$6e@%v=>KX#|wo_Evz{*!|V>Y2KCdhz+3 zHRkPoe$JD2dU&zL-;sHLU!1;vXC*%Wv#yct@PEAgI`Jd$e{7uov*|ML?~C)}^5pYJ zYk0v~;{SMhcs=+(-u@=>KB+g}Zw-Ifz2iRXo}JasXXEa(SCR|FJRO z4*rkbE`Dh3e}BumRpu>4wtUNPk3ZQC|F`O?Wc7d@a{W*2ziX`J@^9<7(;Dk1zw+`O z_IPeSvqtCt@%hoZyUt14e!Fe&+*Kid|F(dJ|KsVKwpTa_Z{1?s8^kOA*F9giu3wj@ z{*TX}y0y9L|J;rBf7y*23e^Ac@{8p5V*VeyOzt1}KQi^iy zi#_W9*hQ<$)&H?e*NQI{|Hu7-4}t&V@x^>Q%>U!@FYb?4|Hu2QWFSWUA3G20i~Z#i zyZ>_J`%w5lKL4`h`}$Ws7X|c38!xcOPqwUQh4p{=_(Nm<9~(aKlD$W)JzX)*1D%Jh zW4ja8|MBsivM59SADi?4p8i3+`oH3(GQU*(-zVO9^?&K|eJT7O8{fySU$o1g@Iai- z1B6d_VERt$68Swj{9nVCX!U0D^tDD(H=|F|9V?co1l&VJ{)+}FCdQT-pgS|0DG z{@(6i-W;Lc3w_>mt=5I&)8PMjdNlkWyJ6d?|6|u}8TEhc8fo}HcB9NMh5ut0?`l^6 z$1XXuMdquO+4hz*>z%BtORQVP&%yuk_I2%Ua2`o5u{Vw+H{n z#{5F~KX$*I9{!I#D83N>&)x8U>^?c3@PF=x|6{}V!KSbq<@E>u&BpULJ|xVJceD6* znO9}qu%%Z0A5UMi!7H9)j&0A`TUUR<8My2uG~>CUSzU0=A+i0 zG0__9$;1Eg@z8%}o%%mEUe9Ch{?94)fXqX^t@a<*@ZGY$s&(_`GUt(q=Q~Ui=@sWvCQ>$ht;O5C6yQB{F{$ z^Z(dUG7o3U^5<=TVr9O9%zLxOyrYOqPX+WXiH}+1^#J~lmxmVrV%sr43I31At4RC< z{2#kS=9R(!vCG9{!~d}hHu%*4u?uB=GtB>Emv5|8|Hm#}Uk?9c+biVw-j#mgDKQ)B z`O4N5i!V81jo0_>-#utuDeK9?|MB#x@_P>WKQ`7&h5zIAVf|eAKQ`9yh5zH}i=^TI z+ztQ7)5H5={-3+y|JXS)9})hKohg6c;Q!e4f4qEnKKMU2{U1-CC$H!5f7~7`_ZR#h zJ5FBD;s4n5e>}gw-i!ZZ!{5OFv9sjw2mBu!^Y7sQ+ztQ7&Jqs~|Ht<9#N+vEjlW-* z|Htid;-TRG?(Yj%|2Lz1)c>*PiC@D1*a-_$)&KGKB+5KG_&;|1pw3IPPFk#9u#($j z|JVuQ{ow!D$>J~J|JaG*E#d#z z@p6A*{vR9b*UIZv756Vq=7+)mu^pLzg!zBga=hXH*i*$1V*Vd{x_HD7@6V~??T-*I z0{_Pjm+zn9|JX6|eg^)J9i{Ws7_f=Q2ZYo z^Pe&QkDV&>xZwZTiCyV({O+~J;}`yq+oR?88t{MY3Ec_m|Jajc|1tlMjrnWvf9#pE ze^1Z&fi=dELH!<{Y{g<=UD&O-SB^G_!-RqW0wxe@AK|# zux^+2CgK0M9S#4-hDU+_b2sMyv5Vw*!T)jp(C~k3ov$nYkB#-mG5?R9D_#im|JZp; z<@<7(|HsZ0F9`p~#(LxMf9%|WJoSIp0Pm%RZG5?S4$UHXqKkK$co&U!k-<+!ck3FL&PyL^D zUyb@d_JU=tI{%MdytGgKAG>ttDZC{U5t$%_{YO?C#-}>i^h{YnG}1V^^;jRR71nPX*!&vHq{SvHmYR zS3Da0AG<)j8s`78JLUNd|L1P_KX&`-3iW?%ydJ>+vHQi-!vC?`#H+#o@$-$UzAW{B z{5&Jo8>Z|3^7F5>l1OK7!*{%FPhl87|FTXh99{pHpH~#r#i{>eW1b)UA3u*MkiXaP ze{9bGW0#0OhyP<&%6v=sKel&Kf%-o-KF^TP2W@+q_-^<=ZpV7H@PBNqcP*bkTEl;1 z{vWqvo;duUyW#)b4gbfk5+4Wu$1arjYk!M<&Kf=!{*T+ySpS!e`ML0a>{R)C4gbf+ z`t|*)%7W^N(MP9$)|JbcEpAY_z$G>9vsQ=@3>@WNuyLwo>w)j7GrTB07KQ`9K z!TP^!d|nLy$M(wK3-~{NzEmpf2R|?K|JeBb2>c%#zaN4BC@H!aeH{?==?u6<^$fA{gK@tm=6g5$NMKabGG_Fc4GQWXZpU6 zz5M(zO!mir>&Nzdi^vGk^?&(%49yNx|Hsp#;s4x?`G4#MS)uCx*mLCaHXi-l%jbVs zex&+8c2ZfC`aiy2r27)o|FLUoWWL8_$H&gdn4)FSg*mv#c?XOXky9_f(Xt|8t)o z^Z(fJSMY!ChW}$@9wYo8uMg`l!~eM({*R|$F6+Z${vUg>cs9)c-}##*z5gY zE%O`QwQdxP#~aO_zCQ?$g6Jxf{O8-S9*1hG+ZVHvC^x<3;NKaDMndcf9y6{U00i_u&8B4gbf64}|}d*97%{X!t)iE+78S z-SB^GTp#@3yFa-^{U1&b|99gzE>-`h`zQ1Njvu*9ecFUC{NJJB`5{&4fFrl6DOap{*R6IS>gZKQ)GS`{2zOUtk(+v=Wh5vYw=z1e{9S@ga2bsn>Nk) z`Cm_3)BlO#Q;#@z?p*bMZ2CVo{U00NPyTy^jd_3Ye{A|cc5XzB)B5_QcKunQkMF zAN-%Y;s4wX|L1P_KQ_D}{GYX4AN(JW4<3J*|Hp<0#r!`u=Jmn<@%CVzAN(J?LLM)e z|Hm#7&jkO+rvGC{OdhB6|9JT!@_fPkKX;##w%7J|n)trY682b6m6xBtUvs8Czwml8 z?}}a4xINjIonf6XKC|V*oz_|Me8v1f-v98KnE%H{yXkB$2m z^Z(fMWIbT`KX!O%l=?q*Tuh?+KXy_=iuymcCn-(+AGQBv z?4+c?d2)$~m>)6r?~VA_!0icf$?E^^`Ohx(fWDYi^?&S+%wqL_?CermzfSxgyR5E5 z{U5ueX4L<&i>q7J|FN+h{*PTM-tVE?%dFGt+nj6PC>go_`)Byi`QUwDa&?ol=5NK; ziQWdMAatxFiYlFP#YMI~D^u2M=`XZS@uWFl-BnonOC~63{PBA8VZcu>y~6$K|>2 z4|rzyzozSw)cN zjrD)o`279*cm2XY{Idl0e(-UhKJ%vk%FYD!e(-bff9!=DE7bq7t2dRX|6|u~k@+@@ zUh{wV*?9GSgVOMS?0z{t{2#kPya4>4yW#)XzKx^)kL{K9MKJ%*-SB^Gtal3k$Hwi0 z|2sDg zuS34?me0?udsb%Q^EK-}nHL8C$I~~iFI4}>ZWkXXpWoSb%!h;j<90OspS$7zxIfk6 zQRMSO+g^93_&o7{JUtrzkB#|w@P9mi+wN-hf4u$hBk+H0td9u)$6mg>N&O#>_t4%J z=k3?-wc}sAr^R{U&Tm^+$ojYU9=OLE^9SMo`1t9Q`GoL)d^}?N_{h7hF<>3B=qt7z>jOtUd82jB7O(UCB{x`O z9_Egv*IUYZU*-{mEKe?rbi* zBB0^_c>IfHeY#(K@3?h=tUreNf4sji{{;SzT_WqBJ^j6ltuqH?y_Xv=3h2i_zrgPQ zR9W9H#CN_uo|0vKxXO@Y);eG2gCo`+S$_upkB?WZUyS*Gd^{)gC#(Ns=ZHVV`oFXG z#g48IEItta&-ZbR`o991Uj+ZhE|m4n;QzL-k5T`J`9<)5>;_psskUx|{|{ji>isHZ z{d4#~c9X1k4*wT(B3%7n^UiYhe{9VEd+oF3eyj;QI=`>MxzWGW8vgILXBPP}GY+1w zL3-1rgVy!p)nq=Cb<=@1r)YJLAI9wUZ=Cd@|DM%ljrD2a|G2$P=DorHu^acbJB^n& zTQ}|R5HHne-6GpxO0BnUKBo=yy{s$5Ck{U4vn~-|7;$NpHJ(3jFRZYxI@72AkGHQ$ z8vc)sd3Z8k*c$7@!~bzR)?i^g!eevr5*acnD>i^gwGQaGFuYF+W4_lZdzU)2gh5?WBvzOnoZWM2{ za{Vu?>%?dL_TR5t*T{N);-##;GEd|0Sub0c%RH>}p8J9IbeYcu|Hu8Awx2K}=}T9Q&i`|__z2rxAYK9fkNb;;|6}9)@PF=x|6}9&F#nI2 zkB0xV7Egoue>^?r6T<&-`|P1C^?&TStFZsC+IFu0%k#q*V*VdHVrjbiKX&+%G#r21 zPXEX4X!t+&s3**|#(YBfKWC3tpCgXO%=a_`G0>&2vrZ5B7Oz`W5a98 z@u;xVi|2&@V`IHy%>Q$@oW7Ec`$IgOHRc_{|8akEhUNGD;{VvWYf5qZtm-Q$LCAhCZGC0c81Kag#Tk_%KS_CKX$Inzl8r|H*RiJ|HtdEU0;jiSH+IlTCe_( z9kpFfA0Jc2+ZVmHK|GtsI(B=L`af>3k@X4T|JdHOHR}J^$>MY2|J;rFf9(8q)$0G) zd24;@|Jcbge+d4MowTY_{U7%?T6_ZhAA5m#9r!W9Q5M!2hxHWS$uOA3I}7f%-o-JQ4gK zJ5v7rB(JYy`zwA;{I&H0d3}=CXX{XTd}IC}AK$pWnE&T)%>U!%r-%=M|6`|#2Z8@% z#}8Mj|6?b~{RRJLE%!J4pS$7z*q-%u>i^j3o14`Cu|1n>)&Ft-(&h07|HsbU-k|=E zoxQV3{U6WYxus71AG=+i5Ac8NDtSJ^|FLW3@eBXQ9@yNV{?Fa;f9%qAHR}J^m9pL@ z{2#k-W3Bo>cF+21o&U%7t{L@z?uP$k^kuy@PBM<$NWEbjlBOqGE`|D zE4~^2kNck>^HJgd*p1@l;Q!c7@_qvTkKHQoC*c3sErU7g|Jay!2>-{flYd{q|FP4h z;s3aQsWSf%{*R6Idollyjd_;vf7asX;Q!e0H}HRKtZxke=Wh5vcD$_biTQu*nC1la zf9%MXSoMGGu*N6{{*N8rl%)QT9nqYu^Z$~sU!eXkvnf;kAG@TtMCbpp7xc?Ke(`_o zkY2C)KX!6&jru=!+F*nFKelJE)q(%x^=Gf>RsYAXSw5itk6kykQ2igfeDkpSKX&b| z&FcTy9cONHI^RBO_gB~M9rAoWX1#ddStA->VfBCPmB-Fk|Hs~O-VybG?CpmRtN&x~IrlvEe|)^5 zvHmZ6?|J8`|8qCy|FMS;?Nk59UUl$n^?&^PwDO$o>i^iwc5l}Cf9xe^ZBYNm?%ldl z{U3YT>Mr$v?EWQ9c)#Igx5+%ip_`UxoXSTtp~)j%ilX|tS626 zfBgIc^CG_%aj%!3Z{>DosQ+Up)yAs-V`nwQI?GSH-^-3;s4kT^8Nt+k6kLS$MApdhW}&Z_owiG?Bd}H^?&R-{fXpT_-$1bRztNxFlH|1A`s{do>RV+~d$J3|( zAI{zb%8u$v+b)43O0AAkOX?tXROg&;M|I9wIcKS*R%+#(6UteDKx7OK7#o9IfYUhP zv43n2_F!-}GkCB)&f^b%``xW~cisE1HD3N^ty#k}=hUflt4>v4RXz9Jg@Nk-xf%W+ zIW|Y~RKEVM&1YJ=n94qy7k^e^?CXD*OaC0aM^0|b*8D$mN_&p_f8?CjboKvu{pWXNssBgL>dJPm z{OE6Xf5@Gkr~V(GkH*i+Q~!@VQG9RI|0OqN1#12uxh~C5{`EHa{;eW6$%|WNdgoh} z`S>Hqzk>hA_ocJMe}Vt!X83>f58B0Vs=0r;wS!+6zQVXEOMXxBz)Ir=@v(M{U1i*y zov;2M$6r)cr~V(gyRuUKKXRkwg~9(bmb^98|8+C!|B~UyA^(qz`oYh{^&01jUkLw? z?M1oryj}c1a<}+c@c+oD?<)1ODSn3a$NF3rebgAf*0IOE`MKz0gY9`4&bJ=-=HEph zw|4q}wmfk&)jA|BsC0i~K)s z4~G9oo-Mu_^8efn|Bnox7yci)rO?}V^Y#6FeL!E|&(|OGZTDs0JV0On@1GsdcYNe8 zy6=a+`G)XK-R-`N{L%ldyE|xp#C57&XE5{9xlEg>i?3N z|3}9D;Qx{7|4F8(m;XmbfB1i79Z&o}GCnW-zmPYNd-;FgzIMXP{}X3T{Xf+2Mg3p$ zNb$*fGY1)dCj39ixKlsSf9xpr|J;oHKQjDI_(cssgVCi4xczl^Z&@G=L`Rj93C2|{-2xY z&N*%4$4?Gc|Bw5R3k_2LkH>G4e}FSTi_Y41dsPq|BvSzd4OTjN9_FL z_`?6=`U)IB+PSY`km0*M|ILHe4nG$DANyl{NRjU0x2W8?5q!}0qE<21Q{!2jdtO&xZh`hVm&@pV!EmmK5Vr~V(uN4_8Y zKQi+DkpD+Uz90NQ&L7-6Wvekh&j&$UjB&hIj^AuNMe+>g`=yN+D!!k5|1`$-^8M5p z_n*#(*Vue<|2$E$%GL|~zw(lm#yH;a|B81XQD4+A*kAoWGW=BJ|B)w7nyUUEnf{-f zk^e_#{vSCxVw(DYWcq*P_-O<6f63FPO>=UJ=GlCwOqrtjf4m;<7k;L2jR@D|B;ao2>;K`@c+me zk{1a7?>iOi)&EN=o~iyHIkiCQPl*3Vj?a`lw5i#)J^a7$f-K`0$v1qnJJT3G=I*T- z#_;hHE~Xp9$AkaJ`Ai87caD84)fhfs&aYF9;s5>Ofk6(M8sS`wOSX3KJBNSKzx4Ov z>eqq4)ctc~|Ih*d??%=%_5a{Y!~Y|vCnP%X|HyeWr>Xx(ZjyQssQ>%*k438QmnV5u z@c-QW$i*M^j~E)MzEq>scN_hiAKL!wZc1RRjJXxnX&>`hVmq@f+a(xf%W+xm5CUkpD+6k@utU|H#$iOThng zGyFety}TcV|M#so!UppHq@EG{KXQ%uJn;X>)sjyF|BsBk0{DL)<%g;N2ZsMg#`f_4 z5u^AYe~BLf8=8Ez2N_mk;e!Bk6bOs8~z_TSK8(I zps`2t?%@Biy=IHNFBSifj66K}f8=JV4+{T}pQm9{F@C>1$Wk9vo^KjAZ}B*X|Lx<( zvp1FF`KTSQxsu-{&rgjTw^TS^`S4@LHIfhbn=d|RjJ(6EE#m*(TQBe*8$a``t*3@{ zMNamKXS^8xU)HV&^;KKNC;e{!Q^u%YeD~~=#*LDP*!STRw%(h?H(K=Ca9K1^y~Ax|3@yC`j21OddtQKKUa0r80Y`e#2d!B z%d?z4?_V=U{b2Zi9IsG(rqG0|#`RKfIDhVC>tE6x?L;MAGLGq(?1WsuX#KO7C8+<$ z@$w|U5dI%ISMm$t|MB>i&5`_1@&CxBvu8M8zJA&m^#|eq@qUmczvqVkM@IcP_*%>uW^$2Gw}bi-U(6v z5AQqS|B>q?pAG)s(vA@I|H^yw9KV!>{YO6xR^P8__e}Nw$hA_>^}RpO?ng~n&F>S2 z|3_}wRi*wPxmD`9!v7<;?XFe-51DfC|2p>8tN%xC+1sH0AGvj3qxyg3mOaht|B;(_ zH>v+eMmzjJH^cvPGyFet)2>GK|HzGfCF=jV8To&lf1~(<@c+oQlAj0vkDM*_hvEN` zbHoRP|3{APDOUfF93#gc{vR3nbIAWAr;EQ1|BqZP?;GI%kt-xW0{$O)hWIzg|05?z z{tWy-@(ihm2mgmp(dC@pfd=>bAY@f0?Tm3(BnD|lf z|Hu=U<@k*CV{J2_v*;o{T5|6_aFf-Lx4#yQIh z)c<39(efgEUTe=^g8as@#<;%W|FM68+#h6o<1EROme2bN=bJ6Z5C22{2U z?co2BJu9SsjQD?Umi~q0rXKa-jO*7_sQ<_L)M(!4)#!rp2 z-+1r?W3(6j_BX~kD~g<#TK`~-?-R)XHc=nWd<8=AG0{lN7 zulTNL_5a9;vj^(`l2Kn7{vR2>+|rOt8!x7Py83@?kCS@f@c+nYhyUkh_r zIDatwKk}6JY3l!xC(G|4;Qx^$TBfT1N1oOeuKpi6sAaPHf8@aCQ1$=F_csKq|Ht`^ zkl$ax|054?2vh%$Jgk1I`hR3c>Pf=?Bi|>!k=(CrevZ`3{^_^p84ri?}+9jHEFKzFnH zf8@wnE$aWd8To(Yh`Al=|B)_5Zm4m^G`_|07qe-|T#M$3FXfHN9J% z-(T2o+_-6nDUqHD_^>3^99TAQ;atp+~?f?*UMfU8F+P&_wP~vkDs?^?=JQK z$g6hussBe_x^1KSf8_bSJr45!$g|e2QvZ*$0N6W!2jd(Kh&Q_{vSC@d_Z~r<>B)(Qf;9k6gCgqy8V+BR(PgKXQZoy@UTpu9NQ*@c+p8JvZwAl3D+k48IZn9~nM4{68}C z6XE}n8|I`t0e9Z=@Oe_HJl}%6y} z|HuB(nFINMWb=tj2~hu!^NUHEp#C2jz8?HPH^cuU`zMW6|BoCXzTWd! zes1m99{wNOqmsv~|3{u7^M(IM#(ew>{=+yqIY9kCTi=NjoUEw-vg;`!Z>lq{=|kh> z!U*;M_>7ye>g zEBTmT{o!AYk(UYokIyf`OMm*2htEU1XJxAYM{baM@$mo16~&X(|0B;V8OZ-5mlvjb z`4Tl{-uYhDCEmVIO=+(Be|$d*{|NpcxivS_`Ptu>8p8*I|7Y!ze+K`LjQXJP|H$y) z;Qx`4pLPHBmBoC2JGZ>t`Ra{T#@#bZoU^x98+S-v8T>zPU+KwG|If|v|HxfA1O6Ww z{vP~4GJG8Pe`NSC@c+p0#ol;!qwOCI|Bv&9?*sqO&G7%o@N3}zk+DDce`NZ9Wcq*P z;+$ml|H$P9azB;)KQjCv_pAr5a z8TEtV|B+EY82NwX?t&8a|H!inOV$4)x8@eA|L11-e`M4@hW|%K9wYoezF#ht^9lct zT$U~W-i;?;in=0kMo0nCN7;Z z)(iYUw&U}_|0AQmFZ@3;@(khsaeVl9$p0hHmi#vOe}kN_{vWrWRg|axA6dT1tN-U_ z_fYYh zZ}j#5?wdHttG^@uk$ZbzKhT%qzqtGRGV;UR?Y`{m|M@a}Irx84b5;F6F#JC<{Xa7H z5C4yhdaCgM+zkIu?jZyDf6@;BkBsf%|B*31^8egi^uU$7;vk#vhx|V>`j`Lp^4+?x z995qW^F6!Go8S54C2Jpj&;Mh8F!KLKoIR%gAAGPsN&er?Rmau;Lp@RWf5zhH!T%$} zM}zP;0dGE|1%bU z4*nk*z8(BOGV1w$=EDb#;j7$PGsy7&&j0d^wSy(=&Uj*Ifck$+rkqrNFet>&f&a(x zrw93||L10L0j(YWA^blcZ{!nxaPhb?{Kt=~kJs6*CYeLnI3xPHL!|HxRs@c%eJtk2$E-u(B!9JF?8^A2mg=lI6v_J$haTE|09o)JXQJrY8)i|T*z84mhZoIej^?j;e>y6 znXQkckU*#JYfFt|gC{xP`uY;%B=N&g|M$ZKhtwB@pNIOtZifG795vO6**D*dQU90i z$n!(}Uo!Ik3cfqn_7@Qmq5dE5e^|e$|4YX4f&WJi4h~lTZ`!Zds{dCvC0hMI@~ZrD z_5a9ItLoMNb2IAyk_*ZQ{6BJG#en}uuC8oQ|BqZXb0GhZoGrgMTKdIY8!xS_(((UE zj&XG9Oy~8#XB&sg?_J>kar>yueD(jxLD5oQLHs{*TzItlf8>~{)7AeY!}o*#=VthS z4KQ&%`&;MgP@>Ssfk@FU(JMjPBemqS5zc%?jC;UI| zzeS#h!2cuT`91Rg$PLSLocli^zF*)}_50xeeQ@Y|#^vH~!T)1>_3}c^|07q)`xNB= z8Q=5&++6;(Z}o?-o1(rR{J=F2ziEv374ZMqze#+lS8Bdt?ckq;eciZK@|WQMaXc{m zKQi(O;Qx{9<$VeKKQjEjXR5zsTqo~;zcclV#;7NR`o9gooUDEz82;bRMU&MB1jGL$ zBaa9E9~t>GsQ*jOkoVE>|H$w!;s22m>FWQny;16U z!v7<~pM(F$`8O;}SO1UPvMf#gKXTWa9QFUm$OnAx`4?<^i^c!Dcm06RWs3iIk5Qi({vWRgaOUF2ym)HHqh1XEkJr;IsSgbQkK7^02l;>G z#${3uQv5%TUoSod{6BJ$)X#?hM=o46L;XK;;^J6m<>#(id+KtjZ+r5JahmuI@c-C9 zRq{CC|B)-^B|GCjx?o&3CsF-B&JTHI@c-QWwGC&jzen=&;Q#S>6^d^I|BqZM^$ee1 zd&-O9|M7gGz7708GV0&J|Ks^hl;>~o|Huibm-pylWB7yc|JWYa9Hssrug|!a2=)KC z9#JnC{vX#j#((Hvb{Qv2eK+`jZ+C=x`G4djxgWs)BO?#$dtX}D|N3V``k%OQu^8{u z;s5QtEj3&pJYS6blW*lM>wkK3kota&;w!-aBbQ6wCj7tp&jhOf*Sx<$>YL8%-SJMQ^^?B8|I|0BZ>ME;+fk^e_- z*)@>=M{eCckpD++lDt6pe{P2VN3P%9toeWBrhRSd{~7m{tN-U__<#JoZGF}1|B+iI zPZa(ixnxVF`hVmy=`TKw?SIDhMyD?<**Ixei~4`;pTDhH{Xep2SG)Ru4M7(5(I+`%m87p#Gnm;s24RZ)sBh zj~uhDRsBD5eqWpVe{P2VN1nQ^Mf3m25j)$}|06f{b*TSGuG`$I{vSC})(8AQa>~v& z&Hp3UZEsiqk6gc_1AdeBkC*)+|Bvlp_QDx zF`gmUBm6%e@5H@Lc>il0v8z@6KekVk@!naZR-D#+jh07|3_|-^$Guv z9KWqW{XcT@?pF9u*4`-lhyTa++HH;M|B=JD)oT79KY!$odR)JDd?L40!3VMJ!Qz(~ zH}}@TS21qrsfO=noU}pn;cUFL&9&B;)rg$p0hb`>mW`V~^xRBL9!` z0mJ_zf61s12mg_~r2bIREM5v&!{p?NjCbvs}N%vGV;(@}i8R<@*=>KW<+r z^`GJYar^?wPlf+SPHc~mTG7{vcE0YfJ{>sm)3=Ogw5bm<*kAIR;s0^_%$8~D|G63d zANQZp9I5^vIlU=D{Xa6kuXVlms*M*b@5kZ)alC-0aP|MlLGpbP`G1^mjMNi`|3}8} zJK+D3qoh7E{6BI;-Bk7eINo^iKj8ndeS-9d|3^msV)%dLF!?i?0$>Vwq(BTtdi?0Wo0D<9SbMmPFTYRl@O(vd>+cr^S@Lh>_YKD3omq0d zhZ)DneBu9b{8*_!0RNAiFw3LF~PQvn^o>Szc0yn#+;d& z|HtDQJ*PtbKR3hwv+?Fus{hCK~X&FcTTS?(v+p1h!0{Xe#+EpAi)k6gXDOZ`92r)AAT_5aAV>z1nj zN3LJLT>U?C{_ZX6|B*fWx2ylh@jE214gQ~-;s256Nj@F?Kl1$jyK#Rr?mT?JdF%Re z;?*Bm?M?0c=pci=rbD@{nqB!d+LJvfBbx4_a6;I>>vIguQ&NOq;vDNTT#{Xe$vmb^mL|0QpgJVVs~bu;S!k~eMZ zbKw7x`*!VA|BrlP!wRkcOYUi})B3;UQEgf3|M7e{31ij&Be!OcRsWB?x-nYw|M+|X zd71G4$no-fD)@hV-jLLqr2ZdyM$-)S|HuU`Gt~bhmr5Qe{68}Cbzgh>CFA_Xh3fzD z`9-cU^8d(1D@ry0kDRu=Lj6B-`ihzA|B(wMj~M2mg;8CEw@Z|B)lQQndarxmtWO_PYqfjAu@A@^}4zo@ag- zs=psCE(uiskDTWTRR52hTNI%F9~t?5sQ*ij$(4FOQva9Fmm(y;@51wM8&ApbQ~!_s z!&1jPuWf(F<~KEEoce#9AN)Mz|G63Ye{P2VM~1%#|BoD-I!^sRH^cuUC#O$P|BsxJ z6YNa+#IJ0i_Y2%C3o4|BqbWnXdjH zpZ6t;&x-s%a_0P8_5a9Ob92@IBWKUcbE=~MVApGzod2-qKN^?JN>l%j{kuCe)c+&T zmhV6C|H$={cfI$2{%YITcBMI8F@H0jGb_iLu<#@64~{?ecjKCdL?>ddQ_S&-%cnVs zzZ>LQkGEe^U*he*An(upKGZi4u)e6kdG>S5i}}76eiQsZzR!fO1OLy>@c-Nl|BnoR z2mT)!+r$6k`)uTa!T%$p-Yon-H^cwq_BF+Y>i?0OW|raotF{v&kq3tSKQjCr_NYS|08$E@k9O}xjS3l?@0b1xi)XW|0CDr%I~M64i)o#G3p(E z>dqj;&w~HQcH|er|05$GQU2SQ{vX>LGjrAdBf}qr|3`)oC~loG);s(^wqrfQ|07qH z7dydE4026nnfibHJafw{)c+%Q7J1bFBO?zH{-2xS|8e}zqJjKBa(D57|3{uH^?Z^4 z$L+z$|06e*4AlQ6!&ij=N5=Jr{6BJs%*TB{==Qlk`1*kV$p3?{=^hX3^`BwiJUw6b z_3v=~xyLV-de?6D_3eD~_k7vc--GY!9+oRb&rqy zOE)9`(#^j4h*+QhTf1+*pszpJ;&XmbFV#IB^6}j4o5wdy{26z@#y>pLx`F~{p(PPyA zBO{*<{@;`7$JGCWzX$)13_lO~f8=oiqt*W-`vr~F`oCoVK*@g=|BoCHG|qwlXDt34 z{68}4_oDtU8TEVN|G63d9~r(M{68}K!~Y`(1qG@9M-B-IQU8xTX5x6K=iSrRe?-6o z&I@^G?*9A8;{$nu0b|wwWB<^g@ecey@|X#uwEi!T-!Lf<3;&PDAO5A(m%l5{y852D zKIC3%3_lP4AJ+%`F!}ps3_nc%z8NE5Q~DZX{h|IZw+F-jW3?B~pe`NZ9WcYXR|9HH{%l_d1 zktYhn|Koa}G;FB)f8@}6{vUaw~sx|J?kg zYg=tSjFsyV{vXG~`G^1KX83<()Juo|N1pJ&Xy@wo9{c>m#`-y*+Pu#A0skQ6Ut9m^ zz!2we#VhRm$4{K>yi~m0czR@v`hUECp}sEszlV<s`}KXOrNjrxD&WKV_qf8?0#LiPXLjQl@x!1Q?a|Hu(j;?(~mhfj`G|BoCN z8l(On8SU`@$U&2%)&C=hOpVq2KQjD4Ts1{;!+i|G63Ye`NT6@c(*3Le>AP zS(&B&AGuC^wey?5IoQ4`SN%V>SFg-b|BqZF?ePD|mEs4&|07pRo&o$na@E2F_5aB9 z|Hyb>iu}Ku7bdCi2ZsOWX83kX}#17{fp%N-CJ+)|03o+ZR@jL{KAo`PZ_s}U-;Ymo-}UWSm?a{-N(Hc{vWT0 z>J5d?j^X0}-MhZ3#OGV`Z{qviWB7>h|DLOwqP{GA#Sueq8zaB)H*Y;`jQqm4AAiWW za?ODM$L%Xt4fucL;w7=p8<(!z{t6aMcb;8w%{XS(MCVeT_<#52lfEoU{XcFGKLGxp zo8kYFnTc@f2$Mui;Sn&VI@p8Y+eR#XA|2TP{kNUqcBPW^2#s70N{6BJa zZ>Hw|k?XhQYW^Qt>tl=mN3N0j+3^3!rJD=X|07q({80awT)U}I{XaLu|KsPal6vLH z|07r4%l{)6$nit|pPS+TalEuGrRx8YGq+W!|HuASTdURoBUej3a^(M!+jlgm|3_}y zF283G|BvG}?W|G%kKDMUTKzxkFFqpj|JdHKy;l7{a{I1k_5awvd0V~ue{ApA(WL$# zxp_;i`hVp5%~CH={6BKtCiq8VjT@vMH0uAdy}qwZ{XcTs);jh7$jzGu{68}M?5~Zw z&$b66|Bvl;a{S=`k!!`zg8wIuf%<>&HR1n}Tg2By{vZ1nivNlHKR3hwBNvMwhWfwc zQt`u(|3_{TM*bhUUd|uS-hYk34HvE&L|q*1aw2|FIqUnehLNch;%@M}}Vu|BuIO)&2qhkGyo(fd5Cv zc<}$ojXN9g{?{1wy~PjmV)%dTU)NWm{vWwvd!_n+i>~br5*ks zIdQ4{{$29_$nla74gZgvyg=&5i~mPXoHqm4uW`y8t!MoT+tcSKV0`0*MKSoiuW-IG zb0g*Xn*+y3ufGSnC!@W9JZ^3{)`#)()URR510)jeJPKi>bMXGLlKUt`HDhX2R@v9n{<|0Co3 z2K+yAf#iF_|05&+OR|8B<2&Nj|KsP0m;4X-f8;pH|A7BTj+Odh@c+m$Evf4Nkt3wO z9{fLYxa6C{|0BnCB&h#Kj%tll|BpOezVE>QBadpw=i6%Y4Ul|Q_i^mNO8wOTGp-C$|8I~( z)&DcDnymic;CNHC{x5k*Lp1IOgZmdB4*s8Q-i-(IR;d4H+*ytF@3G_C-GJ{0gFLHI{XgqJ zSNwX(|1+N5fa}HjKhW8r{vXF1JF6MrUk2Ofx2gZf_6LOF|B**5=)m_Q;|CUZtN+LS zja@ol{Xeqbibd-Gkwcd)RR51WdHEt)ZwWTvn3YS_|6_afiY2&ytsVVif1YMMWyNC6 z|6~8y)r*}+YO<|8p=UX+cjN4htJVMG`N`e9R{cM+XY)q&|2SUJre5{`$Qc_pssBe# zU%yfF|H#E_de#3Um#*7{`-$y8cheU2|JYuzb({KsUKXDfK zH|sz51 z@c%gen&W5G|0A!H^8x>ltiGZ6f8-VN`QZO?yiE^YQ2&pN`N97qZxVkJ{vUax><{^W z3?_3Q zZuS4j7q)Iz|Bu`z_gmEe<>#LmIz;_HvXeei{XcSWW0c&l?pS~Ne|-KICwb(}8$RJ7 zBVQf)e|(;mBJJ}0%oz0%kpIW_BB?J9|Bsv}^;Y2jkv)>niu^x5ufXrO;s22fmt{FM zv7fX4`O6B`|6@BC`G4d>`MnAJKXS4B9tHV-@`9`*mo z9ZQSV|06fd%~Ai4jPGyo|J)4!kDMVsB>X=&!~Y|DBo7|`AGuI|zX|`3jQlqEf8;Xx z{V4oDa)F#r_*|qA^B{`|1-`BQU8z6Pt&u5)&C=>wkMO{6CI|yhiwcZvNAbKN)v+r#Wvv{%7N^S?SJG|N0l>M#)2i}h=a2t0$OYp6xZj6@ zqhDNB%=fqO^Wguv8U7#NXCl81{vR3jU*Z3e(Z2Pv_<{G{kAn-ZiXTY6=l_wB-v$4V z4F3!MpPS+TaeU;pO})L=+N%pa&QBi|Kk(l8bELj3{6F@GPqY3B@dNL*H)W?fSx<={ zc#j)0lbydkEq)+b^6udOk>LZu|0Bb1g8xTulK#m5BNwG*sQ*VU&d5^#k6eVkK82+NXD=y~yV)TdqM@Icq_)#@PPOSG`$kFIqeOKaNlTj|{&K{vWxmqRf%nyvDQ3 zJa^{{&r81`hVn(VvpwkaXi%XMgE_gk^e`YQ&z72AGhx=E>ZuF48ITc zf87lKkBrX;|Bqaq=bbO-n@0y<)P2A3&5QHh{vY{ezCNI@FX-#r`7+j)YMl zoa3E;=Q}@N{zrL$zW$*v<9_1ae{EWV7Z+tEdU094_xxHVPu0D>Z#`zz-*&g-{@~`$ z9B*#T$n|RX{k*u``q#MD}yY)5d1&(NB$Z7KR3hwyD#d1`hW2A;QzT9{-2v8PhPnz_dLt{oBN}y zcO`>OeLd{|S94q}``h~V6>F#eC(f4of?)W6WaMYT|KoVbpF{p18Gax9KdJeu{$JqO zahm^UEct%O|04%a80(~b;-WF??S7Cn$o~HR>i;d6c0~O^)VoFfUo!IfkpD-9&jf|Kss?Mvc(=zdS#Ia=zgI@%)3~|B+E| z7ycjD3mE<%8P^N^KR3(0-5Bc|{vX@1KH&dxd@%e!H^cwq{E!z3|BpOIe8Hxd4j2y^ zF7>X(|KsPof8=oW|H!CM3;&Pn2Mqtu&G7%oW5m}({vR3jzTy9IJTUw}GR7PEh235p z)xXP&k^jf}qd)vV@`zDG)&C<8llsZ<|H$wwQUBM?JL0$5{OJF2J<$In<9x#ZBL~R& zK>c5SzR^-IxaL@|&DT$k-_nB{jB!2g*|Xj_AxfSPi~q;Z?-w7h{vSCcHPv}@{aR}; zlKQgp`xraF`SFSP{%jnY5a+BfUS{iKa$>v__szw2KTDW8QT;#O4^iJ5`F~{8zefI_ zo00!VMm=Bnf8@BhIQ9Q{zs!>T!~f&@OpTfDeDM9*w*REKY0lBdOYZJ@X{pxNEs?zA z&My`lrxX@B(|_tQ&XVsl@c*vi=ui5#f^OOBr$ul^r- z#*`WA|BhFPZs&WcYx{|0C1?b2I!uGVA}o{qu?H|Dpab{6BI~{7C2W zM?W#1IV)HFzb~H*RsXMaVZQUT$e;A@d4H1nNhJ&9_a|BJ^*_5}lKO)1&GKp`@9*CD zVEBJz{QDXHpPS+Tk>LkUdFS8yhcBI|zF(`<2SWZIxk2(S;Qx{9CGQUY9~tfN|Hx?n z@9^*R_rD&ZeqV*uAD#S%e>H}G2LF%kWh*n)|07qd&Q|}AJX8ELa)snQ!T%%I_10?sAGv;Go%(;|TJh1~|II86 zR{swS|BpO(y+{2&_Mg*J0rUj_e<>{*?z z{vWxlNAhaK|07qg%~Ai43?C5wACG^7?0-eY)5guc9;f-6PuY6v>@8IPkL$H#LxK8# zWcq*PmQ6*@8&8SvckgZ2 z_0JIg&2MiSr;0!M_7`p#mrK1}_JpS|H%0ZV%7g67c3NCdGra z{m&SeiEoGeKh6(%fbjpwk*(qC|M7T(;s22ni$ zr2gLw@ohgfrq?({@{{2IjhZn*{XgUZ!vD*D%1`}2aP5l4{ok+jQ{S&^UXIhbY(f99 zFO65w4tN%y#Z0c73k6g5|OY8rV zt2cDv{bIk=h*Mt#EbkwUYuB`?|Hu9{t6SCoBNwe{(fmJh!Kx(u`vXRoML z|Bsx$yh{B)a@w*=2mT*FZ_M(U>i?0aEiTpkKk~$-h3fy2hqunq`oH8!U6ES=&x_OgzhwA3sQ*ij>55YSkL=$Sq5dB~U&!2O z_5aAImyP%@loVPMr{XcT_$W<#+)&Fxd{6BKT(j@i&+zkJZ>{$}6{vWw$ag_RhJYLm{ zqBZ}IT(vL?{*E2b%!Lu^|FJ!Nei-~NYfqV{evlW#|6~8;?hy6=+>H9ads>S;zYzbAJh6E^?kC2%&7_0st z`ToXn>i>}w>I2mOBS%+`#rn77>sL2H{XZUGu;j9CDfBgJe3ybxM8#!P>Iob=zfeS0JK8&O07R&kiju*rK zWB;UiD6X&YmY3)>i@AFEZ4_i``mo>|9E^S&o5N} zkDM>{B}b0@MIkvy^2~qo@}G=jo8r{}gM*8=~KJh?&dr^bPm5%80YgK8sDU)qbs z$21P9k5d1SpFglh>w6ZF@2f{W@mlLYyg3o)*LYfUlKOw_A2M^A`hVo%)sxl#Bae{$ zIQV~@e?;93t^Z4o6TeKZU)z5`yVS!H|Bu^8EULiqx9x-G*TLs7p0cb}{Xgr!vRnPX zAq&T;{};Jxmim9>=+*Po|6~979{5>L*!~LEFIE4K?IoL6ssG3M)@@m#{vWw^^K$k7 z$a$MqtN+LC3%0CP|Bvk1x=#H+a>=&!>i=FQ1kydzuA%(hWtPBoHNM(8e=@`!Sm|> zaXjRMiTh&X%{hMo-!F{kU%IURANy}PcS-#}GJGKTf8^!oE~@|MX30PH@Oqtp{*wBC zY+rcs3VuIf+b_6$#W~gxZM^u}b@l)Fc~;1LQ2&>_?7~I$|H$huURM8)+;i!Q`hVm_ zGCur2HzWU#yhgT%|3_YV?t=P%#uqL-q0i@A`zo1#*L#J=E2aH{f3Y#zQU90QZx;V- zOkcSdBma->ThCun|If|v|H$huU045)y#C5f_5a9gFI-pukG$smHTD0P zHJ5Iv|3_YX`KJ1RZifFyMt|i0k$bK@to|Q)!?oM$|B=^Sen|a4^4d$c)c+%IyL40i zKXTv28@M0Z_?xfXa=x-;z46v-53B#j>t)N;ht&UbvwVNC{)etU?7W<~&5Pmxaeuq7 zJ*57ho00!V-gWhs`hRZz+NcAzUU$m*cz^mqFP8f3#{1>-MRgxGK6vFJxt@=BG5kMX zA83dFN8Tr&7ycjlz>V9Q|3}9B;Qx_#T)u(7?>7H6vVM^N$NBe2fB1jo{pW9J{-2xS z|8cw{7jCHkM?N9v8~z`8pL~A!f8;%~zt60=Y}fx@IX}q%WBb9IkE;JiK6c{~_5a96 zuRkpJm+RL5!CQ~2|Ht<8k36paANj_^x7Gh6KlJDw_5a9^-npaxANj&1+>aiy@hcDP zaFYLi+t?X16yL`O`2ojSopHx_Ms}jyuO2rJkovsx`&JL1Pld|&JLLb7;s3+`Bjfjl z@c+n3-KpyTxf%W+IcxTS|3@yA=cDld_`Cx7ckutnsq*_n)c++TPY?Bf$*6Y=|BsBk zXZU~QJn;+R|B;c;2mgi?1R z;;;T6xzOXM{vSEJV1oL8Ru|M+fQ2&=q|Bp=nj||@q{vSCyd5p8I z{B7e=Nn@OrH9s&OE%|=GYW{co{0WKU)c@mrl9K(L?#1ug`hl;Pdg?u6_Ich&Ac7+23pb4s85qj9tNeWBm}lNbN)uYWeKm+Kw=AIGng^$Guv+$6sTN^bc- z#?A73A>{w@`D9^7hV$+df46q<4_7+H+`han(>edgA;o*?BUfeTIZxl|F|N+ZSO1Ug$issF=VthSWcW_-|H$y6 z;Qx`~*TDZHcVrhhm&-R7^L;4tA%FTL)RjTlLa5+aCLa|HtugeBl3)aXjJw zk>}+XssBgr&dPP*|B;bThWtNrS5~&>|B>Na!T%$}mxKRDULeOG{vUa6R)+e2WcW#_ z|4T+aX!&nr_(|~p*xsJ+QU8w&e-Zv4xl`)*ivM88hyEXrCm8-8d1gVb)A@}<#e5%K zRV4M_>kb=ZeE5HCM?Glxe`Kr=_s$J^`_9LAzP{{x zJcc2T&v|Vx|JRp&{Xbv!_5I*0aV-2_-}e6(hX1$y$vx`-VSM<1AI0ug{}1EA|0AOv z{-3)){69Ct|Jyu$pZb6B_u&5-i@!H?%+^8d(~KkEOIkuM1UkBq!a z_lY5|05%x5dI(66Y3GmXSdHkZqz{j zACCw9KQi+A;Qx`4=Li3f{DAm?@c%eI82%r5wB#Ma|8q0^Kk|5)pXcSBUfliS4j13= zY{;e(~+BuCyFmUYyT!&Pgs9h+cz3V#e_Q@e^_t*BNO7CfBml>jw<~kM~3Pfbjpw zxE|sEkprfNs{cn0jT*@RL$P*)`YyRIe zCxg}h3zYi6@c+p8{T}>3a)Z}xPSNPkb!)_d70|}k@0*8{vWr; z^B(wr=zGzu|NNVK=uC$r9LnGKQf-L$@8)PN6i~K$K ze>@*ek`H!v(o@E5k|&gR`$=05t>W_`|BvgtdvlTI|G63dAGuEQ%%0u(m~s7HIg?J*7&e-wfLv-|JWb(u;KraQ7;?*9~r(3{6BKh@>KQz z$f$3J{68}4+rj@M&yae1@c+mu;+w+%BR4NDaB}xwFs`4UqyAsZ$q@C0Q4jpRhtKts z^Ot0(|3^mtC;UHh$*h6=KaP+3!0`XbIg)n+|BsA(oBe(#i~}Vv5dI&Je^~oK{vSD9 zelHLIkDSn%?9~7Aka2W#oce#f{^|d5eZc?w;mUosKBl!rsQ<_HJiR?q{Xa7D0pb7g zdcgDhxBk9)kY^`5ksse^jQYUGH?8R3)iX|gzi|2eKKws&sN@mB|GPDAoce#sowDA= z|NGjRu>W^?%`b!T-zMvQ7Oza^dz}@DHrLYWGg{|JV*j z{vWw@=N|R{plRa^g=eLK|uRR510*|S9bKR3hwSb1>i>~LR&}WVNA_RZto|R_SyG|?pYi-+ z_5Y0L<*NT@Ecpb;|1+K~d8j{)9^^SW>i@BQsML>v|3`LYJ)-`vamy6-|M>ZwwlMYo z$PYA!sQ*VE-7-=AKeE#}M*TnIjsW%ljGO({|1<6gf&XIX%V`>`{vX?ibO$@_(?$)> zuX(Kce{3Jt;Sc{{aQoJA>i=2$>|pi($U~YZsQ*VE*)kd`_ z&)Q{v$p16$41|w0$j#%_|Fd?PKm0%AWi?04b_C=7 zckE{(+|Bvj{PE`NTxF$sXKV$Lb;Qtv{`lV`u8Dd{WAP_0Xd|1h5COyUeko(|G8QIyO2C%<0|$4$gxsC68V4R z;B^bt|FiMM4}FBB&NB7?*zU;tHu!(W?ddYVRO4Z-a(|cnKYre! zE$LXl#!h3F`hVPh*sK!#{k83@mvpNC$L$lV^40$%JGJ?8KkTvoPD`o!e;m(guUG%i zcut$F=R<@2m&}DPVtoHvobS`d5gRtB|Htj4Hg8t{kNcmorBD68ij*GHyR~1ot=Nj>AXQ|Kt7^A334^A9?M5I$&NSj$58*5^MfCU`oHAPV<*-BBiBoNQo;9a`(~+^`NYFNG=@JHKJ+~= zM*bi7zfkhWCVcZ(UVI|$*T(ZCZ%q7lU9-sNAud4q?UUc?``hV=d^uj~x|B;uRzoq^kdBMf&>i^mH;&;LSBQL%F zkote*g_p0Z|3~f?e+~72$+N{Lga1cfD!vx#|GF9eAFs#NvVY|Nu^oOH{6F%FYd6&Y zBd@%E6W61)uf2K8abAiyUL}5D!G9zeFS>e7{Xc%*CD(7L|3_YX?Uwp~hyO=jCq5heKk_E=(+>Zz%DDIP zE&RPS#{T8^ImRom+))3I+oM17|HvD}H$(m(8OIy`9~t|H|3_XXe%5Nq|06GzcFFTK zUL@PY|6}`NX@~zuUVilv_5a+A{6AxvAL{>-S6zEV{Xg<1@w<@!N8bF;`G4%cNA`#OKk^p&e2woOGRFLn|Ht;7GCur2uKyh}KKwuO zHW}|L<;Pw9pOEYQgz>J&pK^w7J!!n{_8r{+ZTk)4+rj_i{(5gcrv4wf@8)Cb|B<)d zy5p4m&pEq(_dfi%`hT1c82%sm@I!Z;YxS3`{}E}2|Hte9=p#=!ZymT|jCR!j<@P5Y zdR+ZK^6A@8ssBg5@Yplz|BQ-i?0y_QDJ5 z|Bi?1btE1Ha#_G z+&#pi?n$Nn){A?p8;qcek@MeX0QcI5S;{x93X@c-QW!PmcQJR@U**8gQYp5Md& zBh&vQ`zMW6|BoD$D*xUU|Bv&HP8#Rz%l(n9kJyv}|Bve>F=L|of8>Pp5cU7a(OLfL z|GD{dqkd-NO)d;^&S(7GIHqcv`hV;nQ6H)PA308**DZYimo`86nz{b(8yCuY_AmGk z;~aT@2LF%SBi|DK9~r-ohyO<|liwdEKlh<=qx2u~z26wu%ln9T|NdKJ{Qmy4@&9d% zdOYy|I9{XFhlc-0hR+KBkK8ErpyB_K8|3*8{J%j?QU8z67vTfK|0BZ(g#SlI`^a4% z8Ka&t{6DsX;s24F+A^H#j|RCy{{8vlg(23Sk{RvgV`LY2=TX52n)~45V!mI7FEs7k z5@YyB@1I|4+$w$+{6F@GuLb{)+>$HxmBs%f!|#Lt=VthS#^Pte|8q0^Kfb?)zXkt~ z?eMqY{~1f38T>ytBma*KUk3gk8S{bvM}}Vm|If|v|H$*1rp|07ox z<~i{H$ncfm|8aZd*TMfI!^eUDN5=7m|3`*Dh5SEqht#u$|3^k18T>yo>ZhXqFByK& zW0iYtKG>hk%^3NAS05YXPN}E*>h%5Aj`7}oY>+#|FBEsp+Hrnj?hJB6VX^vu+<&L1 z41R<4Zxmk;{vVGI&JXhc+zkJZ44)1DAKy2_cZ2^&?#L}t|Bu`zekS}sa;5l^@c+p4 z|BU7Q!~f&{upUtVmyGiV|BsC81O6Ww^MU_IZY(Zx;Qx_3C9em(WP0c4q24mQE&i{s z|L4oTKAA83`gq9C{@nbJ@&zmNy!}RB#{IxOo-cQa58!TZ zOZE1rYg4@aYG1CCyeIeezU{eL-t#NS_4Y4)=Ublboi~Vjc&>mU32hQ93U`}y+! zi?8RN&p+B8zLUGZFT*#4|M&0D?NI*@d^dHF(I54H*^d3e|8q0^KR3hwdvoS4^Z$N% z>grv&r>gIVyg>MWWQ_ObLfN0Z6FmFIuoCPK{+~Ed>i;3%4gMc_nB=dOef_F2>WALn zCHud(J@UfNzIE9c{vP~4wg(3XtN%wX4hmBLkK^b2`KkX$hA#;J&&}}v$jG;Y|L5js zpSfTRKX7HNH^n@ zKrvdc zK^8v``F}hfSg*+cBZrL~rv4v!>WHE0|B>Mf!vEv`MvGqu|BsCN#PI*z4F8Xe;|2fE z&G7%+4F8Xe>+4|l4x1nSKh6jKU-~Dv+xf@*;Qz55z9alU@)W6u4F8WDDn20mKXRgs z2mg;;6da`fAJ>-?6{`N9ar9(oLT|6_KRh(h`Sr>TUi{UC>y5L<$@&!kkK?C3;OCV6 zaE&qYIY0l_YGe4YxpPYbJNuSV>@{9qJQsy;!^@PoSjQViz-u;Ym(vmo5_|=z;i-~GblcK#NMuQ=k`9pm|%$~6Cv z*F(+LQuY7b4F8V|e{xskZDaVU@c(%IVm-tEb2I!uGV&?m|B;bT3IC6bddTqq+>H9a zWaIJ_5a8b-Er#wkt@XqhW|&#^I+uvMI{BP|5qUSobdn1mFuJ) zsO0~VQ9lO$A2~zTwER9D`G36r)4LL#@~{KOi7hee|MB`oULf-SxW2&1|074Y#i{?t>mf#- zZ^Hj0Po9;k{vUawJkN&z_eSOz_5X&o$Ep8E9xFZ|{J+KD8?F9d{<1k*|ChYx@+tNI z&UBAfA8@z4e|_)Iv-`=rq<$6rKh$)E|F`bK74`qfJr}RSKd|=ROV`x@WBW#Vp9uet zyyL<(t^Z5jF7KyN|CfyM;Qx`=%Xp*aRT?92htMWco z>i?4QKKI?O0%N@Ih5yITyZQQ6_5aAdS1zglM_zyRg8F}MmOL%ne$6GRfAwmz@rrXN z)c<4uMdweb|L11-f8<%`j;sGi?ml}={Xg=&QwP=mBhNm*PyIjglEZtPl@Cm{@fPgg z;Uv8kYCLD(Hm(25{B#( zal>K)A2Zi4RR53X3yl0fa?OTC>i@YJ{vWw` z(_;1i$R(SXsQ*XK+qzW!KR3hwBj@)mQ~!@#ux+{ef8?^Q%hdlPV|@63|Ht;mb#vgqc(sckW8B)iK>a`V z$MKZ+jn-biZoc||Y>!$$SN%UX!~c`aC-rp`H!fEHkDS)0ewVe!%JD$`U$)0>S*rdY zxq9PL_5a9Ky-U>pBUegZm*nx-_BDO0)c<3i@AFjQYRi zn(aO6|B-8DJ){1w@$N0^|B)NydKnQJX6=ppx5HPl;|G>^v&L-)cVj&pw;$RAKlN1} z&*~%l)c+&b9y@^bW9{`PkE#F1>!ta@Q|kYbXP-Tz{vUbn`LpW(kr&DR5dI%|ncNTI z|B*Lcxvu^nx%bjlT))=7_{vrIaIdg^iTEy(FKE0-d>8q=uW0sF3YTZ`@S>kGxFAhyO=jaN~yhe;j|Ij0gXZyiV@# zsQ*h|EAtnBvXGyr=jvtk|H$j){w|-_+LvECul^s~mt8!k{vWyL+!^)%$g5AEz~?RE z{$`yys{S9j`}7g@|HwGs@c+n_vOeJdk*oLhiLaJtT(N5t{=OO4^=(l9kNv^$|H!k% ze_yy_u5r`KMY7(O8K>;nqW&NIXYJdm{vWw=|3UTt$W13s$$CCy+s~7HH~4>SUwQo& zj=%Ayn-8o1$M(&)9+Bg5$=cW5d_?`fBOi@Y|F7rPZT0`i@KNCZar@nmJ*oa5d7t<) z@c+p0U*!I04FBf8=YP70=Lfv%>n|I_KY2H&--{)0bCAUk`G((Dytr)l*Nr!c&jSCC z^X-*;Lr4KG`{xo zUFUa?Z}wuzPc?q%GoN=>kK1m1>!nxadfZ|2d;GJXSO1Uue?rEG|3|(d^MU`z`8@Q> z8|wd&9~FlG$NrDJ{F?fI#WkL}nV^?%8q zl<`sjm;CDIUswN+{MzeZQvZ+qg)jb#`hVmXKmD@&d+oN}pUzyq=KM?4V;=td+Zi&{ z`FY75V~JaE?wj|xaZGHKv;F-iJpA{3geTPL9R8GXvg83H|Buh7kWUQ%kDMTRcJTkm z@T1`Wku#+~{6BJ<)T4#}N6u=CSO1UCC(7Dl)&C<`iC+l+k6bRk9{fLYiPXnM{-2xS z|B(xtW7Yp77q&)g{vWxxBToH4azo1u=c$ig^YHmcqvZP?hE!&cR>s_OFO`mhCuFF+lef-5! zd-v|$eY*Rc>3;fM@c+n-g5`ON_D&o4;c?|S;&82!Wl^}^UcxU^H!?<3>T z$coPH5}(-d5E@=h{XZTbVC4UiW2399|3_|~+(7+5a-&Rt_5a9Cvw}4LkNcx$w`i^Z zORm=|-Z`}9E1OSPk4Wdu^S?8W?h~i}AN#lM6`}qgxpmJl_5a9i#7F(6-ydxGbjkO- zwD^z4c)qaV#Gkwv{vYStxu4Wi5&w^zCHF7k|B(~=gscBYPVO&0n)rX@c0Iz>|0A~% zKN0>P8F_v1|H#Pmga1cv-Jz*-tKQ#@;RkL{|A%pFsUHmgkM|qF@c-Nl|Bu{C>V?Dq zBd2Ets{cpM=n$m-AGt-V5T{n7eAeHS*u+_soyS?R;p+eKd2{y^kNSV)&dJH@|B*AK z-YEP(GJH4qe`NSk@c+nYhyUkh_tR3}y;s3E6`El_7$jG;X z|3`-J2LF!?9|ry(8F^pu|Hz5r)4~5EC&~Em|H$y$kpJgq_Q_2)$_+AOkry9ebTF`u&ai(majGf2Q4*!qygMZb%#SCkQ?*spj z^MSu5?wB$9!~bJD_9y&5GWx^+BV#=He`M4*hW|&#{%lomu5n68xcYx=2gCm(!~cT+ zNA^fQPQJGD;`w|T?ePEH4F8V|zY6((oVga7Ad z_u>t{fW8br$vuBx{&)V~f7%Y8$-TaR$MA#T|HU1hsQw=q z{vR33!~Y{=KJfqC4FAu~@c-l*?B)N7lkMgIkug5}KXI1K|3m#>GW;g^e`_;ms1FGL z2>u_rRN*4(|FM6ClBLxDBg6k|JYiMN_Oxm0pTW1A^xaD1CZ%)zKaSV9l=wn7SK9h3 zl`bRC|3|J}wuJhBTps*j-9p(Z;7Bc5n}7LyuR8zw zX|8cO>HlTwJlj9;{a&GLU^oL^<{;HL0IFWaU7&oX{%gO3I$o8jS z?K;kjd%f*?=U2D76ZD{$ac!9|^8d0u6VwkZTCs%sf8^qoOR4|I>t+4Yh1LHfS1aVG z|3`MjM@IeMMt-ekxN3K}SPyIh~CCU5C zzbYta<$rg{zP0tM_=?pVI;BqpdU4Gs0mi8B`_{d{oa>(M>MItg+ED#JazPn?&aiK? z|L1NQ^=nF0Z{Q4z{k?Iqs`Z=>#lJSD|5qogjQW60>o-vUj~o(L!^z6|GMn7`SO2fg zv(oAVhRFME@c+o6;^V;oBPVtXR{xJ2FZC$k|4r&%TK&Jo&W+UnBe&_B>;D-`eLnbq zw!~bJ@yTOs_|B*8WhHL&GIbPO>{6BKS z&=VthS`EQg||1V{PybmV+pPS+Tkul$tUT3rY+m=+nFIDmfhedp7>=_uW{vX?8 z`UR-}M{e3j-iH+bkK9Z?Klp!SykCj@KR3hwBexa*3i*GWPo~s&hX2Ry!RLwmKeo4& zygT@RWNaVu|H!FhVl@AcjQYFq|HxUAuZR3Uax2N-ga1cPlXm3)as9~Sga1cvJ2651 zKXRt{eenOt@BvGO?={8RXUWca7> z|Hy459}xZ@xmDk$>i>}g<^5OW|B+FD7WseVWbx(T|B>PU!vEv-DY#Fl`hVnzfl=!J zk>mSEtN%xi6JHSiAIHP{x$ytUttB51{vSC=-p57$A2~$s_rd?;^$2;I@c-Nl|BoE? zdNcL^+zkJZ=YMq1VDXGBl1}Mf==h-jfbq= zsQw@O_YnUD{vWxI_zLjNA54ri>e%~o7cX2t@?j#A0R#?^8d(vmakF&&&}}v$o=14 zrT!neuhiFr|7X1TUG@LSy%#Q3|Bu{b(NgvQ$lcyvqW&K_^X*0I|B*AK-XQ+(X83>P z^f%vD|Bs(X`n)&Q|08G2e@p#8a^`}!)&Fxd{6BKWf;ZLwBd5<_p#Gn+jF0?3GRA}d zM{fW2LiPX1?cRD@{XcRisjv9;FVC!h#|87%|6@DysD5g8&)VD1nWz3A+f&7_f&WKN zn>%0qKXS&r`Rf0XGiCnp|Hz%@E>QoE+;Pr)_5aAf=3`m^EEym9e{4^kJxBdNa*LU> z)c+%g3nTx}&G7&BH7=BWrPi`|v?KqI96fg)p8p!B%KG5{u{}-p2lD^OouuBRJn!~m z)c<9B$2S+M|L11Z|0SnOzL(?$c`^Jywr9%ci~K)wd-;6f|B;c`CBB7m*G2EB|Ht-T z?<`mUkK9|%5BPuNUdvX&SF!yA7XQWg^>;N-%ZuUvaesCYe;W0F$zA381pklRSI&Rb z|K<5HP_8G)|09o+`gO?vBjfsr`oH9n;tRq5BO{Lo{vUa`_%^8jOCBcIJNSR(0dl>D z|3@Aw{u2B@@)+gfUMx4@^c=_c$7snLg8#?u$>k-+!?tY0_8Je}ycPXp*}vE3ZSdi| zSo}8Q{^BEvZ(%$@d>;6JTpm7_?4MZ9ceLye_&5W@*bZM3^?%982Sfc| z@<>@8`G4dQ;=jrMGw!=)4UUgE&ZoE3|3m#>GU}7U|8q0^KXUg)INzg;JHI(c{Xe#6 z%$lkGAGytR&EK{D?IurA|BvliQ>Ur_M{Y4=uKIuEmNVz6|3^+;@Q(U_Rf9oHY@G2(~8|6~8LTX!K} z+s1=WR$##aWB69``5KSjv`hUzemMtTs4E`S(ei{5fUN0~|_bu|Hti{v}uF-f8=Rf zx2XTe{*$(BQvZ)UMcU=~x8*0u=L!Fh%a7ONp|tTZ@iFE70xy=|AI3do`M++eWc>QJ zo$CK_eK^h+SA9?nk_woDI`p?{T5Z4FeX*>6;|Hu9__8e0Gk34hFVfFvWv-Tdr_oc0G?!Key z|FM1E{$uL@xf%I?i>~fp1Y#{pPP~Y$Kz@3xy$PRk=JEkQU8y; zG3ToKf8%kPu^@c-Bj-kCJb_@FG0{6DULzpM}bA9>T+%j*Ae`K{-#OJ3(} zYk&XJP4)lS|A4F?`G4f~GXBAN^E|vBZM<;ZDYj|8@n%_m*og&ReB;iW#yc+DaQuGv zmhpC3Kl1-L{i@YJ{vUb2v?KqId_a~*{og#krv4xKpv({cAGi0I_;c|8$VV?- zbDq~7t` zEZ^?o-{<+A{LcCJcNhyg8*lG4u2!dp`hVM^5OHTmP3FD|vkI|H!CM4F8YpC-r#c{-be>%;(2L*&f~xj1|A{-qRdo_;I9XGaIS@M-FRUPxJq5eJyLL|3|KqSVjFmvR`6l_5aBAJr&gdBL_=9UFaWg z+I$0|%4z*ywl|6?tNtI?4@UkUIWQ*I|6_mnf$;y>4nGj}f5{EP%WD1~IV7T@`hVnr zkg}TpM}|)b|BqZZq?7~ykL!C?+Ts6^3r3b#|BqZVqO$sb= z#pn8ep9%h-v45`r=VthS8MU{6Dt05x)=q9~s*N|BsCPFmbz# zG5>Ncrh75`KlV=w3RVBl&5|t_&*!(8f300JjWK`tf7W08Eck!q_&|U4|Hv_tmjeHf z92*#{{vWwj(;)T#$f->N)&C>I_k;gOMm;?Ef1IBusFC`AtTPpmv0;D?bBsO`1p7}>+{_{_^a;mT1Y)< zH>3Wxn>)z)rbCbvec2CRx2-_+@c+owDwbCNk6fd&)Vq@Uzf&(xQ~wW){6BJoO0vHs|BwAq{}lco_Xm7N_gB@!lka@>Me+H=|0C1?b2I!uH^cvPGyFe}kLBV2xw-1Oc{U#$kH7t8 zp3S#Ffn5KO^RJx0p!$F03XbH}iT}s#MSWn@|7AOlSE-$ATrmGDPI}*2wtleW2j{UY zFYgz4v1IYt@|ZvTKaLNE|L11-e{P2VN5=UF|Bv$p!~Y`}5{CarE+KxO{NFf#k;3Z# zvHjJeMb!TzmnvFN^Z&?YOB7N6kL*`M{{9mGj~rN`iu!-#5+zEg|3`*z2>*{i>}=V^cK$kDQQ_oBu}+ zYo1&G*Uj+%+zkJZ9Fm;o!2currR3KCC0C1#RsWA%G2G+aE*F+_YivjL_X_(3Ixj*) zjqBBJ;(Xm9#2EE`e;gldTuSmy;s0^@;^I5Q|1+*u-+})}E+zSZ&3^DVhA$XXK9AuC z!vDKDx|I5V<*V0H|BqauMs4-~$W7~1bUdH_&icm&H&p-c`yWfH511_XL*W0ByUP1$ zsQ+7IdP(*F0>pQL|3~)k7NGtgxw-s3iTb~8hX0qEzohzq8C`PyKXSKzx&9wHWk9g{ zf8^HU)4~5E!>{|}yr*7_`oC;%E%kVBr9I02=g<=B2ey&=w($SRS;OPh|08D%j#B@R z96TgO{XaJ^AAiS|hoAPh^|!Jc{}hAMu~4I{vSE(*Ze;>Bma*a*DqZCKXT-+{vR2iFZ@4pbMbxQ|MB`0 zAfGq#|HxszgPrexTx$KJdWSn7Uw_9qPJBT4e;lt%zgYGE$Q^q}ssBd~?<@5kHoR@y z8!7MS!vEv`Ntb*<__sp#C2@ylXQj?95ziM|~0G|M7Z*{_y{Jy@(Tk z5B?uHs(mB5e>crO-{{Ob>i_Zhi<5fA@c+nVrJirC?}uma+*3GvWu=wzPI5){|I#lM z%=Q1GN~r%w4jj`${l7mAD5(D5)LC=X|07?#epCHFI9c#Fc3!!q{vUaB_GR_|$lK3e zRR52>O`g9Y|1W850rmafJ9Sq5Kk~+7AE^IlEYAbs|B*LHo(KFt^5XYTsQ*V^bm+MH zf8_ZGj;a4go+o)C@c+ou4;)edk34PP`|AIZr|dqY{vUa=JU@m1$L*Q1^MLw)v3;^EkNiI}>W3l!kBoX~ z$p0gwewsZ0Hy$qS$l_r;@_z7ao;*Z+0Q{dkNPJ4<|MByHA0&Q)7bE|V?E}RR62HNC z(3b7+AB;!Hd{FR%@ z|BpOXmWTgGo+k5~edVSx#)tpM_R->lEdTz3@hE9W{a?1@^M(IMo-FN+KRj+cQRajE zKemtEyaV}I#^a?P8vH-D50lRy`G0Ok{a^B6IsV}Pk%#Tt3xCIW?2g@dUTZvB{0#B0 zjFFcl`C!Hqx9x#Hl*ck3_fp9cOP+rjYv$P?xBlm5n&xUfAwmmcCe1QMQ>&sO6zJdQoo+8I5 z{6F#}*}w4r$hf}4|07S3?-%%gU@pzcEYRRsWAXRD5apf8@R^ zB=1xFKQi(H;s0^_Mr_&Y$g%C=@jZUm9(;dWJ3c@8em9;c`&W*C<1zaWtN+LGCcJ+f zzaOl9uKeDE|HpRZyTSh>&p0CfnD~EgmftVNZyh;}-#5mKj-OTkkNp>)IH&%fo8kYF zmq>s3f8=+hKm0#3{4@A}WcX+B|H#OTga7Ad_rvB~Tdyk#FxBD5Nxck^y^z#5OPW2ybeDL;T z_5U~?SblHV_#fPTs`Y=_e&+sj@omRg`&Ia~TK_~mVDKX>n`^HqgK#vk5!?4$%NHokoKk+ZGk65}hf z{jci@YJ{vY|;?fdHgxf%W+ z`TCs)>i>~%+gh+_a^*XzM!a|8e~RsWsLABR5XY_5aAV5-O_yN3JXFsQ*h2ORS*&A2~E3 zxBjoOr?T_AxI5NAB(9Q^J@Bq^gfQ~|tbcTQ_5V2E@Tl_Y|G63Yf8?;Jvg-elgTqTX zkGemx@uI~?+&}NBaYB3*_5ZlO*IG+`Xz~BZMcYX}q~!mRLo*~FQu6=EQ5}M{{x3PW zQ@C?}$|u$y)-}pmx9wBoJxe;hwu>gmG& zBWLxGRR53MVnCGof8?|wx%q$O5rg8KnXSII{WYjhgwtir?~OZ1{f?k@-x#NNY33BU z@CV~|of|v9{rZnyJmJ%CZ9c8#{$AUHe=%+&_xBnE{?*tc=NtS#-roho|0B2Q)I|M1 za`TLO>i>~jO1%)||B+MMH&p+RjCvvP|Hwhz8ms?DhTk`B@;|Me{vYo*wi6!^{-2xS z|B*901v=j@b>cZ*M#li>WxZF7TV&Ot!T%#8Ukm;pIlZae@0I*Naz-0|5vo#Z0isIuh;!Nj`o*4 zzl=H7j{Q;aULIq6kpIW=&<_8P+@eVn_5U~@F!KM%_&kvRN5=8_v*iDg;aeg9kK8>p zSp7e8H`yNee`NG;b3Kpg|8YL><-WiAmi32E)w0Fg#yH+LT=C{Vr!2H~9Ix>IxIXxK z$p0f_{_y|Em=F9vH^cwqe2~uw|Bp=nkBmGzQ{T6Fq<5a4uaD>J&-v~TUw;n!*F9g~yg%RNQQzC$AN8Ew z?CVSV_V;Dq{o}hm|0$!swR=9uuXeKoz0c+Qf!qu~=RaXzzwqBN{2}-FVC4V3a&Dwo z{-2xS|G63d9~tw7|3}8wApdV#(&${DOWNW8i4(3qAl8@o<+_}oR*$#5Klp!Si-ojTGW~NVvV&IFH^)>HhFc8S97t$MKLq_LgV4^+%pwg|qJ(BX4heR35|s z3p%yT+EI@;J2a0gRjTB`|Ks|Q-v|HC&4UiUF`_~r!ThU{i>8#|BvGZ)UKxfALmoMZZ-A)xWD03qW&+B2l!*C|4S|; z?|Z@jPyIhP!~Y}G|Ks}U|B*31{68|rhyTarB`#3?KR3hwb2I!uH^cuk#`!J& zA3q=L5BPs%xRQ*3Pd_Ls=xf%I?bwuATaGA+fPe=y6XT zC*}Ho8){^!AJ{Y|*Z(62#5Z?(mW#Fi;Vs%Y!$M<>6NRUAh&E1W-r89(KFT;!e7}_| zBaI`HS~=T~M;Heur8PXkAEo{u=U={NWA*>Yb!s+p){YF$>GM@) z_7_us8xOv+G|0Ge?Rw64hXcL1*24f}_Iqc;@9O&E>iKk1P-Wuk!w4>i;EoX{h;s^9|#sn3@i@AF4F8YZQS#d0|8e{d zl6MFHkBmIPkvlI~{}z&02>*}E2M-KX|BoCxI9UBZvZsH9`hPbM7E%8%LGst&|BtK|J<(Qm)u%>O89@q;@iRh zBexwZ{^(D;jN8e0RUhm$&K#ZV|MBxlm-@x<|J)4!kDMmQ1N=X7s}Z^WA31(xwDYw8 z7Hdx$6X)E!D0zRs9{2cHrCA30;3$N5W{ z^~P;w`(J#u);LY_1Cjs7^F39LANYUd#DOvD|B+*)9ys#<$Z0(rsQ*V!?OxBRleOI1 z{kt`EiqwDCIJ9>&_5avEwpXb7e`Jr;+kpQ^?%6NSdH%y9n{T(?(aweI3yo3V1O6Yk zH%;;Y;s22n`i7|gM@C*H{6BKA_{pgMOAhPaRQ*44P>)>ykJqQ*o&iqN|DI+0ANhb; z+os#+7v9xh>;Lk2YMfPF{XcTkjy0W>Pey02?^G!Jbd6QekVoN(o z$%C_p{p&S-KH${Jr~co{H(yg9FllhAQ{L&9O@8y8RqFqV!=OIki->) z=XI$6OWu3&y83_QJ(q8&|3}_^={o$3Y&cw~54`Q-HTD0V+Zyk33P@ z;s0@arbs*T|HzZ29vS>U^7KQ;)c+&TkmuX*|HyL>A6Ng6JoCU|_5a9|_a0LJ&&}}v z$kX;6QvZ)Ub?-s-|H#wic{}_+@)YqA;Qx`whz|k(k33F%2l#)+;v>TUBaaoo3;rK@ znlSu7GW@18Gs|T2co`!8*RvL-jNyxIDpA51J`-wNvHwW%hmd_ihQEks=Nun?8~#ro z2j6XGJ}(~B$}vWs82mqee#irY|L11-e`NHB|3`+O2>;K`@c+m|#GixzM~2@5|Bnn` z5dI$-z8(BOGUfySj|_hb{vR1W4E#Sb{7m?NWb6<4e`M@0_P8Gaf3Kk_8`{NVqQC(HWf|Hf#C|HpRJD~12Z<9()# z2mg=!w)npA|9HNYlJSiPh)*Q_W7&V4 ztPlPl_ZJxcA9=hSpYZ?K9}NGGjQ;Td$T*+i|B>O>!vAwK{6F#t+28R0xWB;g|H$wG z<^OSRmifnV`BCCe!T%$VlzOIP?$@;b@B_OY@iQK(`Hq3sf0Wc~h5yIphl;NU|BpOy z)jIY6$OBfQUULU)NB(QIfS$(vWcfmc1{(KTv%&e{^O44VC4Ub7AIBRiz8d^LH^cuU z_m$%p{vWx&oKNuo$UWqEhyO=@U5i=i=R{cNrUw%AW{Xg=G6FKVtk(VDo zr~V&#+0hR*|Bv&Xee6Tc|06H>;5@F+9`YK=TSNU{@+!%HL;YX!YRQK~{a-iB_1<`~ z)E7nlU$!rk->)&>G%?;Nzi$)8|Kt2NT)2wsm9-;(4f%gue#7}|>i?0E7l-^m^480@ z)c+&zlDskaf8-sPuB!h>-X(cy@c-P5`oH`>+j{7N8T&zoBvTu>%af% z9rgd%e(2gA_5a8R#pjD2n{NI0T)n0KAKUj{yRG?uL|`hVm@ z^7n^)pWFCHg^~ZqcKCuFhV}Af4$rT?-_ctS)c+%&y!S-?Kk~8r&(!~OGyFgDaq-t) z>owH)%#)9ui%W+aUwraX{Xee%%JWau|07>}{;~RhFG!6|G63dANj)L z=j#8FFFtvp`G0x*QvE;jg~u57T;sD3KT`jX+xy{z zm+JqK&pv$Vtd3sbnfiUc>;W-L%af@c(Q+ckZeGN4_pTAoBk>e)jdN>i?1V9y=oW(3`D&->yyS z|MC1>vtpt8f4rVf8QE3+KmI*lT6{m`|B)qb!5PwLmxq7Pm#I`v{XcT0fU4^Mk!yz6 zaW1qv=ox*tklZg{72hbWruu)ppB5?i7qzHwP_aNMVGe$iI_l>&3A33Xky!wCSg#NLb|3{7$9}NB<=hvcZ zfck&r6v>B!|3^l>Quu%5WXb!3|3^-2TTlHzazdNB>i=TKga1d4m-lVq|B=(=eO&l|Zcd!@g>5hH&sEv? zrE$gpsn7G^x5k-+!ks%meP!HU>i6ub{a?oY`X@M7XZ@Gw`>-O}`J1eX@A-PPvt{?! z#vOVDI#cfc-Z)e0SHu6~{%+g3srr9zhX2R;A|DU_9~t?0@c-QWuP*=X#qj@l|CatA zxkYAu_5a9elCKH>kDS@5vHE{xygv;8kDS;oNc}%@`|hFY|B*Ah;(p`L)}Q%*yg!UQ zLim5=^zLEm|8e;?T|?CWBO{;i+UZx~$;c->mYy$<+lDw>zRcq=Pd#VROZ!2fgegM^{R@R2Gd4l{k($kTk{^ejEHh&If)W{69B~OXbDz|Ja_| zteN_MWcXL`|H#Peg8yeM>xcj6X5{~o>HoPI{vR3hMgAWd`vd-;o8kYFvA${zLvB`$sfu zto|Q4Cdgm?KQjG4H^cvPGxGo34F8V|zYG4Ko8N2smT|IdKm0$or%3%*_zxY4&{opIP=L?_5&Ht(YSJY?uA~GN3|Mj~#)Oi@AF`C;(?I6m_D;Qx_P4;cO*8TEYO|B;#hC(e=jg<$x9ZXOew$M6Z^|8e~l zO6U52ZvN-_<<^dRqwxRO4j&NyADR9i8F_&4|H$wG;s250@4^2gqaFSq8Oy`}BV&B{ zf7~80{6BJC$y0;>*Hvn$EgoJlp<(56>i>~Ze;EFso8kX)dE}?1R9j^0Yf?r2o{;=M zuD?>9TI&CCe;2DzPW?Z5$3T71vISn%{68Kq#pP&*|3`)|3;)kp4tMx}WcY#b|J*F! zf5tdphVPi`#i;+w^&?*m^?x}(@QKrNjj?>b$UH_qVaCZh)?Pvw`G4GAF#Nwf&Zqf* zTpxTti=;(F#JC^!~b)$)UvhD2layC|MBxeePZ~3WYph< z|3|J`yrlYn_%H2;qrRS@8>;_D_Ve>|>K`9q%QtJ> zz&ZLuANxFm1DZH1q7!o}3~j5vTjNN1f2@0gaiAyGsW?6%Cwg4E`hKA)Y3l!xW81V> z|Bu{A^8XSa$65cnp5{)*_p!#+#n*%X$NqI%rmO!)PD{;D|Bsy7qOJOWj^B1=R za=!1~Ci|zXFXPc3@Mr%#7Qb(LX>Yz6(#+c7`&I1J)Qge-H|ls%_5W(ssH^@Txq8)F z>i>~bYL`?0k31kLO#Qz#o}%ji`AIzoi>~jjY?4ekDNL(Uj09ESIKv)`9GIz z`3`dbqs85e#%(1Z5&j?hw|KpY`hVnrUjFL;k;4Y$=KqnKi?4_LzlyIHQvVO{Tf+Y% zBM%V%A30V0Lim5==7ZzZ|8q0^KR3hwBexjhQU8zZ862zrALkQ;^^5;UZY%X%QU8~m zCdU{2KXQXU{_6jc8}<#*{68}CBjNwK8TEh3(fyif{-2xS|B+kuZKnPoIjx_+`hR5X zfB1jo4Dllq_v|pv6#sL`%|3gxZIYqzhd{vWwP z=X&b@kz+bFRR510->r%If8>xpftvrv>sfgJ5cU7as6Pzi?1VUAw3LANjo-57hr7Z@u|Y{Xfosy*zJ(|3}^+&m-agk+;b6N7VmyGyFgD zj+=MY|08d^ep~%N@HD`@(9@;_H~){^OX_vP|07RZx>Wr?9=~Je&xa3pmONqJ z0`>oRzKoOl(eVGsy_YOg|BpOi`6~7Q$X&(nga1eFzGJ8Qf8-%DU-*CIp|U;j|H#wC zcl<;7Cm)hgZxa3==Li1^{vUa)_{#W49w+Au{6BAAVmy4`VfFvm4u=0nMxLu&PmLFd ze=XlH#&czS_{73mbjFIQ)KQ7uB`HdAjBpZ*F zJkeLe+8Dz}lzc~H_^I&!xIQraKQeq|_K zo%|5jKjWoGPpkjO{!8S2fFZX|+w$)oIi>y|+wuJZ|Bt-%*eUh@$P4BAhWfwcS&}D= z{68{|7x;gi&pYDh!~Y{s6JHblA9>NFN$UTR=Z+es{vWwRm#*snkv&Pt>i>~zCAZT2 zKXUQFaP|MlPI8Lo|B+uwZKeJnxwhP2k^g(hm1C3e{p;cOIH{@le$L~>MD_pJo|)Q4 z{Xg=88FO&{TK`UxuZjAd z`;N-*+s>cI8Y3@nMVWYG_;T?7*#D&D*%h0VY<%j@6ZQYx?ePEHjQYRiQ+FS$|L11- zf8^6LAJqRPe<;7lk^e_NbN7k*e`NGW{a^AS{QV&Hf87lKkNknOuZiyISrPM!`hI65 zj}HDH`ShcY)&C=(dHjj`f8>)-K2iUV{K2!&9Qc3aOV2)4|BrnA<1f|!BVT*=i8Jf` zNb7&~>BmmoUq>6?kiU<9sy)t&Pqv?6eCFk6&bYagj6eM7b0_Hd6yx(RKUM#a+k4@o z&(!}T-+1wv6Iyqc^~ZeR|8ag7pMI+TANi7OAN)V^71=)2|0Q32{+arJWQ+&@@9Y&v z{Xc9U{6F$}X-EBE_P;3eLH-{Z%ftU8V|nENkuQk<2>;K`@c+o?q(Aci$REnzfAIgf z{g;K||Bi>~1KX~MPd2Ow2|JD1C zoTSgz8DF}S>;G~5lh?1S|3}_&@}&BIc@#esX`& zxT*L@@c+2}Wbw^V|CgL7z7zaEa%x&t_5aAtTUJv4kDQWHUHv~d%lp$F-cLch)K@W1 zPOhf)f7zZaexKZ*we~h`{nYi>~jNM2s?^0%#jV8|3vlw z+&nq?g{>ccX1if8jhhcibQ-Vt$T)RKvXlSAkG=SlFFx_&lSMu=P8-(TSsMJgai^il z&fsppG441d$$|gJ?M;{WhkJkZg(varg6i+J9T4qA75l9hmks&K82#b@arusNyuttD z^6h$ts{cpM>Jg^?9~pie{68+=Ui?1f|G63dpY1Qn!-M}vZr54rm5TpI?%Xlhf&WMD z)FH@uKKnc4^bUT`;eFqG@xn(x7`M;zcl!SGN8^r?fBD~1|Cjd*kyi-+kKA6)@9pXT zFz(bNT>U?`<>o%A2~$oAH)A6HRUzhvYW!vAwK z{6BJg$$x|YN5=Z#|G63d9~t`x{-2xS|B>OxA^(q@CHaN<>di6k7#XMaf7#wOHc|aQ ze*OtDvFiVkk$(vPkNvZnOKJaH_ z78)ZD5B?w9+l7a#|3{|($MM=ro*eu?a=Vly=h8QeZTa@ilby~(mKdi<{ciYw?B7!U zK6U$8t>V4w-TKyt?GWkhi*<_j$+z?2&N1HgbpKs{U!TpFeSJ1xzt7ii^JU-u|Biiq zJm0)N-+aULFmFHbf3f(O?)~kXf9Sh?zU;d{eA&0&vM;xn>#=+NnLa+_|MLBy>$&p( z{?oiaU;pnvUEa4p{K4(l*XDSJ576@m{$RqmozTjVJx# z|FNC^AGv1fV(R~q;Tt0Vk4*oMO#jc#@c+p5%T-kWk6fp8Iraa@sCNwikMl2EwygSp zbf;)c@n> zQJ_R=_5W^c7^40kd^ptqTIL|0Co4k=nsF zUWoj?4gZhh2Z^5x|Bqaw&}-`dk*gPcRsBCQ)(`)WTtf05;s24#7Avm)AGuud66*hP zK49ekk#WAj|0Co0h5tv!@hkr~u34$F`hQXrSpC+z)v7y59}TnifZBe}xyM6|LmNmv zM)ChRUeo#w)c+%+{_mdyhU9R(zKXO&sfAIgv^=k#F|HtjCRW;ZD zGp^>R{vWwcjmFNZeStZC-=wPVSEW`X2mT)!{$GLbn&m9I-co#yFVqKIQ6Y~jNIhWq zf9zjN#)tn$#`y665<3-E|F2<sPCz{vSEMVJT;J)!$_g`J#~eetpwI)c+%+ zegynKa=83`iTc0GM;21w5A`{b|3{9L`kC&}!M_?2_bj{oj|J4%L;cs4WuF=&Z}05y9~-w6pX$q;N5-hHTXgk9 zFNXie@lwUdg8xTuIV@cLKQi+D_I`WE+7k!L-cmm)qQ{6Ayy zx8VPgQzb7B`G4frl20i2r;O8v$EyFw_D+&_2>*}VLAD3}9~pim{6BJxyswM=KXR=; zLF)gJ8%n;R+<(g+P@;hPesKfi)c+&L^p|?a;{TD64+#H{4F3}TA315LNBuuH!~Y}4 z4)bXKpPP~YXFN1s{XfnxYEZ2Df8>b%ay=3Mj~w1F4E0ZJ`MSatW*;(cAoYj~{rRBv zho1=lkIN_Yi`4qRWaJ0V7{AZjLk5Iv{vX>@`bDV!=Vs*pk>O9m|0Bbng#Sl|FA4vT zjQYOt|Hw&_=Lr9goGf{d@c(#xG5?R8Fe*ms|B?OV{aNJyksD^zRsWA% zGqbMxf8^Tj>#P4qE+X|dQ2&=)M)FIM|3_{l_s5a{NA{QdUtZ6^@c;OEhxd~EGZ~ZY_zmgN)Oq}`@x~3LK1uDvV~q<&7FGZ6Z*RVm z>;F}GMg6~8-L4*nnc#N&_E|8w(C%`&o4!xjGD3CY)h|3^M4&x?@%N5=CZ_i>~9 zT)CzGpB+CJZ>#@DUViy5{Gn{}=8Lz~|08d@a8vz1@{S8PkS}EYQEv`eI$Ym6$?w6l zb@CeV5%GUx@eASqkylGSJotZPp^f8?>^SHb^tGyFgDfc+=b|054P za1!-9t$pS7cf8;mCSAze?@t2Cv1^t*Mt8@M!j}9K8#0-Un{;;4EM(v@wrg{m;AQ)TJZn4{9BUG z3jdFcJXiRCWaPcV|0B;h{(<^`-6kko|AIJH>DcdK6@`hVoXyAG-UM;;-5F#JFA zsQv0+8pHQP{vX>19XX-?A9;)%FUbERkCk@h|BCjsJKjYRN z)c+&D(z&<#e`KfsQ1$+9JY*DDYEmu#KpNbO2vCn8*~ z=Y{e(pptXuWf9}}39sXP_i+DIpZp>re_!6$fd5C{Ee!vUyi5A;u29Fbzx*%fCS@;;-*Nqc)30Sc)$q6Zf#Ltz{BAy0|If|x`_c9f#z+1i+rjYv zxc)=(`xE{j8TD!5|BNANi#Cc<}$oC&b4?{a-TtLim4V_=WKQjBh_t z|Brm^&Qs0*b2I!uH^cukmi7I$P)FmF^7|P6AKQ_)2mgpM0wRpPNztmwa0Kqy8`XjQDWy|Hv1f=lXwS_-)AlBcFZpk@|n+3ok!c|Brn8 zli#TSN51v(=MMZo^5u_n{XaLu|0AE5^?m!>X~r0TfB6~4*Isd|muS_u|yynM03izEJfrSZ+jx&9x=zxCv~ z`hVmb4|4rK^38`&)c^ar+0W;Yhj{D$WA*>Ys3$yX-Ub{0(#@OB-HjWKPoF=p{-4eF z{3WM;^cI`{6Y&RAvfeX(mUCA9KmL6_s&fbR|Hwfl3aS6czvmlCK49tcdp!65@k;in zGArVX*DT`vDP*s4)n=8P|2cBN6L2fPz8~n9SlQV);*h66{Hy8%qTUMpKi*%9@7h%J z|Hz5m{WbrOjQ6wQ|B+MW{ww@HatraP;Qx`~1H%6!XNX?~|Bu|dOOX112LF$o)UlEJf8^j671jSEhy3dQkpm?!uY39>TON6Sp%X6~HxS>i_~t9d zja$}I|Bv@yDz&Yz{vWw|`^M`3k?XZ{anAK&7iA9>zc|C;)FUFCjwt-7BW zx0m_+z1642SpL!I&x|_`igymK`P?{bK%BE6`!~iJ^1dwmKaQU%@2A86Be(4v>A?RZ zw~_k3f9(1@W7PMB|Ht-@^1K20e`NZ9WcYvWfB44Q+spX^|Bu^?db#lbxIfdy$AkYz z&gdMh{vWx0mk{;;$mx=o0RNAS{5<%7WaQ_;|0AQ`F8n_-{6hGDyq}vU^>E<-ku&7@ zf&XVL=O60-lCval5&j>!tN6F@|J)4!kKA64Kh*yv!~ccd2M!TG?2;+<;ICmeenO>4F8V|9}xZ@8OIO&KQfMA_N; zA^(q@86K_qe>R>l{6BJs*aY?e*uQgpuK!1Fp5#&gkNv@JzpG1J-2cgK6C%CZ|5NVf ziS}B)Yn)F#+*og4uzifTUzq8WSC<~)?X&%_dcP6gJ|3+MkMGMFk>2@;zT4wF9{f)C{Cv4XOpI51r#SC?zz#n9&(}xH2=}g!?Cab8|IP5D z+}rERm=FBF&6E15{|AQuM@Ie{{J)0r{nh_-#5aQfM}|Lm@SSxzl38o@eQy@eW90k6 z|9ii{Aoc%BOP(M6zsMeg)&DC{s<`@pYzM>tBUdk3#QAYr9wUzo{vVgGRkDowf9wy2 z|3|J-yp;NX>|e7)Y4!ie$P0x3C(e)hfA9<8|B>NCq5d!XBR>%Ne`NT5@c+oj_k;gO zM&2Is|J;oHKR3hwBg6MY{vR26f5`uHbG0?Xzs?u^UzW{d_=9VfEw%PSWlF05$Noji zl~(_cjQ$S_ykq?_9{fMHquww4KQjEMlbaXWeBeL9|Kt1`Rj;Z3AGuVes_Oso^Kc3k zRsWC2OTB#g)&Jx1R9lW#_i-%`o}TCQG~+Twi)sEJKTp(ShW|%Ky=M4- zTt2#ryk92%AGxXcdhq|q{sjxD|L11Z|0P$D^_Ofq*7i>oS$?127~|^2N;)a^M;qgO zm8?Kp9`&JT%oydxYp0AfM*U&%jlpJFcbrfAHJ?8Ioj- z-zVP;O3G=uELH3G;`1oi*O;UTe_|3?mJ8m9gqxv_t^`hVmqH5xdjiiYLP8P`Jn z#zx}XA^(ruq*hbS|07qbk?a4FtJKQ%|9XsT?&bfv8U9~(rxf-7;P=7*b91ferpA6% z{G2+)zsc@bu7LV@jjBq01o8jM{jGrde<4*HsQ>3?)c+;7_OIw%>GG8=KRhGSIn?C0 z#tp>pTm8!y#*O+#ssG3I#mL|1@c+os^7r}j)1PK9-1eIKehKn^DEvQiO!r{*|H$Fp z8#y1hewiIx?ltxOqF!&R{vSELXQ29j@;9UUf9)hs3;rJ&{t)~>a!bkoga1c{KL`Jh zoFzUM{68}MKKOrbM*bfeKA_y+$zBxrYHq%t)N7UdKgRF}k^jeb^zSbI9~nLt{6BIl zsSgYPkBodm_f&WL&9F*(-k+D4dKXSVGUGV?NQ6m!7|073_Oj7^v zSayE(|KNim|BswH%A@|Do8kYF(I5UFIc=;*{XcU0#3Zf%OHP~6T>U?C+sUb#|3_{$ zxwZO#oL|d{t0|Hw@w?-2QaWcq((_^P75e`NZ9Wcq((w8Q`7`ILg=Mf^W9>Orsm<67geA@csW_DWoImjYc>br2ic|lOoG88{{6BJn_^a^$$l>CT_6}HPZth|4*ae(-lugqLz93=kb@7pglZYJ+HKWy-}vA^7ZJoEQA^SEE4 zv+eEz5C4yRO7bD#|B)|BfB1iHmglF&Ig$?o|BvHmi?0a( zkNX4d@c+n{Uw)zfANkUY->CmbzWDre_5a9tzL+TfpPS+Tk#nRS{vR3p5B?wdgO7fr z{-2wrex1$ttn44DZ)g0WJl_*P$@qfgfvkI@nz3$=_N`!vAwK{6Bu)@H656k_r$NfG<&zTuex|g{Xe#^xqMHKpUu|3_{v@N|JeSH zSJoda*PlF={7dnPjgfyT`Jl$jrC#~Ax>3e&i~kA#kK?ZrzYG2!d6v|Fh5tuhKY5b+ zf8=rPGS&Yh=TA#k|Bvj12dMvN92<}0?JPOJyq_e;kFk@|9LK|1?jI*U0sdMZN5{dJ z%Hx1w_<3h}J~@&PhWtO{7H!o3Bgdq-QU8zJcfvUMJ2u{k#Vg^%eaQ7M5`R?uI^%_V z;PVwXUVS`A?f^J?PU8Dy*{K|~$8h=8k{1g9k39d}MQm>jxBpG4uL=K;yd_)fX?ijI zKQ6!W{8jb;+zkJZy!h;8_5a9AWc|qhBX1DD82%r5yX1qx|0A!H^9}wVdA<14a(yv= z@A@5lzHyxIRyls*|B?4!zN!8nc~_3+v&M0}wQ_vI|0A!HdZ6Mv8ZVJNR``ExfBS=T zGT$WQg(uId|Hsb{4FAviOP(G4Kl1$dPpJQA{6V(*f8@75yny{_{TGQZ?Kw9qj^l%o z|Hu9d&s|dgkGw=a5840LKL5fs_5auoM*bgpscb*|Kk^dEmzC>}?Z3sczr;^AUUumQ zu3yGDo{;~?{k!tROX~lT7YW1vw@H2;r$@Wvy}|Kt1)iEju0k4*oMjQ2I*|8aZw$@>`a z|J;oHKlVqSH2gpE8S&-d|B>O_!T;lYj>`KXe>fUo?MKDGYxq@=G3wF6|Kt8REdAeW z6>jZd_9#w({a%;@jBzPfNZx^8Yv=^oRfFX83>PQ&Mjh{-2wB?dg;^zSO6!{-TR9 z-XDVh$N35YAi@%tVAAKNcTJN!TLW%+#$|Bsw4{u}E5lFy2d zSp0)wp4s>RrvBGa@!M|yZiMkk@!=MhA8mYDexJ8Y8SBNbjT>)#ReZUNTPGS{e(|X@ z`~GC(OCNvX#Q$rm@#Rmxbbf9&-57ayeI`FjukAKPz=4+#H{d|N&*_{T}Z zyN{kZ_1CR7zV`U3Gym`!<4gCY-n8WZar>{y?{DP)k*~`4|JEPZ8{d`sz)p#c#t&rq zrYAPp`tLt{r2Zd|e=z(%^3&@#oqxW&&8`QFXUtOnkAJ@}FI!OkznN=)IoEUP^7!fU z+Y0_4|K2ZGET8&+26j(f)a^ZjthGuEnARjaD@-d*+7JLP?A@&CxJBu@|iA33I%NBuu? z!hmG;|9HPGba0}R_w7OJA3ikMdAHJGe{fd5BM8BeM5TO1a`^U=r#_<2h3GzNK{68|rga1eF)H7V_f&6Zq)ic7WnE8ishrTiL z{_vm1nE(9?|1$0*=hu6O{%PE6P@?*OydT_E@+0B@k<+>dtN%xiYg=FaKXPlSCyo3+ za;uD*n*T?RYu#A=KXQEA0QLXKNvQ$q|B>So8^|YI{&V~ZCu727W^VN9OGsalonUxcbvAq*kJZp^k zs=53*W6Wp&>`BI0e%t9nMm{0@KOUa|@!#P8ks~BeZrtn7d+Fz-MnpR$OT1tV9}@l_ z`@_!+DfXhZcayxpgD)3yswYPMKaQ6kAE*8wxw|J`{XcToSdaRDWGuh>-!I$vDKU|b zcj7C?c-{^F&$dSx{vR3jTH*hZvAyvB$f)NG|Bnpc4E`S(^O?BMmuDxvZte8{xV>Qb ze`G9=`oA0x#{>Q!8RrA)|B_RpVjR@}C1d}Q|L102yZC=6kFVe7&#k52pSyp%MWa*qVxyumJUUZ4K$qJ8~9f8WiY{e3zAygYo~xVJYl%-0u;3itK#{QbYQXy5tp zAK#z-x5uCTea8Rb|Kj`k@4vtQ=kHf`it+UU{nzL3AO8RL{r<1(gHPo?p5RUo&dZxM zwU7FI7;nssxyJCL-Yo0O@c-DqXwjk${68}4eZv2H=#Rd+zx?aI_;TgSssFbuwZHm* zWh#_Z|BvmZ%NOMTk&&+l|Bnp+F6qx%#>fLh{vX@H@c+oj!$bXFH>3V98F_e7t!L(O zdn#6}sQ#bS@U(is@c-D3@!|iG;TOUGBiAWkN&P=E^7-KZk?U5dtoeWBhaP%J^Z&@G zR|@}++(`T*_gnx zj~8+o@lE0XmGbmf-xTK~{69Ct|05R@e-QrPlrufm{{tickBoY~@c-B!=P&C2^8CD4 zd^`AmZqEJu1!MHTJfM&<-tV`bw|4l8@c(!|)fQnE{vXGq|3{|($L*p2N4~%4JzD>l z<2`U+f&a((MBX3#KQihK!~Y{!c;Er`|Hznc_|QzKSr;cVC{7)KdAm6`^Qx- ztNtH3wDkSz|B-7vP{O$sJjV9FR*6#1*yf{+k>3}#a-_`%&W91pM;OB|h5yI>MZ45u zHZEJ@erJ63$Bj!%ej)rnt{?3i$2?~IP=&INWCI+7Pg{%KZjtMXD|HvWodt}`8*u2Q!6V=`bwz}6P^j10 zbST`oK~Riy^Q$o9hwB8W|HtiVP&-ilKXSdA&78jm1n158XM*~DC8Qp3>f|8fvUQtl z{vX@R)o<=Rb+TFBkGJC0_bVg*V&!rHd1+sHbNk%B?yV?3;hxZ@#+7R~b4GM&VqB(9 zGxh(%cHFD}AGp-@FLTN8BY)ZOg%4kO`E%pwh#Knuv46*QG3x)3BjkNB_--liun8wYi7rv4w>!+HlhDT6NL zO2)kUeknbhD}ok zZM;PB1?BzCLY90s_aZO^n-4NK*fg>u)zcLH$2+)|0aSE^DlR z%OL?yzn~9|6Z`eLB^q`*4FFryAq>ZgcPrV~_ZM z8I|6!&ky8Zj{SOyas0q2XMWym#_;p@y))T3YN*^V9rCJi^pIHf|F}O<(jWdG89pEU zKXRCi-#z_Bi@AlT<)*J|073;PYM5zpKqZ91J(cI@j>3?Pk)ZL{R`|H;v}qi z(zw37pAY{p$N5YBKPRk&)GHjAD>Vw$_j9V>;~YQTFBeV}e2nZdot?Ml^)Y^J_AF=K zyq>vIlTv-ZQ&+F3|3^M{`3mwma^;z_`gRA-eS-WB<84weSf1}0=Uu&y{H;R1azp(; zj+ZBl{68}MHF>^h{lStyVhsOJ@=1($$@4n+f7~AWe`NZ9WaMAK|0C~~=X>z~$ne?Z z`Ks||@!7-&vh7GmgjAgTi5ep_opKbDd7th|wTjlvL#^QL$mxTZ4X83>X|DilTg#SlgE&bvDkylCn2>d@X+Ts6^ z*UI?>|Bt*z@@wG#k(WySFsTn|>t8APBk=#&zUKS|t^ez0@sX_m8p$Vt|7Y#O@c+mw zg^~Y9ULos)|3_YR9Q6uU8?QKWO8q~!&lZ0I`G4eh#h-xxM}F(j8TJ3jGmoBA|Bt*} z{6^IOB`-U6TKzxr2Zv8;{vUajtRMM*IW_b2IY)$nYWI z|B;bz3IC70LF#A2|08b^KMVdJdHsI)lu^cuH}6vakL{=j4gZhaeG1cv*n9Py-aD_W$o>{sQ+i&tq;zh!uA0})c@oBIDH4I|7YBzr}}@! z9Xi6l+C?ssnxOuleIF!5tN&*l_Ne-Qi==Prf}@ta$BtN+LCn=koe@c+p34jxzk zk33)UQ03p&zDUkbIlgh+-o5y$Zs3d8>+zb8H{{6F%n zy$99*Bfp)$PyIjgOxYjg|MB>N;s3FHs_Z}fKk^&myCMIN{I)Ri|HxQgd{G;3w)m0o z|2RH;#faKkC|G510+&$|5k(Y`e2mg;eN9x7P z=eO~6smG4|KelHK7$)cEnK+)WWxMxO|Bqa}V`ugM$WFg*>i>}&ygNhvKl13s>zoIV ze`({rxIWLB67;R{^sRd(kL-uIE!n@S&o^iHamgS1)p+*4gHmtw594`{r~V&#L*8!n|Hv!Xtad){Uc&lMnLZWgzlZbD{jnZSP*Pdr zYE2)J`kv*izw>Alspnb2IHY5L_5ZlMvv`yGf8??UFF8|pJ#76yIDAq4KW@*eBbUU# zdDO%GLH*yaZr3n|j|cyc?Hlg;f8_Pz=hqxx-`Y1x9y9zuj=%Y2f&WL|F3Yc-6kzRO z_Hm@G|B<(!De(W? z4F8Y3L;OPce{P2VN5*(-H?=ZGp7!wDt&P#%sB&9lwBK%#ZM;qVz9r+@8^Z^L|Htvc z@c+p4|H$zB;QzT9{vR2>9{fKt@&V!hk@5G!xh4ZVMMwXVgFH99@A6jHLB`0_ga60= zVEBLRkN08V|B>^>mxKRDhF=H&k9<_x;s258|B(-hKM4Pid|cj#g8%1c_GiSYl(7_ZLHm?B$nl5&=VthS==j8Kfq4Aj$$DKaI7u)B<^w*~# z@7BZb%V#rNtN&NB)}QMCAzuOhpZ&dG+;Q6ezRGiU;lFa0&wIyPxpsm7_v&;1&e>jl zrng+s{SN#;a*W(Bfd4nPhNJ!;{2};%nbRHh|1!IUI`IF<@B`C7F*(cQ)8+O^Y%JKo%7+_F=c1OJcf zgU<*5kBoXTH#_AUCrf>hUC-_|?jpY1toQdAcb5AvBaZDgP97TWr2V|l823-*{;P-g z3vvJVulR$7?Q*~L+@M3oxL*tZkNsOb9=+$f5|6|yKLM^?oYx0H)$3b93c&SB+6m_J@zJ z8Mp0G;Qz6IhWKvq|Hx_GLe&2wM+w9KBgcr38uZp}<8(Q{N^bky7|Y+j@`Z6~w;-+m z%l(D#hWtNrTgmT(|L5kMa^Knfw!Q2B@%}6r{vYQb{ww@Ha_f%G)c<4uxOVl`|05@M zF3A5QXLJox|Bsw4c?t0U$Q}C0`6K?Ho8kYF>Hm?l2gIoVNABOx<2?D}zpQ^3+25?H ze;a3HHE?Fua=h%HmRZ*+vZavYQYxtb$NQBjt*fd3XWXX1|0B0(+eH08a;x-${6BJw zl=_S_D|05%h5B?vyO?bHa ze`NSX@c-Nl|BsCR@c+p0qu~FMy@Act|09QoG@z?$9DREi?13#Yug2@&Cw~krC?u zk>P8>|Kt8(e&GL+yUTpS|08#k;{pGV3}3Iu@+o${fS<4bx-sgp!vACc4v~?X|L0ym z^8d(~fB1i7`hQ#=^?~94k#T;Y{xAEdN5yLWUo!Rw{vZ4M`(yt8oj?2M;bkSp%P*Wl z|2Mm(FK4yz_4|6p`}%_LGkuo#^WXfp&)=uR{J59*=S;aC-R=JQfBua5b@$Jf#V=k5Jp+27}b zkK~?@|Hl5y|2M{X@c$;h(!=un;Qx_}if?qe*u1<+-}F?U?}2;oa~i%f*SKtnlFr!s z3b|CNQtJP)Kl1jF|5rAwxB7o2D^*bckL{%@SJeDJa-~X@)c+$_u3TCDKXSb)1^It& zhW|&dU%86C|Ks+6k^fhIZXfmk;OoKvV>=lBAGvY)%Ig1-11deN z{vWwP<%gZY4c@l#;3L*w_LlJj;t$@eS;(a;J>)E2@TRrH@9SB$kegI0@7#I%&Acjq z_f@|yx?I$bQP-CT4|&PPgTDv=kL!a^2mg-@-wysC8S97t z=VthSZifHI^9lXo|FNC^9~u7Ni|Zy?e{9dGfI_}c_UF^VlWhJ_&lmZBJfEP0{@R3{$M%v|Hw6}R#g9w`~OIl z2i5;0KU}M>`hVR2+KmI$|06%rw5j@k>|e2NUG@LSO~hw~|3_{p`JnLsxc-XO<@dJu zf8^>7>#6@ou3x{t`hVocjT@`~N3J7z!|?ye_2u^z{6BKT$RPFqc>Xtv3ReG*946my z$p7Q@21foL*&7n3{@?aj64d`|la!+VANd)nw;S3!DevaQ#N2-6zVwa^_d3#+$9BA* zQvV%qo;ZQ(1E$LNJM#a?wGzDQ|9$t2SN*@L;@89fBR36k*?R(jy{$IIR$+Hsw zk6hm4RsWCtko?|)|5s;poce!Y_sD^lpB(k~I&_x%J40?7BhT+*+zsP6dEYGm z!Ox6Q?-c$Ymv1TcFZ&<6l6!fuqrP9N)W?MXM@BpRKQfj_{-2v)Uh_$={EeE^An09h z+kQdn|B>4d3RC}&48Q8n;E%08e7RaB&Ke`%EbX(?#!=$)jofz181+@*|8YDp{6BKq zW0C6rk&*WY|BsyhShV_o&U!Lg{XcTgaV^#VBX=8)U-~u`$jM_?|CBDc_??5G5l5df9wyAzVl8Y%k=>NkL?Kq0-a4&-?HVS z1_n8w{y4)pq_;c|6#tL?TlH$J{vSC*+Ts6^y?uh!|8w(`3tqSOc)1_>-smaD3E~Iu zPkYT6{vP~4e!hU=|B+FTxT5zJV|<>(R(#pmBYC3zzk1Oa^_SuQ@$(LTZBq3YjN#K> z9z4nVHyRl&_v4i>~1UcZidnz@oGQ{emEysiEpIseKv z_5aA5uH8`okG%Q%P4)lCdDm_sAH>E3OMZy)-mACO|6~7s*FIPOkBoNse`K`7|05rj z=V!?OBOjCg$p0hnmG!~@Bj-r|2K+xV^7Y{Vk+;h8DENPzkGYcf2mg=r_ukdd)&C=J z{PdRkf8)Rsx1OJb_>)LJg|HwJlKNlaO zjvm@c+m=#HWP+N8TyN z5B?uHN9F_1&bYqqa{Tdc^0uotk)LG!m&)@`_P{F|08dZdUk(&wLFLC`%1~fne_4!<27>r7OVB1G3HjnNF z89plV|H#Pee0KR{W7PYD|Ht+{;!DE+TSaRBM)ooQU8zZOc;yn#oEih z`wsjU<3^jdsQ<_QA-VbL|B;c8hx|YCo7?i$|07S{fxNdpyEs2!>t2Po|^XdZ8ZQ^$68V2@Un%ItN%xyEPf^O|H$v{DDeNt&%C=p{Xg=Ur=OPJGbe2Q ziD_x#Kb?saCr^F6y}NDXLika(B9qRFWoeLTk=&?n|*0K z^WaITPkP6Akudx}u5YQ-rxo|bc%9_Q!vACYTDd-u|3_Xg`LoFXBg5x{|Ht`WbLzbM ze`NUN$p0g+ljY(6k(Z0_Dc7&@)-~&#Uc1W}Pkwfi`hVQ zIM~UWQpGq@#)JRI{`17&J^EcWR>#9^ecQwbEdK8Z<6Sa7 z{6B6_jx3+QF~&2c(hushVZ4bq;(R#f!Fb~xXD>RxdlQX!etgN<@_4fGE@>aLpoQ^H z@de@kaeZL;f8-ol9{wMBn|z}ibpxm{26Hr{{rmQ&?leT{d^?=$#+oG<)dh5twX`1)<9?Q27f z&wci}`hRRcCBFyZ|G63dANivE9*6(u=Ipmed(K6DU*Olt`pV^xH9joA$4}lFXM9qA zuTFdTDIadt;u+%;@_W9-=x2TScAH7Y$n#4Y_`DA z_A2@MZ{Xd@n`=$Ob{6F%ZV@K5g6}{(aw2?&iY(BRf(*3I5-}hyGCiuUf4~HUF>LFMp{2S2ehp z`hR59^L_Hob)MrV|I9hMc%~Qr-y?0;dtO}qR}S(3;s5<(%m(8m@r&U9g}wUE9OMJG zek|D;-F>rh!efa}>ld~dw;Y}7G+4RSxW~v0_5XN3uji=N&gGxCTYLJ5R?g;!cN%9% zJN!TP@A`OaXYha=YwtX~m6P~-u5sGqY3l#6f5xZ`=eP6u*53PxB+^8R$W9S4nZ|84EG!?wM+|2BE^5o4^c&!?eCoR z;m5juY}?yXe8iTM&KaYAOs(bTefZC#pBT3p7^nUpkAJ4rw}AgghF^B{*-Li5WXkh^ z_m^HaM*Y}Hhdwn%{n#$wUNLUpJL|ivUe%_beJ~M_tw`bA~W7Jok|Nc#5 z)K`Z8$L(v?ReU1x|J)4!j~p*~lDYSOWtR{xZ()*xcDy`CrB@Th(=BTaDYcuBHAT$IFtuKlp#- z^vs6NW9dbVGuk#*|Bv@4Q>5PU!khPa$?07})&Cs?AQ?X|J)4! zkK9T8IrsCej*=G#|L@KxT{RB}ei`!r+zkKE&G7%osP7B^kI&a5<#{OlKR3hwBg5~3 z|3`*D1^Nu!T;m=0v`t$|HjFYzT+cb(cRzQkM#Eg zdy22??hk*|&HnS95#sxK858Ndz43nall|A{&n@G8x8L6%^!M}p{k#9G59r_De|&%b zpYr|O^W)ziK2k!-`FUSm>8gGoc-m|8jFImL|BvnWlqjbDAGv7h66*hvQO_6oe{P2V zH=$N{_5a|Lb${+%Yeya)>i@Do{4(VKk&zdM{69A%|If|v|H!qZerfgWS++j#>XS2l z81;XhNj=o}Lp%IG<3|eoKW=aJhYRxm$nXo1|3|JP`DLj8OGcg<{6CI|{6hGD`D#z~|Eg6kr~V(gQn?c9|B>&PddnS3Pq*cZl_{S1ehO|3@zOU?uhc$Q3F+r1^i`Khz6G{a-TbCBy$CmoHsh{Xa75xx)YB z@d5ukwUEmcFY2^9_^P!d9}xauzvsHBj|zV9&dbInirwop8&=50?sJ@0U%zDSIDe7< zcP^&0`hsB8|0S0c|F8bC7mQ1ZUw2R4LT*sxUgz4<=dHcIbC2f#aeFGscoq9UZ|j5a z2mg=l^#9y^ZqIYp4*wATALj!M|Bv&9dcN@g$PeCMRQ*3P<`4cKxoV{cop;+lYsVY; zjpfrP`Y`-I9#8nFsQ*jG`33)v<28D)jOPE5BWgUN{vWwvokz9)FFBxLZT0`SKLHIJ zY5iZaCn{R&|B~TfBma-wyk2ds|I6{3Jo=E<|0UO{R8IXr@X47B;{ zEZ=96<(KzU5s&(Q@uA`B|B>4!w{TugOwN1n7mxaWPh_@N|Bu``G+O;X_K$8B=)C%V zyp2cyugx#9>I25d$7}sxa-_Wf0RK<^Qy(y(X>;}e$l>z+i2Oftuxu~#|HxkP;gJ7F zPEAc!|BsxMl%)P2IY=1!e{P2VM~?F(sQ*Wfl;6k5|NEm%jQW3#BO=xRbMwqqf!1DM z_UFd2=01%2za5H1s}G3fQU8}580T?N|Cb!#^=kg#MqeaF_%CPyWVL{||YB z$p0g^ly>C*k@0>f{68}M9r%CbNU5g^|BoDV*Z(7@&4*nnecOIwr$Bf&LF7W@@j{3Rq|Hx_M)7AeYXFOTp|B=(jq^kc%&YX~@ z{vWx`Q|apekvmI0U*!L}S?(X^p7{PBdOxxAQz^K=XxwQ+GTuKn?k{tEhr%l96g z=zP+1y>aH~SoQxnUv0;F)c+&*yj%a5+)e8LBL9yJU$gmv5AFDY;s3E6{uc88$nm4& z)&CqWXX2Oj$qtKR3hwBX<~=p#C2@OU8r$M@||Q<$Sqhk#WlC0{@Tg z$n%5$M~3g$y~zUO=rQvC+P(9QV`P5d|M7f9{@>EbxjuZj>>Oi^2mg=#TaNLn|7R@o z;hj0t+FQtY1Bbt3oFV7uw4}F<6Xbe^|HtKP_K#5i&&~H9o^I`^e~bJ-UjN~}nyddu zZqPGO{XcT!J|PbLKXOQ)K=uE~5d#YRKXRnhUxEL}&ztapvFiVkk&l|^!zX$)1{ewq@tN+LS4;d-nzvBP#c!r2?4F8WD zJ}OTAKW=~2uw-X&?cupIKKm)>`I&Efi$;`F|L@o9-xc_OmG5yX+}AG`&J*hS_IR?d z`hVoNq`n;T|Hx-<+))2dGG^5OJALDp`hVn;*TsjE{6BK;UH^}q|Jg0||HylU;s3cA z{vUa__*wFNF;|{x>+|wG@;pwSKN{2jV}CIGKk^~*x8VPgkIC~p_&h;-G z)c-By&$a$98NMI~yZ#?J|E~W>hTn$#Kk`o5fB1jo-JgA-{vR3R!T%$}4}|~c zX83>PU6*g7KA$msMycOt3|~<4eT;Wr`x5?(@p{Qe+;ORd@h0gH|BvHuzWRmwe`K`7 z|08b{{}TS6o8kYFH_P)+_k@qFJRek1%pH^cuUZx&w>{vVg$BI|?yN8Tzv zBK$ux&Ug5KWb*l7{QQ=!>i@BS)i!O_|06qLiR%B6D`fS=^=0E1 zduEFIe{2u^U@OjlYkz*rUidV&zUlkmtNpr*^Sf~WVdQ-oFOa-9Ie&I>yjgqIPcxpm zNAt~$XG^_Y@uiIC?m3A0H(s?f2R_#>p6^S=M}+@Jp1*W~`hVo7o_|{XKeDGsmim9> zCg~n&pSqLmv}vdQA36Aq8FK&8(Q6F;`NVa(>i@BQ_TdZIz8LP`a>=`c|3_Xad3o^v zI6rg64}|3`jT>TARQBfpt{RQ*5lZ1ErA|B>GnUkm;pdCt+Z>i==R z7K^_K|Bt*v>W#wxBX5=bP56K0E#hOr|06FIzYqSOo8kYFmx%8N|BsCPLim5=1$X^F zH^cuU!*_)L=VthSBi9%FKR3hwBOjOThyO?3zJ9a%f8=RXCrUlf@;1KL(@g4jRy1}RS9E@@UBx(g zY%ga+yN8W?uh`^_c&VE4t0yk2|7ZInzBls!$m>s>Q~!^Qd_VYqWcYaS|HxZ~udHn7 z!*ee-Hb#H=f83v~;s+xCkBoZ1XNCn?|IOl~Pn#cNjJ!Pfe_S8@OZb0e_=rVbj`Eb= z_Ko^}=nwyo3?C2vpPR?^@p?L6|62XCUE5B?t+-|z7M$hn_LUbFar+}_>teggbIH^cuU=S%%|3}95!2ctkmHC1HM?NF-0sqff{$7LsN5*{4 zZ~nS5{JwvtykUIo+D-NUIA6!a_e1`lo8kYFPs;Iy|3`+e2>*|K=F@BH|B+A2??w23 zWcYr_|8q0^Kk}(dS2X{Rd{puP;s23ONIp0GKR3hwBf}3w{vY|^$usKzkq^t~OHS;2 z)((E8{X*mXBL|(Qhb=N*zjGUYkK5O;Z*yIlOIg7^LI`hS1S z_(lD{G8N0I|F>@Nuj>C*2`Q-mOOBU(Gx&e~<9}2C5A}QD|5bhHAL{=hFAe^mvE=)~ z|Kt6-c0&@?|0Bmg9;^NzIr)ir_5aA-#eXYuVw)}BQ~Wyke{9c|`*HC9+&ta8%edF5 zMD_pJ-eW|(`hVm$;>$gi>~ZKL!4uvF!iX*A5vYpKo8$BgVbte(rlsj{5NUtYgMq7{T{vXd5)boY^M@Bv!{68}C>)`*9 zJIMJ6|Bu|RYoG)Fj~vvgq56O1@a_Q){6AyK?}Pv6X83MDWky}Wf+@c(%K8VvuB_v2c3ll(RD|Hy56ggV=1d~f~ROa0-uw*Fw; zL44ayw|2vnB5U{vXHd(7(X{BX=H@DE9;ZVeLHz#5=vl{cha3cZ}RW z{KL4D%s>1;F5h0}AO0UXu6Gj1QL{vSEIMPv2<$f@2Y>i?0`6AJSG$o};;;q$=%%e>N2{Xc)d z2Mqs@?eOd1|B;cO)^E>HpIh(#BJr3Xxj%2*D!8fBJN8B6mdzSE zVLJ*rtywdtc;rjgj(W@T_pdSX3gQ28eV*n4>i?13hBQ(CkNev@DMtN2a<}9H|Bu{8 z{7?9QWaLw#{x2E%l<@z^s6P$=kBs`$*G5gT?P(hvp#Gn2k1+f{GR_D1e`NS;@c+m- zzv2Ipael-9Bg5Z>|3}98==Q7peK`N?701KfAM@+x|K|VsuMhsMdwKu${ZF3!J|Hk{3AD`Ua6b!FXEf;_kZ>G{C&Rvw*3Fpj{Lv0@f`~4 z|B7#g{6F%2#fz!`mwl?E`hkw*g(3gX&B*^FmyrBA_*hXVjQZNh|6@BC{vXdL_i=>1ru7Q)|HujQz6tz4ai=>6I^OmFnoNvV|IZT;sQw>0zIm|vf1QWLsQ>3}7Nq_k zIjUh3_5avEvO#0@|H#penmQf#dGp8t4VtL`_sW9Vj)M? zYUB(Hjj?ttKcRiJaYRs<`hVg8sy_(74)uS@4di_T)c+;d3XM|#k6b$}TI>IkLxRK9 z|04$lhRE~i5L>>P_>u2E9&FrP-rs=#7w~RG?jP-LdK*c-WB7k=hW|Htdbp4OM{X*9 zsr&o%(YP3AV2iJE=f3#6`hDOwRlhV2k^Erze{7G4m-ltV|0B1_DDeNteR@h>zvTas zQQs8)9~t#c;s23a3<_2M?;lV7Lw&yt$-{&HM@}CetNx#x;s23Q|Fg&W3%OIy{;IxT zqU8I*|0833_i1-D; zTla3}EDQM180QP}|2Y5Yaz4QSBg40X|L5kC4OiNHM~fd9RAhy5+>;4T=S%M!XN*sA zp53_2xa~7(&bfatvGpU*@UIJtjk`{0<<#D|$T(QqA9`q!Egvx{+wuPRo^j&DEN8%x z1;z=_v~}KCI^Q^KVurKfnR&)BFJ?QdF3+|7X+Nohb9&<(ABO+O^F3R}ga1d)db*AJ zf5y*bsQ*W9_iU#6f8@^3W~u+@X83>PAjzvl{-2xS|B>5@|JiuaG-LRbS>vV}*Od3o zQU5n##c%2dR~{nuEX4mKhYXEX|BoCt+@tw_evBzFE zMt$Y}OI|X@_4oSt7mXvuhlKyf&#yGO{|x_+oFw;G;s22vKNha_f5`zOqqP1nw=Yz# zchvtSM~VN7{6BL1V=bH+?Zy}v4=;;+tXyQ8!S{0>Dx&@$x$Bd?)c+$-URL1$kq_M} z@c*Rdoce$8=TQHbd{UmD!T%#~7vBu^f5|&;e4+jy`QXhj)&Fxd{6F#m=@0);o^h-H zhyL*Y$a`;oh5BU1dv3^hwNs2w$nzxle;n`3%`epdBjfoT^8d&uBp(F+ANjC6&w~F) zhEIt6Kh6j8I^h4o5rfZiO#D6ge`NS|@c-Nl|If|v|J)4!kG$`*FV+8ZGyFfUAML3B z>t^Ktk@I9elH1j^?caUtYsqh`ZoK98*T}~)-X!x2|BuV(%J#$mBV#=He`L%z{68}G z7ychP@5Wc^|G63dA9?$Yui*#S`oZE47;ll~AN#$i4~s8lyzBZ`&M$8l@nQIX9Dmzq zU#b7+X83<(ERQS=H{)3v=X>|{FE#&@$@=VthSWYn8O{-2xS|B;b@2>;K`@c+mk%J~ofkGxinAN)U_ z@9=5i|B;cG1OJbVJW2R}TpkSnkBq#9PI3D~SIljhoB>xWnAKTxOddKkp$cx0U6Q9x; z`FP?-8qYg=O#MGz57TnID)c*Rnj&pSC@-@*OW|6_lrZ)f%YjC*&KzdsyxYVmoQ z`26eY|FQjr-AA!~F&uCCUexnF6T|&qckE;J|H#Puga7Adi=@SmhL&C{vR1W7W_Z*4)K}b|B<(d?+5>n zjPnWppPS+Tk(bE+!T)nJ{6Ayy5t08#UM#*M{68}C0^$F;8U7!6iPTFJKiKADndBeA z|Kt8H6Q6DBt~qf$p77b^co{F2{KOTNm&Eb<2iF|G+!*zl=U!Z8JZC?A(RGE(?>;EL z)kbSylz%|{s;$QK|G55Xn|G=INAA1sL-qg2PEx%5J~?d5I~n!V|Ks*0&l;irANkdJ z^VI(%uidjp{Xg<7sb`J+Kk{7hFX8`@Q4jsCu3yB-f9ijso~^hg#yEbGHD&z1_>Ny}i?0K$oUKZkGxzypOODZ-Y)(k{6BK8_<8XE$ZMruDEvS2I{AKq|3^lB-OeQfe7I6f zbK@x+$L05H`ePG}kIC;z_-(_Z#V8J?;n5nO#eUZ6%^5ee!@{Do% zpm^s{sgI4@4vcq}2A(s{8kFEnY=6Fx2PQh5$A4nnrhmK>JpY1mg7|^(|9HM64)m!1 zNA4;0Dd7K+`woj!|Bu{%NDKA<$bAMTssBfgm%KaV|B;jAeOLH@KKi;owFFxk$)RrM{X}Z4g5cHwB*;p|8q0^ zKXRKesUIu;pPS+Tk>MX9|BnnG4*s99_dF20*HJ?uWKV$Ln;QzT9 z`F~`Lhx|V`!~Y{Ap9TIOIYFL3!v7=Vc{Th$a$n+`gZ8wWZ5&u!Sx$DXBSR14hRTvo}Txtagg|WwS%AaK9Sre_fD1*?+FfdhBbZ8 z81>}3R+wbmG$h!0c19rwgi1a5JC@D1VraeKh<|HxTE!Rr5!TL&~#|BsyByt(>+ zWcYya|H$bIB(Z z|Ib+F3;v&*;s0@a;6Eb&kBoZJ@c+oje}n%=j*AXg|BsCG75<-_;s2502g3g&xAyb@ zP|w=^JldbJeeQOD#`e0~{e40BsP1;0?{4;Q_vioc{lpJ;FYoWq`TKwVd3dcozP_G+ zJ!1F~|J(Tf>w^#M?vHxRKJ1ro=$}XUU-!>{fBpEs`h|Y|{nz(^N?!T%$dt6If@|3`kfT1EB$$TezJRsWA%Q~W*T|B)Lss;&8dWN;e zFvI%CCMG+xXG}K^j`yhl$MrXo>jnNFIaEH6;s24bz3~6Y&6+e&|Bu|HVO`DtBjb3% z|09>LSX%u*a>deRH2;rWzGNxq&O5JJ|FRDhSO1U41MTqt$d#piPD&wHyuX@-W zEq0Ike`NZ9WSr0N{}x2G^~wJu!>>dB9~pif{6BKTdkXwNay{|);Qx`4?+5>n>jT68 zbGO6)b2I!u_Q&-I|Bw3%hW|&#_I=#`Ss(sR>i=>+k(UVnkIeeN3?_Hi=H&b@&B#%IO|`l&Lisoaed8d)>i+I`x7d^ zf8hU-!|K*l|BwBfSFft|f7xD3@;6ccmt3)If&WLo_u;DQ|B*}8uH&?*IL!LP=e=HT zs4?pEK2>^%G2XYRRAR7kTu7k$f83q~@zv7q9cbZj^HR?HaZhG>_4XW35BsKR3hwBiEGoGm!sBh7TzJHpX~yO+$Sc{vZ2?%I_8U zf8;RvJ+ps$kTLu~_H@0T{D!2cts%JT64$ezKm>i>~rb% z1^IvE*da0M|B=&%N2~wmX83<()Q3Iy>4{v)^jF`no%mt!|H$wY;s3cA{vR3RBma-w zO5PVeH|S8V+#^uG55C`D@dtev{vX>D3)W4Wn6eyhG6_?g=|#_{4OF3I0z3?CByAD54l`poeE$f0t-1O6YmsniRR z`+K&0ldd7S|7TpMtN6Y*HyhWL`Uvpg zQ~!?~BK0TW|B+kuiB|uQoG$M(!~Y|P%Kg0A^HuSRj(;N7xs~~WG4lT4 z|M7UFOa37IKXNO{+k^i{Zu?}S`hVm$V-wW>cCvAjTrcqd zuKoRELH%Q4_i=>4aPdpw|B(|%WUBv1zCWbA`hRek)c-5zINihh z=89vYK3|_P{hb>3^){Zqbg6UmbPwYbck}<)AJ2c_|B;dZ0RNASdav;R$auabeugog zry>83?I*-Pljn!I@{HSjKY6~GTjgIj^!fIoTVLV%qw#U^*`z+1@iFlM;s0@Y_Vt@VF7{?;4csQ>3?_U@c+nr#dn4ON8Tp+l<@z^J0x!f{vR26lJNiB4F8YwiF`izf8^b= zJ@Eg?@cG2gF~}xaB z|Ks*;Jc#D@nad>%ZpgC-7g4KR9zv{XdSsO7dcm|3_Xg?ecHqk4}Fq+keLR z19^T7|Bvej!~Y|%minIX|HvPT4+#H{48I5dA9=I1!~Y}aOWxYX>_Fqa;%mYGWBY;K zJJtUquavw%8Gk3a*T@3@kDq7Wwzxm(s6(sYKSPFNycqUR&dJC55ySnTCB7p3Kk`EH zm6Ds6iskWLE`E;qG{!5$cN4$F`2AC7CGTvk@d}yG^`9WA9=RqBTD^h>px58N9tP}&zAX-<7>P|@&Khiw(&ag zVdeb*<4tnCNPTS|hX2R)t&{vT_TkBs?%|3_YW?4@)+OCBWrzd}By{-2xW_*(nYy@%BQWBdDZzQO+^FWOs>|Ht*c zvo%NkKXU)&E7kuaJAuLK|8aSzep&VZ$WJVs>@<4ybR2)r%v`lne5Z59>ksUc`lgqR zm+d*O{vVfLDfy7{Z`;1b`wRR(j<@{C$Ljx)Ka%4Q|BsBkIrx8Md>+F8i?0u4(q1=AGua=ZT0`iPS+0V|B<`o?NI-ZjC$ISw6Ede ze5^fnQT&=(##_aweRq8wWB82l|G516a|Qk%`6Ky!fd5C{aM%AMZS? zj|AHInTFRR52B zT7J*N|0AOwF!KN0JZafv+g`k1Rb$6%J`Del{g2-D|J)4!kBs-R;Qx`2%kRUguT3|G z4>*3|3?II*`Ar{=IQEtg&${upG4ciB|8e{ym#?Y+M?NO!JN!TLLAie5|B(+%{vZ55 zHzWU#=OcVU_+U^?a2RYv*$hIy(dmOYc4D_-hJ%26E7JIJjzMk{bnW^5us@0tpm6jMwIVR_k>8m{#v+k(xSE6)DXLs5f&x~5%s^8}{ zE$YmFY^`xXuSoU(*bd(a{vYqRA)gKYAGwX(KZE~A?jZgc{6BK15sB*mk-JD99sECX z-zVCt|L11-f8<_cTB-j>?l!Wey9}fSI+uK>{)x!THXAcT@X7tN7&XW7h zLto7^&h8iFq^!<2ZX@si!vEv?klzOXkDS>(MEyT9^4{S8k<;Ycch+I%J&Q zxw&&s$HT@M9hy0xK6S)6y%ybPNtq3t8T*bIr?i!Pg0GGnr)M=&|BvfSYb!q2 z#FMr^DQ(2(6913$f&4Z2f8-V&0@eQ`x9k|C{vWx8_*n4&$mx=g2mg=Ux|iHf75|T% z**jAGKQjEa()kyy9sK#tOU8Zrg*m&6eQMlqK!h{D$ra;Xk{9q~o2$lsNCG;U*QoFwT~GxkaPCG|uc5?OgBi zm2sT-dOKeD+J{?>z2o8i*|c5-{vYqJg5}>HGW-{|Bsy6FG~GC za_fGv>i>~({~G=uIi*vevue>ld|0vyjicrKga60=F;edr{vSD@bD;Wv`{vX*Zd2{gp$no;L6ZL<|@Ri{IJ@-*-_5Z-||Gpld zq5dE8+2H??TQq5+{vSEAX*1_ygyaWyYo)$lO!ET&kBqz+_i=^8z^MOA#_>h|pPS+TkUyT5;)Ap8h-yT4!T@4NZ?fbfgm%fl~rv;Xq`{vM8xyT3pC=NtMj z?_dAdpa0wXaeUqD_g^0M7TxXe3*7AQ`xO_z$lYGnFCWmK{qqC=8^hOgj}KqU&E*h) z=Hx%e|B6W78UKy{gW>;G9@^T+|06%}zyr>kW#?MEQ>K)&X4)JdK2o}nng3U3bEf)& zWgo7r{vWygBURP^BR^ETruu*6@(l{||H#z>>#P4qhF^pFzvR%y4b=Z5S8rTP{XcSz zCI$W<8SPQ6#TWd%jrxCRfAEL5ZMn3vHE{pzD__B_5a8< z8#h${kBq#u%DdjQ^*tKc&{-N)$Tfl+J3(7#SbK2uChGqk2+C4lFfgEzld)mCwKr|r z)VbK)mj|txX6;Sn`v&=cTt688A33O5WA*>Y&6_q<|BqZ%d?n=nkt^1#t^S{J^+(kI zBi~=HjQW3M)TixPWr{5iUk&~r+i^ZkDDTU~W=yvBV#SK7|HtEn^ZSdvuh{&jMn`kL_h-eE5Il(&7ig|6_mX!SMfV|L!ZI{vVnC9~s*-B5R`cuT=a#r+DTw#t)S$ zrul!I-zp{VSO1S(O?2hH?LAn{XcGh=p!}N|06f9Q&;^z_ODmHhWdYOZ&a z|BsCN+Q|PSV|n<0WPF~$|07qaRYUzha%inb)&C<0*QlocAGas2S}pbe*xs^U69@hu z8Towh|JXmGek1k&PIL}c|F22o0QLXKO`9}R|8H!kF!lfH%kRI6W0Ld8b?^Fr?B7Uy zWB7mM`r;$UZ;vnJx{aLg&wGvQ)oG~y--6L0>IZ`1|G9a(H@1))1*!k{+n8YW0qOsV zgQxyqU8zTm{6BJ?kSNXnBR33*R{zh<@c+p0`{4h%8U7zRGPuD1BjfkD{M*`_1cf+1 ze-vokRNjZFd8WBB`nUeMnQ?Te@AonOK7s#trS|vg|AFEE8OH=Wt$)9r8&>zb0v|6U z$r*F}mT_yT_xr%CTh_n#V=dMH!2cr$J?2sWkDUBitk(Y}r${{nCL4Q%87Ee`A33;N6ZQYdHG4Kx z|Bqa&S0nZRxIJ}yG*ti3&B*^FH|y0@{XZ@r*hk*C81$aC2lj66%uHBd9NafZ{Xh1P z>QztuKXQ2Y+Rnueb8UN@b#0*jAJ5n3-5NT-zy7YBzg4?6R{xLfVEBLJ@;&OP|Htd4 zLeIMD|B>r-YvkeS*~gBL{YAr2Zc{u5W?=N6r`(t^OZ5e3ZwDsW;x% z7d2uh%pE)c+$-UA#p7Kk~_& zx3vB*`TX^p&Z8GQ=SoJ6`g&)tT*vb}W6kRm|BwBTfAyXC6WPWWzWNr=2dzIC{vXFX zDt;gQzj+I}Li39~t?B z2bx7&JN5_uALkFg-J-N`+n;^1ef_J18pH2va68C&ujF6A|9flRXX*zYy!DOxf8@iT zf2;L>$!9e|Bvg(^6>x2SRVc#8NMC-Kh8fG{vUbIZ5dzk|HykkzazfI z!^Zit{;VlgjN$)@&t!b)_8s;AxIVDt_gFi&Px5_?kAC?*{3m0KkNiKbAATbIKQiVI z{vY{(_=@oV$opmck^e_NAlpA;@4s`%yJbFp?fItzsWd1;s245PYM6e&G7%osP_#2kBq!T_c8t2RNarl3nzy0$375*O?&$r?Kk@5T-{vR2B zYQ@eojkn451OJchTV;Fei2p}MJ}CS@H^cuUZHtXi8|3_Z1 zX}kJ=JRUnFFAn}6d8Onz!T)3b<&qx-|Bt*x>NO(&kGxcTGWdVwjnXb|k?{uc%i#a9 zeZi@7>i=1#^Z)qym6(_)_tPBtjw$%QxhFXT^ASVty<`>6591ehiXYeF zObn0r+sEMVm5L=J&kX*bo8kYFm&oye|3_XX^9lct4F3}TAJ-3t|Ht+f;`6}&Bd-+S z2mT-Xue$61kyqaJ|HvCoUsV6k&G7#?U+bk_FZ@692FV|T|3_XWeir;c@qxe_w|J)4!kDPb6~+>a}MO3 z4Jat;IEtc(h&twkq9P(HsHmVK3X*fECg+@kC}6@gj`3D!9G`vd=GuL#=3e)#|GVcM z-*rx%I+ePcs!#3TF7l) z$6g>mpW*-5Ymc5)|Hoc)_yK$rv8sz z5$>=4kL~oxQ2)oib;Dcg|JW~yZ-oEj?R!_|)4~6-aeu-8xf}kEmxss0{6BXeDo?fj z7t8UUyCvOv$;pq^|8al#bof6zzU&YG$6h5qukPWziVH{1UYgf;)_GuIfi>34h5zIJ zX!t)i{U00tPkz7I`C|Uwuaz~nKm4Bj{cOEK&KLgAE-&-;F#nIeQ5yb_T_^j0kkZfE zBiqMZKEN9D{8A$HqKA_&@fx4=?EaKi)r>--r2s zY|P_>|6{}R!T+)G_YC|W8=epTkG)U+o`U~l)m#v!|_b{6Btw#v0!bo7G{8^|FN+@{2zO#{QnjHkG)m?p2Yk=HasBwAA9?WGwT1?`!3D@bNAuDzT(irU=r=0(wg72RN$2E6uY`)04=g>l@CT+2G-^)wY|8ak8 zhyP>O4$oEp$L@NWet*}tV?LO?zvtEPf82jS-)QxJ?A|@XoIZ z*Vmz-h4cFlo4xvI&{pe?g)Ni^iKRYB_i z*o9@Coc$g5+VOJ=+B);{_gQz%Y2!S4#eVC`^ycdScza^AS~_=sb-?bA_?*_x5Whp# zQTZ*M%Si3X4(RId%v^WeI-*~=GvT8X)+N1y z)c^5(N_z*Z|6}))hW}&t?h&B=kDb*!Q2ie}Z$PN}Ki)qT17p?yv1^7VI`Dt&;$f-k z|JWtN)71a5D`Y+%{2#kgd?x%KyIA}u{GYq!-_{x8Vd4L{JyU!m{2$++ExIPpNqF^J zuNE6Z-S_4m>i^hR$$Z4EPyO32kNFR; zFaFaS^F!BZaV6hxy59}{`{-LXFaSkSRYWbKj@q4vDWZrc{R6L)BoN1ZEy92od3s$w}JoT@vjzdHK2C9^$3}l_EPPg z)|~&x%fm;(|FPlaF#pfp@PF=x|6{|;!T+(b9vS=}8|#(9|FLoV;Q!d=@_8iu9~<*w z;Qu~e*Gv5${Mx^h?ze_FOH6pc8uRlo|F7rdp6Ua8z;B5EOTD9q`af*P{6BZY|FL_@ zyg>LrHoPAE9~<5c{*T8Wl2fSu&)x8UZ1_OynXPa@PBOhP53`H z{3iS#8;>9SAMYf-c_YS5oNh0e#Q! zzqRk}_w|LojrFnJ=j+?PUefpa@qBb&-nV`Iqi_2j&-eT@^Sym#cA@w6{Wq@%ALKqi z-}ar)=X<>Ww!KYLZx86(zQ;pPxc2$FtM`|APVfJpO7xo-r+W3?#n06(J6h^VpY%(m z)3TZKQc*)UYSr9<|NGbIUg`&%wrQ>N|DJibxB9#Rm{nh_*do$stSpS#Zyt(|nF8+@V&j-|DBYfcF7az3_me=3x8@(I;?=OWt%?HB&u`%Bd z{*R5dc*ubHoPC^|FJtZZ>Ii_9VGV` z{2v=05bOW){={~y|I1Dc4OIWfPU;+>{*Rpy+)4c(J3P3f`agDuHq9K&|6@1n*i!x9 z^5A~zQv+i{)cht+nlm z@hQ%a3u?Uj+FjMwaWRSN|DHUMt=$F8FXsQ<7m%qwkn8`tTV@H`{+$2E?P&NvcV8UZ#r99nE^@>o zS|`f?N1D8tW1S#>-*sFe>jPgpUv$(lSs(aPC+B6I2@P7~9@s;{N%oBwFV^i^i)H`TBI%g!ECq4WRPdGdW! z%>QF|ll3~W{x7?$%+tDd=wZ*?m@m}xVSU{v(+^qqlJ#EU|G57^@i*{)+`qs0I`}_! zAMt?Kez?c;%@v=k??XSiVz)JX(N`bu^yEzYOg$gE!`dCz{cbIH3Z`$j?knGSh5xht z#}=#qWA_pNC*NQ7$afso^Yy!3=Ftt^WZhflmt|*dw8s4h|Hu7{ugy^Z$4(xWr2dbc za>@U(bL9Jl@PF=x|Fa&Et^SXlKT7`pEdGyOe62iQ;{VuqzXbk|-TRs@>i^h%N9U{m zWA~HyKj8m(`+Lj#ADI8g#`i0+{;#_+|BpRL*294RW8?dY@PB-~GOx^1|Hn=qnxg)X z9Xlvq{U1AiNTSaFV`t0vDdGRvX@gSL|FJ^{*ZV(rWBp&APx#ca`sQ!=L zxPQE^|I62h(?3T2pY^~v^?&R}a((cBcKHEuj$hRCc6lVv-^X|)(P_S3-kYYJ}L73W%xffo^SAf z?16tNR{zH?y`@O~9~<*C;s4mVGEa1Ai$|?<onVVL?q_T*W!)&H>%%I85cPs=Wk&r{(4PPaOv{tut$!2hxF`Hjr?us$fC zFNx2vJ}mRz@uHGG=P z53~LEh^NE+zwoTH>H*QEU!{3q$lx>ad7QH{#jD}}xP7;Lo(KQO#^vGv+ztQ7^TYn| ze{A?X_&+xMAp9R29uWS|-SB^Gc)ybg{$36L$L-rb{RW@!+wI@+`QP#Rzjd8lzsv{n zYViZs8|Cp5Utqmit`Gi?$H)1@|G69fkB$2q{?Fa;f4qNi`{4iF4gbf+<>CL_joDP} zUE=j%SJ=DdeDQBK{hzzx|JbYK^IP~o_Gwa8)+4pv_t{1D zf4qIWFVy=#_Ii1J!vDD&{*S#$=3&DBvEc{d|JXa_`r-fB_dSC-zf1a}+tN&~0bL#*2df)i* z1@(XImG$$2Hn1Of>wWkG>zZkAsQ=^foWid7`C!)K!w&%Z&|1QkLUM(-3Il4 zeEilQg13vb$8(iWn(@d{2zO{e7+3-$6hM)0pb7HI3DKz z@%k6ZyfyegHs}Ab7s~uR_&@eyY4|@LZ;{M{ga2c%*j4ZUxc@3y4_LgOZC@ty*yMcH z+5YwO1=n%^bxW41|KrcM{$0Dv`+1K14!QLEC%+etSIVw>U>cqu)^{%3p#G1K&(s5_ z)c>*HtDmP;#(wwE3H*MsUMLO!$L)({fA~K(=J~<@@%nN9WBp$?wqyNYcfHpaD zf9!?g=UP-WE$98QNW2sLAA5=TJNQ2~ydeA^dxfkA4gbepzW)R~rZs$;cyw#{w1Zu% z%X$4*Enb89me%98?Z@M5{rbLB_b6-2>-`^UHqy1e6an|@P9mitZ%(^$jov+URd8ceZ?$m%(I05<90mX zho5_=oUeEEq4M{w-xDv`_tk~gZ_E6^oxd)%o-6AOcOAaUdj9Tx>i>BBS?lZM=fg(3 zzVUC)l6k}1tXsiR+rMK-*v&&<>-ADhK;p(&M|9Jnd7Jugq z%eC!j_&=WC8o7Vr|JazvV}|JWNY`9C)13(oC# znH_(-%zwN7-Ycy4i0?bqeniD9pPp1NhYl&d+8X}vvcHV7#`?1_J%6n=zOQg}{dHdL zfAI!uc(cL&f3-ev$^Y^GfuDo_b9aXq$9nBQVB_u9`2Wh3ukWzN|EKl^O|ZuQe=z@# zx97u)->Uy(pOou^|6^nRIs6}czx@9Q{*Qf3t}ov2VXxj2`-n9>Bm5utN5lWI;q~DE z*zkt%e{6hz3jU9c?@z)1xf}kEjs4;O*z|vF`ad@QKL-ED#{W0V5}&g^EPtw_PkSO3Sy2MzznK6LJabLF(@w*Nj^5BRrtU$ovM^RwaqxIg_Ld-sV`I{(kz z@PF(*Cr_*YV`CoRs+8C4_&de353ihMyTsIKaJ({6nX#4x@llj^?!UnEw?sT{U5ucPlEbCc5(M; z^?&Tb+9+pc!E!rZeszS-|Ks-D+647~?DX;|o&U#9DhyEn$BxKot^RLa<4@Hq`e(LN z|Hp2h+FJb|yJbp8^?!{@KT-eJCOts?AG=Xbu=+pl-#9l!{U19z$6x&)J1V=A`agEN ztYGzj?uP$kch2dg{*N7+>+d`@a=UF$%nw%o$J>X-{6BV9QLxi__b%H%yEw%8@!Q?j zMWqqy|9JegOj&PA{2x0ZL)N1b|L1PZ|6@mHw^#qi`y)EHqxwHK&KLgA-SB_x;DTWF zf9{6=W4A00R{zItUD{dwA3M1s!Wq!$lpz$Bu?Mv(y>7>1U&N``kl+%3OdFz5+3C{VCE?8F#%5daZ*4>6?IWHxCW?eft z!@0fp=hoc^rm6qqkacG;s4l}2MPbj?tgW*`akyY z8;YD|ZNIneL*(;}XLEnB9&}?D^?%%dsC?fU{?Fa;f9xx+&v$;>^^5hDHx#J<Rz2QO>Vh z8@g*roV*{~%(hn)czd0yB5$wb>uLU@QF!o*Cxbnb2t1S zyCge9=l`+cq2T}6@M7?P?uP$kV}2U^AGH!C2W$XMucHi`R|HsDsH~2sHz%H^LoA^H- z?=qR!g86^!;kiXR|Buc2e{A?c%>QE-caiyr;{PglbW`70QBk3G0VK7SPd$L?QH z;yk|Oal1U`NnVllgf-^r-FWXL+aKHi`D;VNPs0E4c)0)J|J)7#$HwD1B=#vgK73fx zn+=WmZSa4*J@9()e{5`r|KsuC_u&87*dP9njs4;O+>P~r-R*uobuaeud_Fy(z}w^b z`afT<25;#;zVG}xU$5rt<$PcNgJu0s_wfdF@%DnnImuqzedibYdO6?qihaGIZ{zvz zzW)E#@SyJfeQ)1?%qJ}M_KH1y+V}kN^T~aD-+6z1<>!-odr`jk{a04(?KK_oM(+I` znLp-kU%%(u4hDp|=JowY|Ci(cZ@$lcJX~Mj)6ds^(4ttqAG&Dv)Vjw0Me6&|jZ+#L z$AkalcFYTe|8w`KjZ+$0JYZ^1@2>u2X5DjjJ=Dv!5U&LP_w&r|>I0jL2Yc_2m#yKS zu>LQ%`!#Ol)c*dGb!VBU2>-|J5v^LP|6^nR8T=m`^U<*WFFVYyrTRa2!~d~k+O$;v z=WfjZV~4kE<@|PYL*sb=+BnT_Uu@e}>i>9q}Xl<6#kDL78a)d&(0@2T>YQBG5?SIM?^$8y-q%3=N}){*?DPrL&HnK|8f7|xO)G` z?idlE{*Ub!9H9P>?KE$q{*R645Bwh+&mZ_dHayFB)22ne|Ks`7|FLm-_&+v0 zAm;zEu|MYjvEc*Z|2`ejO+6}nAp9S@gPbqs|Mf2Ds@|`i%-@6mW5fHcKJ-vs(XTc7 z_mIE%z3T@zH2mI-w;rMRo|CjAAuP^vN zc7WVJnE%JdcKAPbV9VytTfP5goh$yfyvM!PeG}rHlePC)2c$%)|KsD)GQwZ|A3Hv% z-v6<&UNHP08}mOudUb+z$EXPPf80+0$A(XZ|6}Jw%lt_3e>{KmM=`fq$3=#y|KoPQ zmW|c_v0KaQ8UBwQD1H(1|JX@Eoz?%b(?aY0pS!XCFFPwT#)1E1$3)3|LRtTp9TgF) z{*T=zJW~B1yOX>h8}i%ehW(RL)c^gxBvbuglr;PwyHi@K^V6hmbu+WFJaun;RoOl{ z$%%Wbt2M44{*U`dN5(nuf9^i`S(P>RuWa1VN#d2^|7yEu)ce5j2&pjqb7WuZ{Oilr|H({1^?}v5_i|dTJa5~}?yOP&$Kw}|t5pBT?sI#k z`agGH9QdK{u>TD)oQt-gnhHi<%y^{YT!_OZ^|WUp=9x zQ`%&o=Lyew^?m~RJUjS5cAsl?eF;yy z!gK2RddT|)GdFLw&L5G4^(m|iu1Z$_$Nf_-OHlvEP8=Gm{*Rq9I7a;+J9$vF`agEc zpak`Q?6e_CI{%LyCGU5@|G69fj~yfHM_~P5cfBoE#`l5Y|Jbn=ZPov=6KguC|KsDAU+b^_kDXW3 zN&O!?OTPb#`G4%}ZUO55*jYWJ)c?5~>;Jm@fn{%7XZDEH`F}j0%)W8z|JdohV|4vr zc9eKJ_&**mW^jV8|I5bq8+OmK?GfVfo_Xsv>-Yin{*U{|^^ey1f9%jfDeC|D{0==1J8vc(R*H6B$@&2>ci31bV|M7T<0}|E$v6I9L!vC>T#aDj+_*2%&1LK|GkxyC| z$?FCFkLO=FBu4!oJMro)^?&T-Q90`W*r~Ff4E!HE?b<9^|KefmtdTiRqm>U?XUgk) zQ0Rl!J+4Vr|HsP@8(XCQkDYyImHI#4p1ixes{dp6o;XnbA3LZvT>W20>4|#(m)u0> z|FNsa_EP`HeqzQ9^?&RmpM3@|;9+CESNOkC^Ny?kgO7v%W7Ge!;s50GKaYIoZS(x# z|JazP0sqHdBcETv|FJiSZo>F2e_3crExp?!QNT82lfvf3Ns4 z_&+v2KZE~sH~b$P>;J<4v3JPlhwy*A{cB}=pMCkZ9qZ}B|8alJtAqbz!^_FMDr?NI zn;4nt!HhU~KlB~_)9m=W=H(<$wD!(HggJ!>V}eed6~XdOX(pfOtRnKb|id z{*S#+?l1U1cf@(pU;LGA-y~je*S<+!J@A%C8(Mtf9~t*=;Op5V^ZlBQztb9?K<4pm;Ln4N z;t6EFkM#oa2Qn|n_8<4=JL>;!{?Fa;e{9V2 zga708!!N=AvELIvh4p{k4gbe}OZ*Vl|7Fh=Pl)w@+3)PytMmWZZ_E4{_&;9%8{(tj z|J*Hp&wBR8EqJ}J^>VIFv_Zx`qrR+X;PQ>%Wdfc3M)&Ft(n}?2L z|1$P0SziUM_wK{*S##E)W05^GCz~vELW(1OLaKFFpzWkG=5H z{6F>*@jdeR+4iN!Ppkjq{fF~`|6?yWa$5Z#`@Mtp^Z(fM!~??rvFFSBpzwce&%P7* zeN@itU%F`ze!rFT_T9O5D}1ZxYnNXl&qsNFSkKr~@Bg^}EBlU!@0xDMgWrSyp0EF)fip6s-)7*ekOkH>p={ap2b?D-qEs{doJmic~SpX~C>#Vf-9ar;{N zc>w>%#(c{&Pkdg^pMUR)U%UL=SJrsG9V`CMtKt86`8x4}@PBOhP0aseyB$Fs_;P%428M|MBth$abv%>u&fz_G&pE{GYqw|Ey1(R{zIdEI%*d|Jbi= z-KzeN-MO~b`D90kosW|pq5hBOfAj1q>i^iUul1<^pIyV{*SkRmCVz_`oFyVYVmULe{7HVdH6pzJRtlZyG||-|HsDs z;BRm3YmMy-Ug>X*?PGQfw1($P`Dw5<=J{QW9%c={2mi<8V}9Q&pI%-OKIN!-zeD2F z;Q!bMW&R)h9~ODlUYubK4|w;#XIk%+4i0$Ldiy2+$K%5{!~e0j z$=`2DTV_>^+I^(n_lfu0apHBahX3RC)!TMBW1oMsVp`#m4R7E6Y-QI$L!5r^%(l*L z(bVbl)dv-Pza&-u_JaT8`$vu1H^Td4)-3{C;Qce}rk$GL{WY(y>#)q)323bTkHG#M=>t>-%)&KGRyEdVX)&H^EM>fa$Ari^J~|Hp0|*GByx_eW#>Uv^k>OZ9*3;P|HM|JcoAo2vg~w~TM@!2hwM zVw%zbrw zWoU7zbNb)MtiwygofXk1tP{#QtN-KW6U#%LwD{9@{Pc=or&*6P*2yLQ>i>BDnZ=#d z|FJWQI;#I;cg%06{*N6X+u{G%>4hEC|FN@61JwVqiwZlb|6>>AcToSwt|)A;{*R9r z8vc)6RoYJdAG=28BVzs^Uk~M#9o7H28~%^oy(&=sAA3+AnU7QQ4?BK|eBb%RsPDZR z^Z&Sid7n`Af9#T;!8-qsUE4cU{U5tW|43*5cmHFTFYKS7{*T*B1|_TivzF_J|6>>S zj#mH2u9b%WV|SJBYkzt8-_||*COBJu{nL7=d|uH1Ij55QS6-Iuyg02DQ5b2t1S8}r!U|M>YhjtBqe zZumd$kNIzy|HqEWNmc*Hj_Z={!2hw!aYOoduqkql}$gWQqKpEmb>I0>pby!r^O3$d%n!iga2b=fA~K(j)(bwYaQvKgx@o1R;$L=qWU+IpAY=1nS?Yli}4Zj5c$Kzd=S3m!cJxs0-^Z(emJm&wg zduL^-|6^y%e8E;lkJj8b+_xAYuKVN@2NS=@G>+_wz=zBc)C-?sUul=9i&wIVz|JURFZ~Mdl{ZWhRYfn-`^>3{c_#zq1E;C17$tc zE1!DFtKt8yex^pfAl6rg|6{jl(Omr>yIqTx>i^iC+O$>w$L`RowfaAI!~eM(^Z(c# zTeorG|JY%2JorC%cmGo6Ctf-~Y@dFkcc1@E<|$s<9@w^%`oG`j*Q$pMZWo~bkL~a8 zul|o66cnWX&sx@3#r!`WFF2&$|FJuF?yU3wxPNG9sQN!{j|mM^|L1P_KkkqDYuQ7d zw&SDkKQ!68b&#L4dq6`wtsEzK|5LWTWs|1r|9HGsGLLe}?k8;HCuOB|I&yGnA zEzg&k-5R>JJip-oxIgFrvD>t4s{W5n|HtPOwqyO@%={|#e#woSs{dmrI*rx;v9Ufd z{NJm8RH*-h2ZaA)V|`xuKkko)|6{jk(n$Ru8y*nr|MGm$@P9mC_(#nDV~5MUKlnd) z!~d~Eo3&8?#|~@WQvDx0xr3kjKX!RStolE8a%!CVKR!OO@e%6(*zkAr-kE66hp5m1 z^?%&nE+k0(AG>p0jQT$|=2K$+A3HrEQT-pgDlSg_AJ3;cK3@GF8}s_^jvQ;Z7xM?P z{x7%F|FMH*o+11n8_$2N|I3Dd#r!`u=l`+OBV~T3_&;{MoDcjTJ25d){U6&uF;4v- zJ21K4|FJQ@5A*-#FGyAYmy(pO{*RrImZARdve(ko|3!!&g#Tj)ghx3;Jhj%C*Z1hD z8tdp7S>N)fYU{`-S&vfuACC`jxiGTQIyNlai7c(K4u}kQp1rKx8tbvA-Ct7I`?F;A zfE{AuoZnw9whoi^isAoW{W(c}V3hp52mi;8%qei-|J)7#$Bvfor@;TQ6LX53gG2M| z_-I+{xbBbjDe4vDvkIL1@9N^!Y14D9)3Ut(-pcAC^VePfAL>%<-Pr~8{!eD~sRzs} zmi3jz|FQcHs#X8T#`>z~KfYkwFO&6u;s3b3`}hjyjy)fHX3qIYJs(>BZ9QmQm9z1l zv(^K}@4^3Z|GszB`#*QX|DC;Xwtl@`nQsUG$L=rl__mAxWB0qOO8p}>h}KIZ?ib7g)T=KryAJgooA&X##>b2hH`YOMe3-VXoA&XRd<@PF*k z{&DL6*qyqE>HI%-o30V+|JZHi`<$5n$4;mTQ~$?~uMSoJ$4;*9tp1PpZ+v;6`agDP zX^{FqcfW&)`YA7b2rxibvOJUJ5#mFFRGc)lgWGS&aFb7a2dGoL?Z`(wT9Wu8Z^yIh^4{*U{k;s4m#qjJ^% zxf}kEjrF53|Bu~O=7D1VAG>CJrTRafZ_j(WssCdSzH7MpKem5iuyflrx7+zS5sjUW zuU+erH5S$H^}4CQGjz-->j$S#Q~xLCLA~Ii&p*X_nzsG8_#pT{ULNxs;Q!d$2LH$NLBs#C_niMy{U3Xue7+|0Q|$8aQL?_8HGGuJ1GCF}F8M!R9`owp|Jd|@ zZ2CVoyx+oyGCaJ0F>en3j}1Qu|L1P_KQ{au{GYqw|JVn=6mKW~kG)^k7fW9eVdn?` zciUrOUM=%;tl|HDjt%x|`TX6h;s1Dhus{4C8@>|pGkGK7j|6^~v1FNpPj z-QDWntL*k-{bX6+(yL|t%Z8Tcx2%t8y+e*K>t|Zy`r-e0f9{aiBm5s5pU1-gvGI8= z{2v?M&ogzZSC3ot^aj2@H_84#51M3+`GEKS^hiUW|5W`S_ox43Zx-(d|Hs$=7MW)V z|Hoc>`eXHf-2b+hUsM0bZh7A=>i^izm=Ws#*kd1lQ09RZ+WD;5xn2DqZ{NZl``~fy z{zr?iwVo$_NM0{?``_KM7kAA7d=J@`L&!~d}tiuV(5X8nPz{|o=e>xU1N zf3I^l{2zO%r{4eZ_KdyvLHYlO1JkF!Z=AtHaDSAt1Me6QpJ#pRYqQn=aXY*d{2zO% ztd9%-$6g6fC-eWT#TUW_$T;3p6`6|KJb6+4`e-3_&+whp8VT-zMPNz zJg{CY{tEt&`(vJ%Jig_;KD3;_HGG!%&~ono!6B?i9BIA$lK{S29e(vo>a{hzu@(<4a0Kd=ee4bxjC(pO*tm{^{Pk^{1UGy zYe8DC6we6%$IHVP!~b#r1u`!b{*S#_=2yc1vEg6g|9JV0;#J}Q+ztQ7#`?7Ie{8JJ z3;$<*&AN(JCy?~Mdl~M|G69fkG)B@!~eM({*S#`=HtQtvA2kyga2c1 z7w-rE=Wh5v-hTK%_&;vnBz_S7kB#52@PBOleue*Q=z9O>ZumbojtBqeZumd8t_Ljs zkG)yEAN(I1-Vgqdy+_u+h5viK@SyrX%%_9@W5fHw|FJp$kG)U+UWflf&XLE|FJR85B`sh`GD|$Z1_0%KQ`v^!T+%jUHDr4AN%kp-{|~5_Hp_D2>c)W z*oCju|FQSV-+%CbYJqC228fb^-sS3X|GPb=Naq$G7oz9v(H+?^TGe|`0#%4 ze{6U__&+wb!~e0dJ}~?r8{QB8&)t~+$Hx3W_&@e8c|F7bvElvT|J)7#$Hu%r_&;}J z{vVtEkG)g=UW5PR{k47HKJ|a@o^t;i6&)|`SMTT9QSblQ!$yu&|HlpsZRwm3UR1&N z3uOF<^WD5f6?{Ly=_sEs6)vve`zOsqT0193F0pRm-&*}2-yg$zM(}^u{>{|?xf}kE z-8is~`agEFkap_-`2Jnn2tW0IY`@5M>i^iGaqZOqx!d`5ZN=xGoL2uAozzMFpO`ZB ze`xqWcDuBC|Hu8&^8RN9j~A8F8t;!Y@83)|K<7Pd@=uz-7&qb`agDH zb_ex;Y|j7V{SlSZLH!>aJ`nzo9g`cN>;JOD^8(fXu_N+>9QeOmu0N&z5Ay-x|Jd+? z@PF)>qCoY3ygXX|ZP%At5~BW(+tXxz;A?4T?e?X}e8Ia0eB{+)^Q>|GX)^zhw>P9P zMExH-qaZ;2A3L)!Q2ie}BTweL$oxNcT5hoVKXzeWfcif^9>oPg>i^hzMIq|{*j?oP zHTXY1-?K_OJ7f2LV~;nw=l9=QCl`b|u|eNirxb>%|Kssei^A3av9W#0V?TK9|MYu5 zT4Vnk_Wxv^RTQEA&(230{*N725~lvo-I)K!#=J`SKX*Sm|DSez+<#Xe{Fil?k|_0m z+&@`-C;T6~Sl(}i|6|w6_q|JF8+kSSAAcTI^h#F$$1bRjcFy!|V%y70Bb}b-8oIbJ zRNjwmTFIYpxw-N3zs&~!m!I$L0paD`+c96x-B|zC-Gg#+osX`$sq)XW<>ud-kG$Es zdw!9VIbw`;fBC#`_~o})WBwfcA3q<5zk>f`!_&b3vEgNYTRqMi-sp{0cUW`&ANS|_ zzwA8mQJDY7?vkIa{*R6Id$Im6ySA`c{hzz@3+}e_$NIMC*G#M&?I~05huaJP$EN>d z!xO^)vEiBE|Jd|@Y$}4L+5WN}{*R6O6aJ4q zOne#U|G69fkIngiYD|L1P_KQ`vOWq#1mxc#Uf9{6=W5e^o|MB^bhW}&tDJxO` z#~#wPM*ScAs=j?4_&;{<5^s;^JCDz|eZ81(!#BELpTm6CxAUF~7zAhrV9Y5f9|v-?!o2+}nNIcYojZ-QTzW!w>q*6NCqZ|Lb?Jtl=c<{h~4d z@Ac=hz5JiM;s4n5f9{6=b2t2-yW#)XxIXwlcYFRirS8uAay|VDf7A21>Ae^0{PW7x zYhnM1Enliz+^<}HAUxvqNiSMs{@dc_4c(?q8)x6+(`|d(w)OsR`vVo~2hmvnm)*K` zYbU4`;1OLbU;rlYL_wK)4c+R#5 z1_nAiukr4{kEhu7_ML;(|M7TetpCdn4i0wybwxwNLt*|Ow?_ttsQ+^}{ND{TD%B%m zJNzHFhXvI8KX#{1oz(xaasR>pu`!?V`o7)`|Htiq;_=}B*ljNPKQ`tA!vC@9|E$Fi zW{!E>?r-?MK3_d%jrn+(|HtPG=I6ox@%fZ3{uJ~7*cme45A*-nag7=~SpSzD>on5! zf7w{?7ygg!C$Hz6Pad-CYa{-z|LBHpd&&RteBcY=|9E>k%kvlhkB#}2@PF=x|6>=5 zr^Ng}c6Gb<>i^i8VZrME*duX!U>WjF@osf9&+=F!g_I_&m)2 zV`rx&sQ+VUrKYL>bNBnn3j_Q>B`G0Jj z|I(kYwT36$c1!oVz*foX{jk0;=KrzdLZj9Hu`!Pi{*Ub^J`w(pjro4lo7C2A`7zmZ z>la^FqA#?sZrC0h?sQD6vc}_e{h%t_AM1gSySBo%W4-WyjW4VFOJtIIMa&xE`PPx?xlUAR zzU?28mg7vgEZ?pV+dmzj=hg1tm)QP)byAx5|8Jt>)18Gcf98=jcGc_Uq=Y!f#(ru& zxOcH5v!|@9udj6CA}(0>9Mj$D^V2!&3h{XGe>`5*_$u{(?2)%utN&wPHMZXWv3raE z8#Ly$N6cTn_nT0y^Z(dG@9gTFyXJ&v?WB|H?}p#i-Dy#B+`9K&UDf|_|JvKi)&H^k zh^M)C+hN_&;`Pc}Mks?uP%ft_f8C=Wh5vc1m@C&i`X4R&-SV z$4-^YWB#AJG5@cj!`1(}8~%@-RvV%I&)xrX=Th5F|7Z7iO{n@mc3gF&`agHW|FPq1 zqICWrJE1mO{U0CCM46ZN@@w<$`GB6>YQ8=Gxc(*Q-}7qtKVCkgGDQ8KyAyAoYy0E- zt$l0W@oM-#?w?oOUi}|Cx6sdl|6?bXv{nDdPAPA%{*R641N@)6;s4kvWgXQ2vGII( z|I90PK4|zqKHt+SI;sC-XVi4m`G4%p+D^LuFJHfDwL$9t*qPlstN&xCiwA}Ot%@lW5?c9<&-AeZJlsSt@=M+f2Y6JsQ+U-rGe`ItP`53 z|GVY0ed;l~jqR)ckNx52+_7K%-_b8VQ~$^9_&jK||K%Q8cqm8XoTKykzU`U;iLJE72PB^seg>Z@p7I+q*%r)(6D* zefe3G^}$R2kLPwKZumcU!~e1O%6et+e{7s@)<=GJdv|~L zi!*Lf8|$sIed$B3tT)U3^Yfq<)>|%qr~Z$}g9n8FWA75*2>-|4{nbCjqx^e=yW#)b zExyWn@0Z^@<=_9qdf!(+hh}?hhf9##|{Kx!1HhdoD|FPH0=dbX8>^eCf{2y=cMp;h| z{*S#u=GDOevA4_R;s4mX{8`V(d-|qrcs^Lab?_+snl;v6 zh5v&wg-6BwH26REyzP6`|FPfLuvzE-u|L?j4c^R-hlc;-^}ix5=d+IerW{Xv-8!D{ zd^vx)z1Cx&cuM|1;yB!%am_W@Udrxq@4dLZ^)s^myx1P=I=Owae;M~*E4~T-kG)Pj z9sC~~>;1z2v6sj^Klnd39zXa$oZm;{LauE4~f>&-OoXO#L5wsd!fSKlVylFB|@kuScw(4gcqE_&@eC z@qO@r?uP$kFWhrP{U3Y5u6qB+UbyG5`akwNn|G=IW8b)8jru>fGh~4JKX&1;A?p9w zQx`6f`DX{q`SWSEXS;Z(W7hDU@PFLCMCJj)|FKud&zF%I7p&ix*8}_?w`09(_&@ft zqbJn=u~*7Gy}>X1XxmqbXFKrC|5&dRPu8dVzpPiE_*nfP&mZ&s;Q!cl(wP6p-X#0W z?{Dj^C(q&cyY=?d7x4Sv`nY&F`TM~7h`c_&Y1_einY{ks|M>Xh^?c*a0k(b4mO3Y4 zW{`DK&#sPtSx5zMuTvA?9R6#l_00<&aHhT(ZasVL8d+~MvLgEY9`$5fK0M>(KNM}f zUi|p@`LWjPPJQGoJsxkpR(#&~jgq`NJ0rzH97g^y-fc~#q~ZT~d(iNI)^h#ue{8Im3;)O7D;^O3kG)5>!~gN|!v64o+>ZHs@PBN0Lij)S zcJX%be{6U?%>Q#Y{2zO(%=d%;V{a3m2mi<3ES~S|=)rb-(cx2uTJQYmb7#bw;a&~@ z$HxmE5dM!1F9`p~#&*pAV`Kf_vzxA|xF%tbdb9)L0VBR1ZH;+(@PFJNUhTE=8*MxK z%wKM@J|zDi2%9>_`mp?eV8ohRt?~bfS1;UV4Ic;p*Kqu=)c>)M$={2Z|HnQf$AkZ4 zpO)*x`oC<<>x2JuH~b&_xcq$u|L1P_KQ_(>{*R6S55fPjkIC(Y|6}8L@PBOhzc!sF zdEGwwJlYz*5B`t$H;xDY$37v~5C7+G_&+w*2ZsM+!}HxdXNonvU#nHmS!4Tqd!|~$ z`@#S5e6bz=kA33f`t^U=$7H@V{2zPo+4JiE*zkbxf9$=d&N!{Enqk+s>-b4$-t9BJ zy65AsSi=KeocXHt?t_P&Nef@I-h23{`aj;@ZHJGj|6|wf-RHpnJwIc&m;YnmFm|kS z^s$8%zpOp2-`^eBu#C1?-^Ds2s~y&Vu@24* zQUAx=7nBjK{*N7*)lvN)-`_>U|5?ktKdk@jZp{B<#f8ouf!v3@Z8 zA3G_lgZe*re>&l)ZO8qC^?$h?>mSctcigKde00J(KCh$tKklDcAnUb!a@x)Z>pyR5 z@u77}agh2yo_|b1XZ3&XhW}$n6?Rtt=WfjZW5d^B{a<%u{a<&(|G69M|FSa*!kj*1 zzp&0M40jTzU9?Usj!^%{#|u6E-LLKWhKB!hZ-@V5W4&kiKX+sP9~;+?`G4#*@pkZk zZ1_g_KXz78korG1&bR8vpKUuD{*SLe+&@2+{c79M`>*}Y8ouwnCw{k1?-C;Gz5dg> zSo|gYAFr=M=06tw{D*b7s!*px=%3bu<^9$PQBEcIFYlkC{*UKV(kIbLUeTzM-BZ?Y z4(!?3y0&Yy)A)?5%fg)RZf#=QYf3|%72}&$^5<1)L4?=mU)5!CUfnOxd%aBGzEV8k zhAlT${?WKp=i6K^J_r79@PF*V+4cU9JtU`4{U47vLi`;3ANvZK zZwLR!hHrxZV`Kgq{2!bC&)t~+$A(9HsrpVkAGD`pLPNvQ;78y*Y(&)x8U>|RBs>i^h% zO3Ky$u}7Cxs{dn;DlSw1$Hw`<|G69fk4^u_$DjU>P5;LpSY4_9kKIqMAO4TsTdv>z zd9?3(y}sSMwAgEZ-yU9C>b2ds;Z@z&SDxejc{e<)dwYS;ygpyA=Gy~ho~8TpzK!Rr zdwZ`;@1Hlmjpx66f4sik?du~kPxSxV?&~9c=O_BE-;2lBeLUa$yKlMo{e5ML_v1NS zeqOjQ@9Y13{id(S`~PFZ|IJ#Kq5co&2mkl&zI63}@P=6b*WJ5ro9eayPrp3p)e#Rg zH2h)DX5M|rGgG|wf7Rc+;s3fV&Q$-0^Vz?0dflj&h5Gvm{;zw=i*>)|7O4ls{J^;P zrdz}R{X4m#{hGIM&dhtkwzqHD%K5tK^tzY37uT-`+p3k*^061JTefWJj7y$o`?r$q z{pLMyjqM{FO|$*6{cjIFZw*ff|HtE_;s4m}+qZWP{qdZ2V7vC}|FXuFs7J*5zwm$T zP62-E|JeS4?Hu?&HvApt|G69fj}1Qv|HsDsK=?m*WBp%ue{%F`Ypg#E|Htj2{sB7w zj~&>dwfa9c)@OzPW5eIU|G69fkB!F%{*T>8JR9c!vAO=QyD|Td4L=C~$NLuz|HpauMhY?Zb!ra@%Wer2>-|K*u0s} z|6}9+f&b&}32xm|{U00aPs9JQ`cfSZ(W#?>ai%{c>O)oveo~wdy5bIWX`R2e`RInI1#gNu?`OEtp1PteSUP56`!&sB7IPiAkPacm2H*e(^+YjcrFyx~ke5w`b^>N;@9T@6G$l?fP;1;s4^M z#?{X+jFrcGL5X!lLbCe5@$bi~2Mmo(Q2)p7kd)zU`m>;p-63x@yW`HYgw%m3{>L%%tq-f#46)$0G)qi(5C|Hr=i#(XEk|CsGR{F+Qh zwpkAvk){5R`wzGxL;WASq<^UTKVE-UZF}{9?7$*F^?%$ysJNZ_zZde3sQ(M=5}^L? z$bE;^|Ka!{@V_z|3kz7u{)Ops{iBu zn1=`d$Hw{$nE%I4stD8hf9%Yv&g%cz*)oq0{*Mj+hWUT&q^c10e{9Upga30k{2x2L zYoz)=cfnqji0371_)pCLAYNWwTFG+;zjj;?8D-T;QwUJJN19~JPQ7gy+`~Q{2v>> zNIw7bj0@OV@BQTSF8Dt-=AmK!9~<+~;Q!nW|HnQopRd9Hxf}kE4bKMu$LmMK|FN;& z6#O3>pYOr{vFZQZ4gbg6kL~b(Yi^jLKmShs9~<`{{2zO_T;HgK2)q9M;@4*X66)3Pf82lXSKq1sWA7H9 z2LH##;|u@iZumd;zOVnG{*Sl!z_&l(^MAX(eP4aA{*T+??co2|8|D15{x6S5|HsDu z@PBL^5B`sR@SE>-{vZ2*oDcjT8=epT&)u8F|FQ9WnRewD8+bnOk}`j(q2>DE|F|8G zC;T59o)c>m@_1&rL$KE9Khv5I%yQTeBkFnki^!C^@-vC z*zkY%|31Nv_tvKEa{R&8b2jZ#|HtE@;s2~<{ZjZp_WbSp;JeoGe3z&PY-|0Ozda=H z4?6lBpXhn6(z$LFJX|UFZ+-7wxV-hGSLdkz&cB?E zd1~_W)Oy*$djH4mbGOU$SNtD)^dmEHd#$_P@&P=$b?ul1>i@X^E#u~^|6||#V7>oi zzwrF~>i^i2pPa4!kNx(2H>>|+KXz4b^?&TiS5~P1V?R77U;Q6@;sbZ#^iJGNfB(bx zwV3ms^`gB;W&YX+UhNE9YQ1>hG4WL^t=EgU`@O|FYmYoWSpS#TH@D8C{*PTcbcp&t zw$t}|`Fm!sUB366wd((PelM=ys{W7t-ocaV|JW%#xB*NEqZ|6^kwBK#kFsm!y4 z|8qCy|FJQD68?|9{F47;uNDsm|Hoc)s^0(c_F#Qm_&@e~c|ODcu{Vg1ga2c1lKtWT z-2GZsn+hI(pX@*4DnGA=|Kt7}<^0|+?PR_FlK(byok! zeq{L^XH`mg#hl4I)cY;)tXBWW-uux>^?&TGa(?iCY|PVx|6^l*9sD2LBkSYB|FP>X z`9JnX*$)55-gNrB`agHW|FJiSmxTZ0`LDm^|Jax}2>-{%dcE*}>|N6G_pRN3JLUS| z|9F4F`@#QlfBHZ64!J!19~<-Z=1lHk=ZD*Wenl^9c);lMeXO^L#~azUzx7t}c&`@@ z^lJD&-d=2n|6^~LhW}&l5Wffi$KEH~;s4nCW&6n6uBteHc)R(&Su;j@HT)m9WBpn9 zKQ_M4bXC9&*6?lcf7}i)2mi;$_krO5*!ced{2v?h`r!ZEeWuMF)(6jj<%H(nY0de6 zygl%Q@PF(h^7kK^gx^rMej`rD`F`+!ynSf+KQ{dzoBodt|Mzv1rz<-4+OD4MxcI}p!OvJ@p8SHe zXRYD=;Qx5}Bl7nj{2%+U%&Ua|W8?MO>)i9!`1|n7pQc$Km-*FCwVG~yM7G2K@%}sT zQT_Zs_TDpRott{RZ2Rw%@0Y;;@%peHF#I2TxA<%LKX=3bvG>aFEBHV59`W3m|Hs~Y zq~8Crx5?jwI{)v|{k38Hc3uCM_uuXJ+@t<)y8m(Ye^>ObQvb*I2LhVa`#*ML|0d20 zH!Z1PcZliejG4C78lJD~x@FeEksX|&J(pMT{gckp8Mm*n4ii7ve8x&^%*P9kSyjRJ z&w^4qIsfRf+B!sf_t-Voom2gtw_aRp4PSTv`gPXvslm?hPu6>Nc59DUx5}xrPDl%J zKDlh8H7>vYflb!%ZZEyF*{k9I_i^sg|HsCBy;Glm zXO~YZ2+{d}+>ZH!@PF+5+)nEM*f>AP7n(bGtXJMq$|9C#|KizxWVcXGTyN~T&|KWJ>e{6U^tpCe~r^Ng}cK`e=o&U$i{e|^^-3|Z8#{Ccf=WfjZyX(^~>hW-S z%>Q%umHrP|W8NbCpItt$Sp6S+Kz^~aWAekcKlMMdiW*q4h>ga2d0Pr?7Odlr^B`D353>x1vR{Og8>r@Q~JlWaSB z_Gb-!g{<$kee{#I9sSkE4GsSV|Htb?!~e12wJ`sWk3ZIb#r!`ud?MEWb$84Q&oo?K zeBsX>p0)P%WxjsQw|)2boj*6ExLn>%YMAdiO#c7pZrp$F#^dL1cvW{-`K(9myMC{4 z`<_ofpY?C?`gI@Q*Tea4_ibPA=i9#bk8cn6@qE6%(s$lpuM%&+_uqPWp|}4VBCjv^ z?e#rh-}#G;8a49T|G%}b5BzWY|F`YF$NS$J{_opwQq=$9c<_IvZBxAbpS$7zxIc~u z|L1P_KX=3bxf}k^-SB_zhW`uxG*$f{{2~0`CciG~|Iqgox>|f;;_4R~wo4x=YG|wv z{J@%NwjI4X`GvXIZQe>1KtQ2*yA4gbf+yg z&xZtgxnlkwoBq$;@PF(UjqB(Cv9aDU{2z}`|HtmsqPg?vqKEAMifq|T{U7h2=+^b~ z|Jd0w&>sGeUC_Rr`agDNP^kJpc2#n^`agEJ)w)6yOIKX$>T`G4&Elr;5!yuTtcGSvUE z{bc>#;ctww`?pz;zcY2#&DQOr!qxxrc<^wT|Hp=xga2dW_QC(T8}t9z@PY7u?39Qo z^?&Sy=uq{4?8KNb^?z)5JNQ2~{U19jDaHAz_}aRXafLc>Ge&NI`}}LHLvym7!1LYe zets)fePCE_ji;rh zqSOb5BxI=nV@D-qs{gagOT+)MGh#E<|FN?Zy#LtBy&aj&Zry84jnib^ht}nz3Y^pz&RE|xAVB>eFMmUy4(k7SeqAbBssCfA z7dBS^$4<^_rv8r|pVmnIAG>o>Q(ga;#}9~gbp2nplh{=KAG=9vOZ9*3jPw@j|9HIo zy!PtcyZ(_K9{EnE`Msw`ZnsXz@8m2j*=CLXj|Oe^ z>bhB5JUkx0UkU%m;{_LWa=OjmXdPBo@Bg?zJQ(~R8(ysDX^%a=XsrLs?dfHq>i^jA zY%4miYuI1<%#UlVqpO0QM*CM=$JK^9^8H`yELqRD-y~_-df4u)Y$o{f^iFI^EDAqUe>iCX}ta151UwvTRQG8eV6(89158my%oCRJD|7VZC z_&3b|b2t2-yW#)b{o`+QJ-4qus2(=8EWimn^p16UMUYcH?`>;rhyUZ{u^s-eq2>F+ z8MAGFc)X9AzS+>_VNUZ8U$@5N2mi^C~*4 z|6}J@hN}N#w$955J#kolqX^G}-l>wNn=2 zq`o=Dx=Br>Gic(o*0}zA`afe0kNIZ8)7DXyLF)f_{V~-c>i^iq;$h+c*hO-G!2hvv z`>(&^aj%B|iH(T_=0ox z_N%P-eElUnjrEZ)zfu3k{SS%{lJ&bhKds%Oz7O;NQhplj)$o7Z4j%{q$KHqeY3KWR z;`6rX=drsTweohwrSm%^pNGkO z6l<*SC7+*KW4@n!zG{tmZn7Sz-G0nBdm<^{tKt86e_-Aj=Kr}H{*R6Me9zsIZjJeT z@PB+f4u1NL`agFMKbK(p9}~YeV@aI#aq(!UABnMs-wPia<<;;rPXSpS#%qp|)k8}s&(jg8yUhk@+t0 zf9#!SK34z7-f;4y`akyLZ@#JX|JdViyGH#VyMOOe^?&R^58bc+kNx(MgX;g-@E7uW zwChL9>&trn$urJN7yLKy=gp!IKX$~wSpR>N-F0|W=i2`Lg%l?S1V{og;_jXx!QI^o zr3DISN9lzy*?$5cM=U*?km)D#1`$vw!!)@pD`N5t8>i_uq*eIVLWBwoe zont5A+pJfJr;`0wt=Ee$g8$?3>%<4b|FJPI5cB`oAIW~I@PF(zhfb*fb2t1SuWyy? z_bT4adi?Eo$$xJ+4%eM=gRox2PFyVW7RCRum%P1F{U3XmJRfp=F}t$X|FPlm;Q!c| zzX$)v{`ji^h%d%c9`$Id@%>Z9uaxPI51rRx9KPt3bT{U7_z>EqS^u~$zYjPK79zFyxP zSC09e)+^@Us{W7b*LH2h_rI;LJbXm`AJ(J z9XYT5kG;0$jQT(JhU4ee|FPG}_XqqRdz0*^3;)OdSo|L5|FPGIcZ2_9k@ZH|U-okSrq*lZ{^9?4KKMZRKQ{bX$m9Oj2hM)(oZS#; zy>@3cex6##S5!E|{DZBX&Yji&@qB#-7OMYaZ`<*K`agbsx9{1b{*Qg);zjj;Z2CVo z{U00i^Wgv3`(-{J{2v?s4fFrl@NMvaY|N{}{6BZY|FLoW%DWfnDnBaQ%`0?B&&yV)}aZ>jV0G^=Eeuw8rCu|Ks(cCsq%&^}RBm@73RiTjTLv z4jW~Sd3_ywjIoA~ga708;dx|v&VGE4 zHU3_y-T8T5J*vU|*6?=le>^|t_rd?MaeMebHoPDF9~=G<{*R4$hwy*wYI*$df9!*` z{*Mh`nS619Js;>6KR<4L;`6W6|MB@dE*=m5kBz_2g8y^(qO!%-XXN%b4_#t?N`C&p z|MC70$j=}6KX!Gk|6^kwAp9R2^Zwxf_RSFjwZGQobKB zuh##ua~gR3AG?WPeVzZu_X9#B+vxm1c1UC^^?y9Rz4$)(Kd!?E!vC>xJp3OU``g0* z+52;e9{{bGoXoQ~jNl z|K8!%55?~C>ahcMd-a?{yX|^0AFuaspIBp_9{eA#KQt*={U00i2I2qs{v`dMyW#(= z#rwUQbkI6HJqYg~TjT!V|M-3@JfQq zga2c95KjjG$Hu%pnT_YwqwYFm4L=6|$K#VSgVq1B6Vh8dvX`yb^*pfuqF0ap;gWT{ zc)aYOPpxB90v-52o-Zh+rTRa1a7Li|KXyh+fcignT9TjoKX=3bv6JGOssCf+^$Y*U z_KOct|HpO`{M7&P>sc>3Q2igD|MX;k^?&S?gciF0FS~70GxdMGeS4V~iTQtA&rJ+e z|HsaZZK?i`js2nF|JX6|`hfpqXQl?K|6}9%fd6Criw}kWV+UooQvb&;lGg*~|FOH5 zbX5PxF6|nr{*T?ef3oiX%g2*7z~le8j)wnZ=M3`rKX%@bOlMGeJzMWD=fnIzp08K0 zI45y>eOpiK8Rb0xkGf8j_gCTnczjt-2lapadDOEc#_RL0KidD(*T=xGVE&)%Dy06e zyLc-2KXwn9hXwz~#=JcEKQ`u%!T+(b|1JCTY9~<)zG5^oq@PBMPpP2v0^Wpi1|6_ChAA6|me~bBl>`;ULz8t2bGU)MN4 z{GYu( z^?O}q9;JI7`&0k7#^ZIb!#BFy*ZYks_P)N6oxQJrM47iY>|N&V&2OHn|6ZZP$JRCG1wL_c znb-RNjIV2W!qZ!q+4(T95dM$n$L-<&*w}9v{%=Qmy81!*HTXX^_P@pazbW|{>i@9+ zFy{ZU{rvpY|FK&HHg$fSx5U=r|C;}Ev9*6-Gbirex(*0xuKusyh)nf@@PCu=Uj5>ob=^AH-`Vung|-g=ck=eS#(cnEet*K&LxTexzdzM=aA0#M@wdlqJ-FF* zPS0EGI-sHBO#Nkntv8eXc^|x`u3I#{&Vm2qU!pv!Jnf9ohevjro4?f9%q>!Rr6m z$sHrq|FQGLkG<9BUOPUoQ=Ixgu4hMfQvb(>PlNwsV;&s*9~-xa|6}Jy$EyEh$HgS7 z|6?a5h~EO z)c>(Nb&&lL#s9JKc>2lwKQ`v&!T-HIK1=;ybW*DNKX!Urrjw99(biK_WL{#@1nZ2{ zL}xpAux{Cdj?9L)4ohmJ{*U(`ns}Z1KXz;Jd6@sl4v24{{*T=(PCW6v6P0~#IH*3cd3+P~ zf9!_wjn)6L8znYX|Hp2h<){9S=j)KC@88(J@>+pis>i=X0pn5>ee}n%keP_S= zzgU^)5C3N^^WNb9*l`7c>i^i0^7n4=e>`7=_(1qSu7?)4RsYAvyf@7Md z)BmyI!DRmt`+8y?-#roQ?CXb?{Y$JdPfqqX@#>#euC{K|P3F5jxXP>H|M>OAJVE$B zcaM1GgUXg|4yoTu?-J(B|I_P;mxKRfJ92;Uf7bH%pzwd}W?drH|FN5QjZ*)|t}pvVWB*@vJdu3*eztg3-~{FK(9{f z|JaWFeJu9>W!E2=p#G1q*U-T!>i^g+yM?R&V>`wE>i^Uf$vmdW8}ilv$&4HIe>W^& ztp1N(`Q6v*|Jdin`@GYCWTkv2uHFyxCE)+qyX5mA_&@d@%#RTN$A+JS|6^mm8vNfo zmnzl&)qLaef9{s~Bes4@e3N`WX?;?B5&R#|2Tuk6$KEGi3I30b&%5CN*!VmQ{*R6Q zisAp<4gbf-zehfQg#Tmjlh4cG|Jb-a{2v=068?{UQoJMlAN#b-vpZIjXboT1+CSc_ z;s1F2vG0CT|L1P_KQ`v?!T+(3i0^{`V`Clj|JYc+vag*r{G9Bs=hZUL%o_9aF#nIQ zAI#&E`8}?6kN@NO;rZbI*hgf3A@=`e*L?FU<_B5B`^kJEua@~k)(7Q$+xIxu)#3}` z|9HN0a((cB>} zFW>(1l-(Yk@YpeHcvkp7K7W{x3IE5&>j{=f43c_5G}gGjQ(nLDf9zfI{Z&3QF!zd-mucf&;u3V}9kA2s}^VR>ci+XfX z|HpRjyjT4ndywo;iT!`s@HFs$?9Jk7;Q!d`WWP=LKfYczUAV0NkG)eG^Z$7Kj`NrB z`rK|U=ZF7eZ#d-ffBbqszI#7j58K(#9XpNrj@E0%yTSkQ^#e}@|HuBI<^(*K9gh|t zX8qn_kN@NG@Q3h!?25xD)&IF$&cBWQ*3Luf|9E{RW2eb~Z#W*qiur#7J^qjDdCQ+t z|HoeX(R%fN?9Jls;Q!dz4;J(P*jwfC!vC@H{KNmTH^@9l%>QF=Jn!*;yk0c?9~<+{ z$$dGUYjsuQ@szu5WL$b3KeKi=QE)1LW%>@CO6tN&wfsyVCvkNxUS zkN;y&U-Yi}KX%WFE7kw8+oj*F{*RsAX@UAbcDJnO)c>&u48ITGA0>Q!jhgrvzJIJ= zmid_S{bl{^jZ@%ntv{GCQvDxq|N6v!>i^g)?w+mwkNy2lkN;z@I$WdvkG(;B1m^#- z@%4rOV{bZfM*SbZf7aLfKlUc^pP2v0#_K;l<-HRA{;)>&hhFvYN7k!lzv1NbYrGo% zkH^FN!T+)00p)*N@2KAIhz+rR?v2-EKH5I(o)6q3zt0@BF1~$^%s)G7-F(S%nRj;5 zy7MRdWWL#1>zAv~%6_JotlvC(*?D%^=hp9wH*Iz8s`W?mdRtcdt@RdpyaCVrXpQfW z#ozsE{jtmg95dmsC09}^)pMcGe*AZ9%)=bj;6K)w|F=7;ekq@iUGn`>4>9{*QfB?jQb-jlVyF|6}9tkKq5<@Obcl?uP$kHpaDe{A?m_&+x0FJk^58~zghukQJ{rv8tOuOH_Bxf}kEP5;NPk?#liKQ`v~ z!T+)0|N7my)EfK$!vFDl(3t(!Y5$K$d8@2p>+ zv-?B$Z}fsS<^iUJyl9R6fm^1&WWE3B3H5)x{_5kW)c>&$)*My;=Wh5v_MV!<>i^jD z{`?63ezlbUeLrE?2)w^#-Bdomk@vr>>-pDH|HtE7iQmKizw9=#{_6ku{z7Y+=hxxO z^`-2g5R&BBlOlsw9{(7@D_Q!?)y?{%vY%D+m71-SB^G%+G`WW5eUg z>@{o5k6ZP|32V%cTd?aO{b$?eoV8Aq{bzp}ea_WworCkw zTPNpu{2#BUeR`M!|L1P_KX#COz2X1Z{weJozr4?^om9{KKfb?RKeL_sKX!C_NA-W~ zsI(61|JXP`{2v?V$Ns-;Cn-?2mZ_fof7#e?8uS0$4gbfkpXKp? z?8fqW0_Oj*<8nOv|FSbXcT)eyF76eh{*T?cUxLp6V;A*{)A@hyhW}%i^^Mc{f9!(p zk?Q~0#oa>H|MB@L>(NpDpRIRKRR71$DUDYD$Kwn0!qxxr`@6hLf^&mkqcV1Bk+;X` zT;lCleD^EGeydY<%_yUHfd6a0bEb9Aq7wCg^cH>cOV$6e%QN%U|5=Oog8yT~E5ZM< z;Q`_Q+ztQ7#ym63|6}9!@PBOhH~2qymmR#V?0kb1^?f-0>%D)n?wMPl{*UXJhX?=X zZumboZjbqYY+Nt=9~-_5{?Fa;f9{6=W7Gdx=N78}W8-?T|1TT+E5rY#1|_Qp9GsTp z!2hw~D>46%$K(0J{=aNIKbZf=;|FBqs{dnSJ|g@dTlYg2|HsDl!vER%r04&$ZXJH_ z&AT75smX8A)&<)-TVKQ`_k z{?Fa;e{Aee3;*YC_&;`+%yef(`-S%S(C~kJym{H_>i^h)E6nO7v zi}{D{&!>HRXr8zC8<^$2e;qud`}Th{Z_d~A`uaED_VsVR``->N_5OL`+rzqe`?w)K zKG666eEptp`yTK6czk`H@6Rva_C25P{rNWLSGu2X-{;5odVIZOk7DoV%h&VC$-T}m zzpnn*hTd~uk8l5<+v@>!^CJIW-p_qL`oAY9MydZp!~eM({?Fa;f9xi5Jp7-#;s4k; zAN(I1*8~6O?(#1dS8eYbt=L5%u8bk9*wRb38FRPQIe%IW-%WmWlY z67=W2@IB||`|28=4<3)}@P6NHT2j?4Azpu;qW2Vf_v;mlZ5^I#UT5!y|67rktp2ZF z(?;t5*!5+88}6@9MvD5sMlC)2|FW+W|AqN~*8VNj|G69fk4^u_rvIDXD^>j;*5UuS zj)wnZH*f3b!2h`${*R6QQ{n&E?c2+|8}WbagwSC1f9wwa&D8&~ljQk@|6?c0^9ldQ zhS!7tV`IJ_{2v?p<--5D8~%@td5!RY?547xFZ>@H`#Hn^@%ayI)?ED`8}s$x|9E^@ zqXz2#xDFo}EBpVl+tv5@KQ{dzyQQqd|FPjsvHvfd{*U(uUkLxl&J74s|HtmqGEn^= zzn+DSnyLR|XUl%m@PF(cAtCDj*wN9^>i^gYGT#jTkB#|uB|Y!4#(u8Y|Cj4&ks$|jrn|-|HsDsJQHe ziS_tDcF*Vp^?z*42b}-UDRw;O1Gf9y_100LVe0>Qe1~A!4^#Xf+mVL<3+R)k{;yG3 z2lapK7@5}y|Hp=}g#TkFi*JMfW2eZxJNQ3#QdYY9KX!`D1ODr+W2@38r&lh1u2E-`!A06SO9VxVK7ZtAlZ`9Rx z>H*;!;s4m-af#~x*zkVvf9?(&k!$C}{=MsF=i2q4S1ic!YWKfqzViUvrlvR}Z~n4! z{OmpI`_T9GxMH1_8m<11>)p#e{*T>hbiVWR$xrS0*s+D`|F~W>I9mN5JF#<+`agLO zMSWprK{NG#T#pr=2>-{9N^h+GkDZX`r~c16yQTU+o-aPDh5A2sM3%q$KX=Ps6qW4o zOh5I1U+vke{trEQ*zrm>_TycUe9XFCp3DauRAaY?w`-kv#2Ow?{(jT0AHEO%kJpQN zdh*|@m9mGg`ajIy!~VbQczOQ>`~R}x>#+YX8@^8dw{>i>$NzC1ef6$gwvPL2K5VBo z=D)%J@p#Pdga708B^0$*|Hr2PW5>$8H26O@{MrWbe{A?Q_&+x0qrv~Nv&0|5|FJQj zP5wUEoS=XiWjY;Wq$_vKi)oJP^$Vrcfy>vDeGzZ}5NY4Yl+CcC6c`K60;o{s#Z&Zumd;COIDdkG)lV9Q+>}eiHtV zeL*}J{2v=$4E~P|F9!d|t`?7m`G4+)|6_Ch9~<5e{?A(G=fVH6kBEhV;s4n1aI!z2^>Oiv@PAy#`7r;FeeB1-sQ+Uh|KWG_e{9U}ga2dW_V9n~n(u#u zm$JruLHIweqv8M9m&NzN|FJ*&@ptuq?A_uA;s4wX|HsDt%l?WL{Q4i2>xKVg!%M>d zvGM%E|FP-+cs_jn;Q!coeSeg2*sHNOAJ?%THfC+F|GS_(AwT_Fnn=!T+&we)vCk!~e125#j&b4gbeJQtSWN_`Lt+ zw1xKk9FfnD!%zR&8lQi||MB?4^7$_OANz>Rdx8J6miaC4e{9Tef&XJyoIkJrkG*2& zPW6B6_g`GB{*OJfr)T~j+qrdy`agE}y_M?!*ms<`Al@j(uK&TyUx`l&vtBRzJ;ML- z^{`RqFJb;4d#B7RlzCd#RpMjd|9Jkb;?>~)*lXnTV$A>J*L(f0eRw@sSIK-n_&=_{ zA^XuLZ+OM}b(sey{>}OW*`E&nkH@c;`FikwY#cAX&iZB9Z&du9_2wgIa6Q|2{Hjkp z`~R|s?An9lZQU6#Sl_YZdeed3@$;aFkMHKSE2S4&zq554zF(|&oj!x}74!C(j|l(A zhWCU2W3LfU3IE4lE8Y_RkG)|6^|uKO>LVj;|CiaOBVx zYxqF;Kc0WBti%7YaXxvxC49VF#WTv!Q|pc5x#Z`w^?Q4DzNGbC&#Y4a$MfAV^?kfP zZ9O4=HvFpfz_yR!^=&;i`YF8rt%rC2llnhi&#du_)c>*HyT#-G*l*47_&@ghvxckx zW4|+fu=uctO8D>bst0Zr5B6v4pLeat_kRgr{~sJaB=g>uSg$*EQhe7_cKk;1efcMz zv)&}H$4v<@Tdx-HhxvazAN(5pANxI-w+R2o>scxD7~%ie?@Pn~u|E{=2LH##{6P8N zUM)7ny87@jM`k&dOu4W{{an?qz2c+xTEF|Q{B{*{(0cmx>z&W;tg&|Pzf1ie@2| z{*S#*UeEA{?69KQa*p^t5=e(56Qn@@PAxK!~e120pb7H z2R{8m{U3Xe93Q)!Q?n+9jb@c_0|Ks%@y7ZO2p1a!m z3GsdKf4slrGEWfxkIngiZ2CWU!~eM({*Mjc2>-{%?+5UI>_eY<=Krye$bP!;f9$g| zPY?c&eOf#p{2zPIr`L4;AA9d--#GAp>|=6!_&+xN9~*zq1pnvm)_ZO$T{32idOvtL z_&+wh9Q+^qtlWNB@f@#)|Ks^^Jp7-#;s4l&<@YoAKQ?}!g8ySsqcavE%`}f81a5!4F#F@1MS#`j9nz;=#KfwuVpqaM2^y`2B3*>yKK)7sCJ9{mbhM z{*Qg~^KaDu@%cC-^UN{-k9|(g2mi-DEng4#KQ`t8V*a1I;s4l2<@FB#$HxA^@PBN~ z_k;iA^`PPZ*e5T4uKtgGRDNGb==hASACun~4rD&-)r&4aYv;%OKlnf1AG{y@AG=yS zAp9TufULv+vGi^hnqk`4{vEl#j ziCAaHw-WD%`F~swh;E_&j|~q9|Hp1B>+pYU|Jwb3`TiZe688UP`=__l{eRi;Vc7rI z-Pr$^jrnx&e>^|t&%yt(;o0E-+ztQ7PRb5a|Hn?q3{d~a^V9#a(V`=zP>W0&i^hO(Yp*Eve_YQl zY_0SE*m!+l|6jIWkfZ*OUFcU&{U5&{21W;~|KmDd-QBvZ1_F+KQ{I+ zh5ut?|6=$*Hs-y-|G69fkB#|l|LS#58GQ-5XSaK;hh}9vOH1Zi!*`v_yU!ZF3-kYY zd(Qu3!?VHvu{&p^IrEp+H9o(6v*m-fj{R2Q|9E^a`Ft4r|FW?^AN(IXJ1t%J|7G_{ zOLIow|FEs&eDHr<$JZ17j}2c5|HsC>H_ZQYH~b$P^A$1wkBxbEnE%JdygkhSb2sMy zvEdit|J)7#$EN>d_fD0cx8ncUczp1G{QBYfx$oo?wvPEaZwy{&ou8AT{*T9(73Zt} zWBY!;`T8(!y4QU@T;F1EZ#c5p+vkla@}B4Cdwl;=@8f;f z|EPVh$JfL8&I=q+=DokM@9llt*WdZ>XY4y4(RbdU@AK{Z_3=I4cRyd>#_QMp_3&-@ zGWWV8e#pBeUHd!#AJ3=%N1f+${;2DD-(UTD0^(ff7v1!K8uR}yJ>Su@|F5jW|FIo8 zAN-%Y;s4n1Pw;>4hW~Rn{GYqw|Jd+;@PCW%5BKtaY@8qd@2km?Hveyaq^srOEqG_K ztv8VUT%S(z?pHs4(rf*p|2$dsOs}ZQ>C66AhOf`%hrK($NnOKpEtvLXRcU#2S{WY|x~Ub0uzR)q>P`n-93--6hsdn>JPdmywvDJ`j!h ze{9STg#Tl=@N25`|J+^v_b0v9;s3batVLt>f7Wt7_&+xGBZmKD`}_N=|6_-UFN6PM z!(UM(`@#Qlo&Jx{cRi^i0GG7n=kH@32|1UeSQGNA)Jf8divg!Za4gbe(E{_NP z&)t8Du4|nCtseK=dPd8p>i>BE#o|RV|BsKaP`o1M|FKiVC&K@+JGXDA{*N6W-9i1I zyW#)X`1-;Bv12-htN&wT9rOR#@PY7u?9_-T^?&TFm^k%+?Buw3o&U#9O-OX$|JYgL z>oEV1oh;{@^UfT5{^1wjTQS=@QoJGjAD^GNs4(?^Z1}yP&{=lAP955+|Ks_CYyBU) zRfiC#!HYN9`8vkOIK|K3XdM?9r~Z$}!%xEhu?u1obp9W^L_8zr|FQE@64n2)GvYd_ z|6}9pgZY2#4()=}|FIhc`8i+xIMLSqJBFzLyEivUJz!W!xcWbKbY!ghKX$x$I`}_! zN^+X|KXyh^n)*L?uWmcWjxUyZgVjN!t?~Qwmn}zGBmIFJ8hr$u*k zTAwJYdgSlHp8bO(!<-4<6xi_*GH>z8hINgvcV&3Kt+(xz?EFxeXB`rk=6o_N&(4Sa zf#Lsnel+|a8y;}ihnZDvMz&FJ7@g?7KX7P5n)<)Lp5CGUFGS`$!vC?8GCcGD*j;+& z>i)m%qG6fp|Jb<$Q`G;lI}J|6f8SS%IaBY}u6sxP_rEpv$Hn|V9v_z0T>T%rO?rU( zKX%*9AoYK2y#EvV&S|?nx^dy@%I))asxQR;xtRaQ?vx#<^Z(emf6V`r_k`5{VSiru zKXz0>u=+oCbYWZdf4n{B=fVH6;q&1Cczy79@PBOhJ9+=dtKt9n{9qma&)x8U?w0qO z?EX?pLh<*hUM+vWYK`+f`}QvD)Y33VuC=bk>s=YS!>gNSR9VN%JT%Pz{9>NNcOjVYWf;$%wyZq`D1I$WBa`AYOjX>TA|vgA>&MaXnJL zf8qbw9S5hW|6?~F8n6D3?KdJx{U19}JRau%v4cir==?u+h5|6_-aNK^mE?l{up z|M>XBM`fu0V@Hq4RR7109iOBAkDW3pPyL^}G5?R9IXPSXAG>&Fsm}jncbiqH{*T@D z<^rAn$Hx3p?ElNoyFOd}A3JSAhWbDLe8`(tp#G0tJgrduAG>gBzWP7jK5I&W`agHW z|FPq5C{X{$&bp;s{U5vgttIOJ*yVGJ9r!%G$Oe_Y>F>;J69^T7YH zvA-<*ANz=SChY&~Zumbo{hzyKeu=GPKQ8z`UN7bk!vC>Pi*JJeW1o_B_&+xM6#SpN zG5-(7>V~2vW%Pe+_$>H8HvAO)AA66?H+=XXDRw^WU%cl?l2^n3@pyQ#-nYluI$FGu z^&atN2ScO1y5&z1)-|#|a92mKhX3RFF^>=a&)x8U?1R^SR{zJwJU;k8_HmgH2>-`E zA>I!Dk9|_S9Q+^qRIUGWH|GDbaXkDV8y*n;&)x8U>;rOr@PBO1|6`y2{&)3%>{D|6 znE%J#Bl8B~|JZxK{SEskR`Bah|L1P_KlagD|HsBWK=?m)we+=!Q`QG+{U7hI`s*Ln z|FJPY5&n;TL_93^mSi86`Ihj1y2r10K+Lm*z2Q3c6UP5$!wAN(I1^KRan_mDL_ zL*E|ryc+(G=Q}8$55xbl;V~ov*+*QwXdoF2(8(*LKZ@#AfkL~pBg*Wu{HHx2~ ze*N-sz9Qa!`O)pTKI_eg_Tl{2d(WRz|Ht!Hir<6(W5ZLz|FPH0{(bO&?uP%f7C#98 z$Hsg>@srjS^7WJNH|t8-PZ0i($5+a{K=?m*!~e0jiywghb2t1SAMY;lYw&;Uo$~y{ z|FPda@HxD<_3h8C#@EC8`e`2j$Kw-H=Boc=7kBXZKX%Xf<@oyA?aO+2{2$lHUcXfR zAN#|(H|hL8_KN9~@OrV^ue^B(zCTO&dVPEPK=pro{jYiSPW6B6pLTCh|HtFk96BW4 zYe@;$x1Bz%{*R4$fAD{7%(J`p!b>GzF4&;nZUdgb?_aZCFVElF(<|(F?Dq`+$J?*2 zo&Q(Y9{iXL_E_)>(Lu4)&KGSAKPi^h>&wru*k9}13zlQ%~Z>!p;{*OKP?ZxW<*ll`es{dm< zQT5gTv8OMYqyCTm)Q4-;|FO5r;}xG>%Gci>Y4|^`5BS4Harph zAN$xBUpdp3#h3E=g4cupb2t1S8@?U>j}6}r|HnQg4gbf+zjv7b$Hu>p(c=Hu`{n-O z|Jd|@>>c9k;Q!e0mr)}-TkjXY4*$n>%x{DLV`E+({2#kQ*0KLDyHflX=KrxV9}oVI zy;p7z|Hs}f-Vpwe{mEs|{6F@dOJD2!KlZ*)J^TN%kBaYu|6?B$-?#kq*iwG~;rEN7 z{~m9R-#>z4Ct1U{o#=nPHGJFCw@q)Wd0zd@kojKy{-XO!`%GD{o(zvK z=iCF;G(hR*vtx|1oRqH;nmzJpPRQ z_Z9pf8|(0Y?33aT;s4m2|L1P_KQ{h*6aJ5VOy>XH`}q>Pet5ufzc01M{J$1UmfP_) z;(32~^C{~i^6xwRAHN>>dyd!~4Pixf}kEjd_3Yf9{6= z&~BR&3)js1YJ|1X>S|FYo+vHvgM&ugF93h)0}WB*+EKdxi{TzUV{ z8vED6|8YG!JJ^B$W2a=dchZ|xdbPZNS=Tb3PTt?N#(X-tt*hJO{ZZ@0tRVG&Jb$?C zkBa$!?1;=jM{H3k-|vji4RLax-fJBt^8_*fkL%dK82*oq#|!^wE%OiI|Jay+i2Z-r z@Q3h!eE$~>|L1PZ|6^mnVE8}YzN73f4FBhD_&;_#@r>|)ygl~+h5uvY{dD+0Hhd-g z9~=7t!~eM({*N7i^iuQut&beSc>6wIzvkP+O1*vE&=POo*Q>bH>;8P(cb*=;zV7Suok!@~ zzTVi^NBVj~U+?!vJw(2L+}GpV1M|J-D-QCR&* z-6FV^?*Gef)w-SfKXzbHumk_ccG?8!{6A~iFZRILB~=sGg{t?%H^)9ZBpAG>9fhU)*=^_n$Q|Hp3Fva$Lk#QwkRHUZ7l|MB?17LC;Zu{+3qyRkC=kH@!@Z`b;= z|1UeRUOi{?F`3^N9j(9r1j+SI9a7h=r6bty-*jO{Vs z&Y#w_q0_p@ebypQ)w?z6{B|5ua}tNt;wc{BBY>}KNInhuy(#cmNErt|;U;gKQg z|JWVE+o}I!V}DopKQ=rd{2v?p)nfl&Hs%Rp{-1TN|8qC|A3HuiUi}|CCMHJxAD{nr zQ4#9@*dd)f^Z(fJbD00fh6lv{zwD$)&;Gyc*swt7z)RC@J+6Ig^?zJXkLsZQj~yEu z>)i3|G&>%>`so|2;TOMIKGix$_M3(O=xpKmUWv4*#Mxapw-j6F$iFA>e_Y4B z%7#A_S||9oa(-`A*F}*r>i?d2CP+PDo2W$fe{Adr4FAXT!TWuATXxm){ekNHB4X1V z?ElM7h)+`g=Wh4EZ`l7A^Z#U~oBF>F`1=m=f9&MUNS*)3rvGDy4(z1 ztkhrq-@cc&ssD>AZ=?Q?om(J(Zz%qc$D=X-kKHyuNc|tXRkmmTA3HF|PyHXeRbGJl zKY5Qx{U5v^{GYp9tvFdJdq}AF!}}TVf9%MDQ1yRo?010qf9wSDfU6rGwNA@#tNxGY zPcLZa6g4<(_m@`K-kE&ypmnOO%U%)IIDXaQ1J)UG{HYuFTf+~^-Aq?ChS=>i^u0`G4#j@ow;c?uP&4^PkrzR{bA4yKlVuKXzvCSoMEb5-ZjJ zH5?SH{*T>gNWA(#c7q|Q>i^sg|Hlp(mZtuX-AdjMf&XJCj4n|B$4(wstp1OU`EKxk z?DWxj>i^h<ij=;#`R@7|BszHrL)feW2a0h)A@hy#{55a_6^;1{vSJM zTDk83%TBtXtM32HPMq3B_y1)l-B_yo|FTnOba4*&zhLLjn95`XZ3&XE`I3Gb?2X6;!GX=sCD`5t`7G9k(A|8w^bcidy=FPqz0{U6thXP2n|W0%b? zRR70LpO~cnkL^D)T>YOje69Mwu&K%F|JakBTB!byz4^N zFI>H*{*S$1{G5EgS2;CzjecH_d1vzZpEZ1+d_L&a^7)}x%jb(;EuTMH)Bo}Q(C~k3 zd|r07Nf)n{{m-m14@34x^J>{Y%^LH~WPdel_$Ki{m3%(1ziHKj+19v!XLzPH<`s60 zPq)V7hyUa4vEMQL9~;j{dP;)bAAFd6zUk|Jd++W5>0$;K#h|HnQo*9-sWZt+ZZe+Pc}Mg1S|9}WM(ph@XQ0W4|lsga2c17ViZA$KE3Iz~KMb@16Th{U7@cnNJ7*$6j>gD6VH4 zyX5`{aenKhsS|L#b^9Ux*3p#ADXjZxr+Y`1OOA zg#Tk#%6vumKlUp5{2u;~{gLcP3jfF6A&(dSkB#%g|FPls;Q!ba7vT$!Tko!&|HpOQ z9{!Jw+sn_Z5Ny%8ZY6{vSIf z`%d+L?9%YZ@%py&^-g?R{U6sy^u9yq|FLIJUabC)y>jjh^?&Rar;L-==WQi?J-$1A zfb+!j_m=SW{LW4N)&H^IzkiPUKlV?bte4mS6L$Psna2kI$MwoHr!k+YgugGq|H*!f z*7Sc|-zfVn!~d~2h)?~hbcOY1S%?4Q`7v)1^Z(fE<@uNY?bTwrtT)N`qs&J0YWP3i zzEbWF^Z$7N*#8;+Z^^cg)&Ffhcv$@(dsWp=^?&TWPcK*h$J;+Od7}D1cGAS@>i^jB z*}O*p<6?ssCfYC-WJx|1W!s{5*jFS1%H=sPRl+Q2P|K?}Oi@ zRH|3Q|MB+pe{A|c_5tyL@PF)say{^WY|Pig{69AK*MUga2dWdg1@r zhvazpKlVoPgz$gtE#lSS|JZwK{hzzx|JeBV|G58Pd;Evw_l@OwL#?rn{eRuZ2R$~@ z)-iwX_^Q#?`1>9BKR)04i^id zf1UqV`~8j{yJePLFZ>+#|K;_gTTh*9=fi)WoLYFBSHu7D{8)$oW5WZ&|FQM<;{V(Y z|HsDsK={A?Z9i83hlc-S!wHpaK z&z$qj|EsP2mii^jAZt#EX zgp45de{9UBga2b=J{|lYJ45!Hh5ut`<$3%c8}HA;|FJWQL!I}dc9-(~gE^+Gr z*r`3@)c>(FdMB#?W2g2>R{zJ&=%1$Z|Jc~i1N;B7vEPUM{l7K*8TS9>ddY|^^?&S~ zk=g41*m<(who9{K%kDNJQ~jUwzgyM+q2d47edK(Y|L1P_KlT9m`(y0?%N{6yf4u2| ztEC0QwpMKE_)J;fQJK#2x4yFOKPKCmwfAf5;j-U{v+*0dJ^I4AZ>@We%XBvU>pQQ; z{=d9_ti%7g8~%^oXI!=u@#N2T`~DO2oWFhii*?zgLg(bkU#+`NDREZ)?{C)q#>@V! z;{W*g(C~lk-s6ka|FQc_C{h2%?l-o``Tc{x+3{%jKVIK}@g?g2*n=l^R{zJwI{Y7d z$mA~S|JXf8_fY@GZW`J|{U19}em=qf@%4&^|6_*)G*bV^P6%(K{*N7)&`$nqvu-|A zPXA)v|Cc|X#&qxOweGurr>|F{|KsPQnE&^7msw@}JiJ`?Gll=7Zy26ir2daRG`m3O z|NWL1sq>J!@qgyuf1|{j&*iMiuymU)Bjl)%6v=lf9xWe zZwCLz#`R<|T_YmA{2v?h z=HUO>on&6$y)VtT+b4>*#QZ<5WB*+EKlaF+T=jo!+#md(yW#)b4gbf6=Y;=b!xv)y zAA6Y0mxKRf!!N@Bxf}kEjr)iHV`H8q{2zN#UXjlKV~@%3?ElLil$oObkKI2lQT-nq zUw`;NHsL&KX<#o9}DI6>F)e|Z~y1(`+Vow70K7%efyGp@BL-*{peoD>)qXd z-&7$cb*_#&+hB(pY6RLvv1?|=RO{cG4IWNd@Db1-`6HU0J-buJ^Yiq z{rvpA+V_0^f!@b=3~25Ief&bzhwi=;3x~+@q)}^b; z>Kc9z{*T9_;s4n68Z~tKJhRXm{;zuRlU0Lzckt{-EFKL0Z%A^4`agI$_&+xG!-fB2 zV;%nQ-=UG7{ev4dQvb)se!B2~?#BE-b|X0+`~R|WJm&wo8}t9z{>>UW^@*yldk7 z^Q=>wG*JJ?`=kHk^}+u=R58!4H??siXZyB$t;5;`JAc`7k2O4B+UC2h;r%fG@2&7C z^@HfQ*57IC@O~H9-eC>j2mi<8(eQulH1Tclf9!mjKX*R!Pu96H@eceS*D)Uu^Z(fJ zX_)`V$JeP-C-r}9cs0!bV<*LW_WxzW%fbJ#V(FW8>BTv2zoXov39~?DmC83F`m2o);gh{*R5@WBwl>e|o1_ z^?z(UKk$F-w8SI_{*RrMl%)QTjs1S%|JdE*Q`G;l%j1%rDff@I>q`~y`0{tfXdLcAIj3i-Lr>h z{vSJTV7&T2c5B&xHhA@AyM061U$*%1OV%x9{@?XeE?UR+2v`5d+jo+AYw&;Um^_)k z`pa4C@QkK9|BvhSvjTMgU-_F-^?r@S>+SvRbmiu+H>>Z%{J-xHp0bADga6|?{yq`@ zj~$sSUQg!#v9aGT{2#l0etY$QZ2bM>sf$N!J-Voa`afO|-VcKRV~hyQao{2v?h>)`+Re1{B-Q~$^A zI51iLA3I$3tHu1k2Ois^{x5V$qWV8}hhfR;|JdO}Q`G;lqei6b{=e)tqdfkP9Wp*! z{U1ASlE?qCV<+aT|6^xN%u)Zx&YJA;f9#U$OVt0dOQ(4JAG>5)iTXcw@eRf5|Ja2$ z*{mYzW|8_oYkB@K|Bu~kW`WNCWA~hytNxGO zU*_+@|FJvYTCDz$uTM1mAG>63k@`O#UnU=|WBwmI|JEY)f9!(Wigo@UyZ0QA|6})> zU8eqz-Sw7I^?&TlNvSeFW^$!`2CjZDcw~q(a@s`egc&Ka-`sfXd!AnAobw-RefaAy z)&KGKXRm&({?FZ*|HrQW>Ra`HSFe1i{_miCo(BKNKKkvC>i^sg|HsC>JNQ3$!~e12 zov{Be?+*?C$A-s)|6{}J!T+)0q2T}6$K~@v_&+v2KZO5tH~b$A)sW4L%iyEn|Jay! z2LH##{lovUaeeTA?BjAg{2%+6oDcqw_lJ3i@PF*X@_fMmu`w?W{*Qg=o1gLdwe_VR ze#7V6))!=6AN(Kh@3{Cj_&+x0^TGeIYkvBR`akwzIUoEV8@}-DhCu6+vL5odzx4(2 zd+>ie9{UHw|FPloF4u4B)#0ZbS!2K7$?r9^#{R)FFU`8@PF=}x$mg; z(eHnDewcO0y5_r|oVl&{Tb~gB_xsk}UVZ1}Dr4gbeJCJpPrJ|eGY{BJh) z1BU-&SBcky|6|w4_XqqR8@FHj%*)o8=h>?Gd24*X!2e;!pw7pX*FXFpd!M}i#dp

@qF;O@PBN0S@=KpiL0`|VAnC$)fd&bSs$u7tp1P3 zFB6Xg|Hu0qJbjeW|MB~;WW!GNf9xmroD|O#RKcHDFP*;Xd^@n2 z^~y6B)c^5#^y2S+-Ok=zJO7XOw@&8w!T<4kH^_dd@PF)e$4;yNV{eepli~l^6>@&~ zKQ{Keg#TmjlX-gZe{9U7!~8$?rs^8_HR}cIKT`k4_3TNbasF*=rzjc6TSreDDeu2I z`WnQ~&pTdt9X}6>`1n2+KL!8C+rv}IJ{so#xm$d(-QUhy|HtdC zlzD^jf9zf258?mVyU$)y|Hpp&pvV8Q=hn{uW6zrLvHCxDc816Qu?v$Is{dnm&Gzj7 z%O2X#(iF4 zv|cB#A6c`8{}Y?z)iV3ZdZYMQ*&EUt^98S@R9a&`;IhB%Eb+hjL(jawQnz$8LMe zed_<%8B1SR|HmGx>J^{{*Rq->qPuKwc}^Ly-DVE zwXt4)=(4g=jU(x-4*_HD10{)M^GD(8@>_#k9}AkFZ`do1AF(d``;$>36I^<%eqoL*s|yQ zSi`Fg-qFt*UM=w20PCaj_e1c1eEi40{#N}T8^5m)nK<0m(eQsv8A<^@qpApThsK;ZfT^{Dk#E@q&MQW}!8XKeuv`SHu7D_Q%8n!vC=`pA+-{*oS4m zYWP2Q!~d}{?+^aZ-TzE}+WN5kd$05VY9G%b@%}phueOg|xa7Qg!*g}V%YMN3-}St8 zwRpdY3tzCte893-U$j1Y`mFjt-v8kfr<|#RRDTW4DO)Q~$?qmE!S#>~?9P z>i^s=wx^Wu|8~l1gZ)XYvEMKJACJfTv+#fJmiIrcLkdEiqyOA#x9?EgLH!@kA1;3{ z4gbfEmcMtFy+%tXHrb?q&yM#`Wq%gym~Ii+zr{LM_V9;%{|5Da1LgiNjsMcC z;s3baZ*-RWKX=3bu?NY#K=?nNf1u10g#Tmr8k42|&)rKSf3S62Kl~pbPyex=`G0K8 z4}|~Y?FUcr_&+v0Ap9SDz@&Wjf7X+8)c?5~{*OIua*_H!cej`Mf9!q}a@GH_aes$v z{%-3-ERX+V56Lc8|409T{b4cxkB$AsF#nG|I452G zAG?1>vid(Z=C@(~9~<-jF#nGYuLJ+bhHr!aW5YMW|FH*_c2WPw?$fzM{U00i)!_fw zxQT-pgXKK9qKXzHV?AIp#kB#ex|6}9v)hv6g?AQB3 zb^aDSR<_>)Ypi4bACJfF;s302Q`P^myXSl6|FPjCvH!2T;s5yc#`g>SpS#^2>;Lur z_21Tg{TW{G?&E#;xAi^Vw|(ae{?U9p-`o4nxAX0;IVoP(SDKOF)y3IKUR|2&eY~$X z^le|S=i8%v{NrdJ|LA+XZ~Hz!zVjF1P2JBw{IR<`=cjqK@8fGA^TyoA*Kh7U@6UH0 zANGHBA0O4i+XG_%Quq2F`M>4?KF0@opD(jz3-y0~siErs(q+C_Rr(86>>$~%^qzyy zRZS=lQQw4~^YPPFhhA)}-*4!w`OB-Woo}N)5DovgrePcPfDHp0tN&v=a`*6mZ0w&p zVfj+KeKYaz)7#dyBlFkb|9E~h{2v=05dP2I@PBMa{(Xi2b2t27hc&@o{*UYMc<_I0 ze`)wX9`7eU5dM!1KM4Ql?lHeCwC4vt@UzOr_I$zz!vEzag_#G0|8w{7xVpxC#LRb} zwDo#T8>#>MvULabf$)9sf9{6=V`Cm5{GYqw|Jc|+7ygg;-@2ur`ad>aU+{ly+#mcO z8|R1rrIvC5B`shpAYbV?Cg%A z>i^hbVPWe3S_E}e{}&n>s{W7biS5JG|FN^8V$}cfc=|tfrp&v8|6{|S!T+(#qT(F* zKQ`vm!T+)0-QfRtfADbF|JU8{f9&MANT*$wnf833k9D459TOMfJkfc&bwE&ar(5Tn ztXsBf?EJIrM(fD9P-kP=G;7Sm!~8$q9~$%j*z|vF%>RS`WA{i%RsYBC8k4C0kDVDG zt^SXXAKmZQN%njsibsS0<2rmF{2v?h1u_4RT_}J50sqIw{AtYpW8?2<;Qx64`3Z6A z|Ja$)k?Q~0@Q(0*eEqd*f4|I^?vPT|7Q3<>)2HFe^mkN)c=LX%kOvM|JaG?;X411 zU0R-{`~R{#3`|h}=Wh5vcH)p^^?&T-VX5l>*ezv#Jm&wg9eMu({*Rq3^Zeld*s&SS z)c>&^*)RCBNoOkMJt_5n^>PB$|HnE%Jde7w0O)pq-$0f{>QkLx%; z{2v>CKMDWG#{RAFf9#l1xjO%koisxJ`%nBIJ7HLs`agE+s4Vq=>~wiQ1OAVlJ+?so zA3JYCvHCxDvi$ua=Kr}H{?Fa;f9{t5R<}->Sf>7u>uHm_==?u+=Jj3i{-Pa^mNo1A z8_L!H@%b;jv4{G<4qvWU|2O2uZtDNogQs=H{wMZ)51HNr`=eNooZT1ur&#x#+s~Pj z@u62^{vXd*IJb|^|6}LNe7O~U-?R1N**(?&alK5A$Ns-7B_UB=hHnJ@K-2iOiq7 zck)Ztop0@;{*Slsa$8sDe-}P)&qwJkWlqPb&sk$09sD1Ur~hMjzqv^LAG>^($N#x| zeaLdVeg5ns^?zK?ll^)d99UxO@P3J}FZOEqKOWyteBa#z7FqWd-}idVLRS|$zdZW5 zU4Ne$1y0)u3#@xj&v#05AG7Wy`{Ul=_h;+DGjeqQU%viEiT_(y`LL~HKi>1tK4jfZ zd?frIkMDI$u@l$x0k3|gbiOri|LXpEcD-oK|KsE9e~V}TUw32wUpD<8J8gWD`ahY8 z~@lNo6>^|?SH|HnQq>+pZo{aizhBfv>o{)0A_0cO|%hzMH^iBS?{l| zR{zKQJNnj(@_gpn^Yh${$@2WASht!w79OO6KaZM?9U}XahFae+bDsJ?t}lCTrTRbi ztj#;s|MB^M?6}AOv0oFP_Uy9Hx4T(ReExa$f9(6FPlsQ#kRR72IW>d%D{M&eaqwk#u z-)H^&)@}0soTKIxKOfib*sK1J$5+e#n{xXi_ImkzULLRYI{7>v{*U)pDf9o}|JYUX ze8K;*x6AF}|J*IFKkGg6dA|5a>wR*(Jb%{kec~&vKau?d#Uonpz5Ka&xi75u$$p>k zf4sj6nIDGvf9%cT`{4iBJH#8p|FLoXnE%IqyZWlm|6|X7Y84)@t$il@UtatZczs*}H<<=Sa{<3~|(kSt%x0dkr`0mth z;>GSM;p_P|nP(0E$A15oaq9orziwV3um2}(eUtdV8E-DO-gDM7|BuI4$o|xr|Hp=x z#Qwi*_&xYP_D0#S75yQ6azhTG6|EWK+$K(IvjsJ@`{_mc;^OFA0j?er* z^@?qKg8x%5-?}^aKlS>xn}YvSuUfIzeA8}!{4*acw0UOxyl;8pS@TN=z3;p72J=dX zy|0`!&E}JR<=tZH^x*$=y>-V-4E|5udfe17|4--dIOziOMSu9?N1b_g@PFEW@aYrn z^*t`39x!rb@PB$gbm`mIUhh)AJ(@f@daX&>V?Ak7@PB%I=8ZQ6|EC@^@0H;H)T5WJ z3jR+$!`9!#|EWLPZC~%^|I|x9`+M+z>W${R@PE2K=9k&eKi-SXFX8{Roj&JiJwM(m z^G+|;K~a)U0QZ z|BE;NPtANl=Ktw>HknUj{-2ulcbWeeZ~UK{`E2+&lmVV^&b28 zAOEM`ZRcnHpL!$n`)vN78V`v7Q?uSI{!hKlUO)Vwdb_<}@PF!Uc0XDFSH0Z)AM^jz zE6nGy{;wJz$ojwW#{b0||EK2tg#T0X`n~w`<$gcb+4Y=r@|E7~-=yo+DUJWr3Cagy=wfQ zdWFsJ!~d!Idcpsx`FgCHUAK3{+3kH-r(tniID*ZXJde|U2}dxswN9&&nS^zLQfdJh}dKI%E`JAXd- zziA7;^X+txPrpy;deM(5&HO*VA7`|WcJ}345D;;$$D+k51s+-OVAf4tAIzlVQq{GZ&fE()T~d7|5M`ung6F|ej4-t)Ol^q z)0+QN4{noO|5rUUvt4xlh?xaf-%=~g$HK$CH|R=l=AYsJw4G-C-+1Hy)U3yg|5M}L znE$8d`1rqgPtE$b%>Prf-ZB19o!2h8{;zsKdt1NS{GYmiyNuxfyzTt> zKQ*5(#Z;K!|}iQ``v#3=(`K<@%u~XEV({qfAh!~bc!Eq5FIpPJY2 z#u<0`cKWIBZuge|)BY9AzvBPA%^%|b)Xbl(a`aa31}9bv{!iQMSFRfTpPG4q_`i5F z|4*H1UtdjZ{a@YRjMB#i|EFgCVf>%I9_YcRUGJ}F9eaJ4|EI5yQ*53h{!iVdOey|; z(K})H>y1`dd$T_9&97bU$8T<50Qf(hpLuGx^}O1;I}X|1aLm|5In$d^-G}x<|vL|5JCZ-y*{QsoOPb z8T_BRedCPa|8#xXjhhAkr_Ql?aQHuUMvI2Q|LK0T&S)I`pSokqX2Jid>)3kb_&+uN z82_g}wMB#A|J2Rw_!kwN?c19+KP~t_ouBJx{a)&$Mncgk!_~mAu;mvx%_&?nr&Hq!|XXU~FshMAl|5NvE-8%R`b#L>7tpBU-&?4#o zbUn>&edyk~qx|_6)T$Z$pYBKd3gv_UQ?s5g^Z(RY_VtPXQ@6GC#PNUXj1x)(|JQZ& z3BmtWxA#B(PhF#I>8Si^oxN+7D<3WFoa5d6h_Jdml|EJCz*ev)z^=UQ_kM)1mO@<`>pSrRAJth86-OPSpg8x%D8r?eh zKXqf9SI7K6HQVuj>L&L0k<9;7x3u3!F#k`TVZR^2|Eb%a(JuHub-S}{{++G=t8P6h zEBHTk=Gi%6{+~K)YF=3XSKWScPMH6vZZRo4_&;@P+n@P=>W*jU2LGq-bdIfWYW`2% zYg&T8PxkJ4Za(Xm`0In;vh_{82bwpt*Uo#a&8Nfv>Gd3MehvSp9(YNY;Q!PEF1Gn< zC%op{dtKZ$di&5TDUJX8xXb+D5BtvO9sM=uW#8WalD<)s^Iq~EFr#ZUpxcWn-F4nv zfBcY(6T$!Kc!SM*;s4ZqZJr+fPd&h{zw*`3`0)l_+%4)j{Aq8_H@@Xl-hD65k8UpU zq<6nd649&s9`_z<$J_euW8Oo|`{Dm|KX^R;PtD_d<~{7)-~8V6>JO##14ke5?q{Bl z^?!B!?2rFbGar!oe`@9fwjOw|Kc4x2BOBl2-Q}X(=$b!gdk?hZy|DAHlwSA7Ebsp3 zC;gwUpZ5#?PtE%a{}*rkpL*!I*}?y*$Jl&9{GYn#j4r|d#T);p#`EF-;*I}PcenT3 zKmK`jN@qWFrMKq)>HcW`pBmq}=f+F@{xukB|Nh$izjt=c4gN10aBA>>>MjpX4gOF4 z(wp;x|5JbRd2;@r8t;eyv(Ma9{GXcje{H@;VWo{PgwMxW57$2bOKJOj&>R0}pC5YT z-|X|nl*a$*_;^42d@`l&^UIXB&o{mCfA;yOH~!8(AN6KEVEg>kdztNTpRal^xAPso zqoemK>$zvNPw9+LGX4H?ec!&>CZ){}d2cZvbL@tE6;Zlgi$EZ2sM!e^f|m zTmRI1r};SiALa}X#QeanSC;ne+wJkTzM%IGo9}1yhrF2wSoXWW7VCPpefNvaqx!cu z$FI=s*Oa#TYTkH7{GZN`XT<-hwf?Uf4~hR%vp@b%z4Pb~!T+h(+WlevpL(_VK>VMY zd5!qLct1aDwO`*#^LULqEcaez$H)I^f9C1o|MdLV+41pzYJ4I7PtE*D{GWQc`C9CQ zdWFs7x-te`6KT&HZN#S;=Gi`|LJ(^%pc(Y)NAbX=%+gk@%?uk`XYLMR&VdsJ9aT2)O+`a z^}+w?e!TGLBfk zsoz+!F8Dw7d+WFI{#m5wQ@CX}?+5P%8deBSn94cD_!$E$wPWRCAW@bOpJ-}{Oc+wJ#jQ81=_ zy}!8;k61oek6*C&a~>b-r2o_QkM|s8|2#E53;(C*yWo?9!T+h3n%~3!sf)}H;s4Z2 zK4IS8Q{F4g^Wp!reXV&u{9nBBf9jRC9sj3Zb?}Se|I{nZAK?Gg%ghtt|J18K`8@bP z^>Xt}_&@b~8d$pPP^q{GWQ>g(HLiQ~$E)h2a0x zAFW>-{GWQ&-re@~a(}*hVX^;HvtBd)PyN2luf+eUKQNzR|J(axo8M@5DW&m$+W#%v zj{j5R0r7uoJR$xs-uOQ?$7lUtHNF%7r=NEUckT=RPyNy6ox%U9KeYEh^Z(+F|5Gnn zzb*Jb_3IxN2LGpi;MIA-|EZ_nd}Hu`>QipGCHOyGU-=6!3G4rAdo+Gr@PFPDCj|ee zu03va@PB%I<)H(E|5HajbEAwMB@*fi}m-&C{RW=W7-i+GbcqsGP-mA#gGd)SJwM;s4YeAOEN3`1n7a zpLulnzj)*S)XbZE@c03V?j2tUzK+oUkK_Neou8L?oBvZYfB4bIMx^wZqEX)X zzuHH}c;o**DL2l0yLrDS+D=I6@uSZ0=JEJHT`!Nv|Eckd_&+tT2mVjZ{l)*OxgYpH zHT&cL;*I}P^Zsb`>Lq?X-0vfsFY{*JB>qqLgU0`;{Em1YrUD@hyT-d8vm!} zeE2^#*Tee1YJ4C5FW&e+HO~+Kr{?{M|I_nhK4ZrIJG{5q{`f!bzsmj|1OKPy=QI4D zn)R;nf9iGS`|yA2?bi4|^;YxtuZ+7lam7>52S2yzz~N}t1^0Qg9`O0s&+%Ss|6cT; zbHDdG`}qL>r{irlABg{pH~vq($^N}y{-1iI{d<7_Q_KIUS^pRRr`}{gZ?gWcTJ!&O z{mZv(4fFrhE4L;6pL+GCO~L=g8~>-@kF9)fe(-<#ed)lw?BM^@Wvd<^{GYl}>r;dO zQ?q^v{!h(%w`Os?TlK6L{GYbd_&;?E+aLcIZ~ULSM)y;L|5Mktd3N|eb=5wNg8z#* z{!d-EcjMsy)Ta$>8R7rb4ejr>@qh8g|EZhU?{As^7jM@8jW_fE)cpRH`G5BudL#J1 zHrCAlQ)il2!~d!AZ_NLTH~!Dt=Go!@)ZNT~;s4@||BE;NPmL$T|Eck9_&+uC@qg;!=Hu{xYJ432PtEhe z|HT{s7w@5$ewJ9;_l@BF%1PkAC3Q0GIz{-u zc>jLdzr2S{$O`^X+iCotdWbdtFW&gSc;o-nct8AKyzzhP;kF(Q{!cx2Li^zV)MLhF z2LGoXIjU1M>G{8W|2A!_M3--m3iNtbuTnbrKYjh#$GO4(>H8aA0{^EzrCy!j|I|&I zRE@TLTdF|65AE2oL3DIlnSvoR-d;SQ(_;mAtho1J-dw!cQLLr5fEdBc<_w+F$-p&GGSn@y7qD@mBahHS2fc|I~OU=KrbjQusez z4}K5-7wjmTg)Ep20r{;REv-y8&o)7*{E&r#M|5FE# zXZ|nV%>Pq!KK!4W&zpO+ySYHVh4pz~dGlD~r7E?&#kUVHp8u!E^M1nrskuJ z@qg-3IXS`qsYly-y7)hxpZSaUzj)*S)ObPsU%c^uIv(5ce`@?5{!h*Mng6F|ePsNf zTK-S(k97Z+?)}m`-T$TgzVz)}Z~W_bSlar!>7DM~(&yWy`@R3w={_*MhuQs!UtjvX zz4T6B-#5KSWT$?AO7HaJ{a>5cGk(44uTQ%7%kP}(Iseyu$MpGr|JOdTe5wb;*Tt{* z|2qG#T;V58|D&II=%J$a@0=LEA9FqBJ3Lr) z!;Z@C0e{+lf6>NYDg_V7^$!_ytXU5Ewf%E^yK$y4|L?(;m4X*6W$X1a|4+^QHT++^ z@qcRhKXobdbojrqXI2dUuZ$f4|EDf%>(}D{bbV#abFu!f9?$x|%>Prf9sd_^{GT4r z`SE}8o?H7^Gw<%_%kJ{~Lyw+zcaiRA346ZyKizMhFaGbp&8i3g$Na*kSKm`KzjTe@ z{UY;V_&;y^fr0sd@y7qDwf=9s@qcRGk30T$teHRg!%wq(`$;w*u+nA6x>~8y!T;&; zC2gJ^{!h)kb=Lp&KK{7i|Ge#f;{VimI@bSH*EE0BfA#G}pZ-!K__X7zRE!?$ncDb2 z?SE3`VEmuDv-v>$pYC^idxJ9nPmRyR|LOHQl@^;s4Zq%AFAWpSqj9p7=j?%`(RY|EJ^Evh}g|zkZdUk9mL{-n`PA^@O|h zyvnby?FnV0-+S14zs2vDtjd*w|I_oUc1oS#|J2oOJ|OG=s_}oU|Eq4+!2UkY*8kQ0 zZ`Q0?SpQeedbIdIwbuVtcWjiL|EKO`&HO(#zK{8TI$uxoUCjSecenG|&!7H$@N#WOvoe}T7pywRyHTB*(W=!`y|Zdoj_R#F+q+Nm2GJGkrg-E3Hm{%T z-MnR^sA<6zKR-SZ|EKGt@qg;}w%#oMPtCkQ{GYm2v(tkAi#PsH-MV>l{-5p-&HO(# z9+3He>UOPK2mhyTYd@bc|4+^9!~8!TpZSQa|EsQ0sZ8*HdcWk_JW=NV#e4qe!~A|^ z+WYr}!$ZAU?|0IXA>Ou{GVF>?}tOLB-j77 z^@H($>Xw;F|EJFF+BWz&ev;PcJP1d z+zB0n|5GPyK0ovS)E&=E1plY*G^tB;;)2!wd~>X`9$e+!$@ZUc;Y#nE$@#(m>G8Q| z7X<&OZZkCz{GYnrw64Mbsq@e47W`kl@qh7dTdvSMaenvU|Fk{Nj>r5zb?&)cg8x%z zPwx`^pE~!V?)?3)Uq3#{en04)xTJURf7-vN`8nqQse4`AC-^`0=@<71{!cynqHe+e z`RijI3;!2yvsK>Xi~XOrk2N2N|5FdN^<$a;7jOID-uSz>&Hrh8KRe!@kLP*!H!p|( z({>vF=Y3I^;Q!Qky-VxN_3fu$(k*)Y$LGCA+4EVt?m2Hf-&fB+>&@fwe||jkg8099 z@reg4ty=^|=p(p3~cGlZ1`?veNd!Lsb{GT4*Zdz{ef9j6Y6T$zfIX?bR z-N#;E{GWR0c}f4L9&DZu|EJEI)*<*mbyr(|82_gpdqLOW|J38{{f+-q_p{fB`G0D> z9{x|Q`G0CWCH_y{)z$;X|EarOmWc3wYW(SKgRk($8}9h)GH>}m-QQD(HD$g}A*Kg^ zQEE`N;Qu<_@NDpaW1dU;KlRgZy&n9ZdfOKV!~8!rpRd_`j>3DceJ1$6ZRP>*?=;+- zd0hBEZC`612>+*MUK##R&HOX`pL(mUhl>AGZ#EBv|Fh5hgE!>y_`i7L|J3*-{GXb6 ze)zw5i%r7^Wp#08}0G z@BQ&NK7aS#W*+aA^(T67GM{$d^Od}}7W+RPpZ)QFYW&;{bIW?;=kR~pj^D%osdw2t zK>VM2`*;5e{x9D6KlQHflm1V=`-h*If3#SySC~)u@weXl?RxQl`ugDftpBU#{P;gL z`{V!Atar@(KlLViJpNC;*5=>g|J1zS@qcQ(9{x|)TWFpS|EFGJuh&bT7JB3T@PFFA z!M5Z7)Vx2;xA^m89w2Mc>G?Bn5C5nAX>5-gzsLVpbG;unf6|+;zwGUgc(1pw_XXEH z;LUdYpPnDb!~dz}|J2M2#Q*7hY{&n_8~>+f{wDrU&HBOSmyWf~6EffAz3%Iy!T)Lh zO*W4P|EJzyUJL)H{_K-|!T+gu+vl&$|5Gn2{E&H2em@_3;=$nmbboKX`r_dK)KkX~ z3;s_Xof+n7`QxJr82q1l(9G+C|I_^%a^+>g|EUMhyp*+d7pX^_KP~t_ zb-%OD;Qsse9uv*NSMEK;RZPTx9^{q(W?wMVJ z|5JZ3xqI+`>iILz4E|63OW{kw|EWJ*w>tPg^{Tze`G4vnTW{CaTg=zL|0~Q_RBZi( zxBQ>>f6vyhHml^3UyWy(aiSo$tw_mC5;k#rr>M9yrYZ zEAA&36b1jM$3J50`!fGeebbVq!T+i6UcVvuKlMCY|CsrI>Nj@mk1BkBLPF>Nc;~@r zL(K}_i}xN5{!iOK+;=$mKlQ@TzKSZ`Th;epX5UXXeo){T#=cn<1 z>J8@a@PBI7x5xjf*^d8HvmO7Z=I>d;{J-M+#lNp%{$Fvko@kEhZf5nY=dw$}D#~yDz`IZ^p_&fZcu7~-N_&+u4L*xI{%k>9IE_gT|Kk=*^yg6UNr8j!x|LWg*llOLee?^bn?2QM+|LOS5o5cUA znO8Zp-|gOPXa1kI)A&C%^Zf9C>aFHO@qcROOXC03%ZvS=dW*dt_&@dLV*jV-%fILN zzj)*S)NAbfFa9sy881BGz23Zj#rGfdW_}_5Pv_(B1Mq+9754oe|EFG4JpWI{!4F#k{2vvk{z;Q!)X_wP?7?EfupS9W&6O8b7F_uJFn%QtNf^Z)ew zunmhB2LGqumrforEcie5sPakwr#`=a&EWsk9doJ$|EKPps1^L5IP5Vf0iM)*H(^NjdEHLoxJPd(hukN=A|{x9Cl|5FdM*OU2w-lMXD z|5N98Z4f;@DJoFs)+!bJpT0g@7|&q-pT56!uz4`}KXt#8YufK)OBU$&qm3I^iEi9c zy5Rd2uLtiZ|EEs(e(62L)?>BLR}1v{Gd+3Pc`03f>G>&*|I_E!_^@F=o>wsa+A6{O zF&_^9r*379|5In0pTqyD@qqZhc;o-n%n!u>$(wZT*eUowHU0?yr~PT>|Eb4hbqfAZ z&3d%>KQ-P8{}*rkpBf*B|BE;NPv>WT9sV!g_&>G$pPJ+0|I|F5`G4_d{-2upZ}`7> zpwI9Psbl&J{13_?qnVi|EJEi*9-rro|v5*{GXcjnDKu)zWkq>^_TH~YSzoe z|EYU)w(nP^?@Vd@pN`)v&%B}eKlMoShWJ1A2=jpWKQ;dAoBp#?I_|T^*!_t2sI>Kb z`{btjwq7}@^W)Oz?F~(vC&>Fde*Cf7IVqj))BdkM5x*Hf{)i5#{xE$WA6_!P|LDBD z|7Z8l>zuMZ-T!g_f z`qJ0?P4|2!S4>^MH@*LV^ZY7RPI*2RtER3eTp?}!-%?e|2LIPFQ91ZO8vm!RRH;%l z{q0A+D_5=@eQ?ghMeFXV7{1?g{Htp{R8)Cwh2R0{mp*);XzUN=g9l`uApUP|?ef6` zR&i?(w|HT{sr)GX0^Z(+_`oC(9&-%ad#{b37 zkN=Br$N#Ch9{iu0`F8j}Js!V^|BE;NPmSmM>#12Oecx}h{Qj_g`8TtRuAf>d_)7V| zFPfeh{2yKr|M%!$CkFq=^Tq$ESx*@Mr!HahweWxH(xppBb6>ivNXIK{^So|sa;z(r zDI3=R)pi>Hr^hqD3;(CCX6qR<|4&`Q*1yI7spbFFJRj!&sqv2ZKQ;3M@qg;7l`4e! ze`?-O%>Row{!fkXYkhudHqZgP}BY%1OKPj3%`i}Q=e46T=0MD0`pbO|5N9im%{(4TiX0U=KtyVH2zQB z+SXUb|EV+V4T%5K_2RSef9g&rRu2A8&$s@`$@zckhNspF{!iWb)Ox}HsoR=A!~gaA zx=Qeuty(k*{x9D6KXngV@0Rs{)!iF4kC^|b&TiT;>NszPzaBLHPv_J8KQ&$u|EK4} zJVN}Ro`376&4T|^v!3qMX;b}vHn+czNlZW6yH%Z&g8$S0Sq!sZL& z|8)MG7R{oAiOJrbnl%ajPuH8-^t9mr)NPwI2>wrvzhnNNn)BiR)SCaN`$b=S+k|7= zo3@NTxMjR|R@)BI_cx96=I6)eH;(mY9wPov$M4dxVRTRKXutkOWs?3+&o9%yK=FU- z4(5CDf4U#|Qv9E~b(zw^|Eck*_&;@9^M3e0HS;R*e>y&o$N#D8pHM#dKQ-$G$Nzn= zQK4#d<)*I-$9(c)@OP~nw~U^7`77@RwjT4U8~*NH&phVQ)4%k_|5a;$B&G3xclLWR zc)-lIN&lzr-mP8mf9kdan*{%-^XJ>&@8SQ{LyP^Ny2rqbsD4A62UvW)9qji(z5cV$ zyHS_A(FHp{@vfI&J9^;Fz241xH;fkCZu0<(AK$>{_2K{2ZO+IF{!iWhtgNV2wVl2_ z=bXIY|FpgPIZ6K)@8_Q0>ic&-J1<&&#TM`E$(^Hr4%zHI{H*NY|Md7F6FUa~r%s%i z8T_BR``KB+|EUYk&W^tMY>nS<8vm#JOXL64U8d#)|EKPDZU=rpRk&!u-0=Iep67Rp z?DtpRIp<{s|EKfi+j^U8$==MT+dc7Z zzaHl2;s4Cs1^-Fg-v;{j)9w2DfAfa-7<<0<_tV~kE=)v^Jo%dU5c5^`y9V!(7ZyZ^ z2fgAw;(|m}zS%r)=GkQ)_p&$Zwc`JDJ@~on-ks~)xxN=?zu-OAJR$y1`*XecKQ+h0 z|HT{sr^b`v|Kg4RQ{xBUx#kH!AH8?vR9z3;S~sOwj^dv~AKF**6_stl^k?p@PC+|QlsuEIP=x%Vg8@`iFaNN{!hK- z@1F(#r)K?M{GWX$AN(JU|5NjMBmPg#=Y#k^HJ_j2|J0iQr)E7{{9nB7^G9zy(U1l` zyw}<1d2@d6>W#nKvb7+k?ekA>JfM9(>dohoHb2FCnSI`6pRanaw9g;$e>Q_C_(RSA zi}#eQOy9o7d|;!BZM@h0{k!1*bpJMd{X_77YPRG5)OaY?|5f9m-r3dYSQq<0-)@cn zQ_KIU@qPF|HS62j=i`2T+sv=w|MYzJ+xoruzj)*S)O-K+Yw&;SJwN^u{GWQeJ>KT~ z`2IV7{1yM?jmI+|kka@+T_4-=fAKbdaBP3O-Z3TqTCDT!F^`A;)BbzS8;+g$i*Kj# zf7*Ya^*Hl?@!mJ}Yj3>Y`07Wz@qo4-s~?~Ffwgi!O=^zh1oTy$k0r*4GbRdHU<#cm?w@ zzCX>ZAKecc`=jI2981SrWnZ7>bG%pD`?JEm_j|J*9{x|yZ;fro|Ec-^Vh|EibT{lNce|24Kh{!fiZX8xagW^*S z8vakcz_#Q6bUyh%^%DF19sd_^{GS?shyPPAH6LK_KksGc?`)g*YV#5JKkdK88vm!> zXxESbQ!laOjA(8gp&%f7<`@>2rerQ@=6u z;^6<(51uh5_&>crUp=E+@PF#Jrt}W}PyPP&=LG+!{<-Mo;Q!PgtWEkqHS7P{_m6yi ze<|FtJNQ2}zQX>uZ)bg9vqs*m2aNyI@mL=g{}*rkpZfLP2ZR4pzk49*|I{mOo*e#9 zy?p-{=BF0>`3h}*6#h@wN8|t03-^B({GWQ!rw4=oi#PsHy}*1R{!d+G>vvDQXuqF- zvH3sye&AhX>wnw7Pu@%H`Q!ie_=P+7nn(IJrK?Z*!TbHq+k^kp{xtqi{oaN`gtk9ny?$m1@0ZMH-t}xLZ~SBbHD$aP+x@`*>G4Z#-Y5P~y<-27;Q!Q1 z?fx_WPrbtCm*M}s%@5)K;*I}Pvz{paPuDO1r`}{g&*A^n_&5BYn#be+)ckyj|5LNR zY?E`Fr1aD|&Agd+hyT;{(D*;~Zu3yg|5M}5nE$8VVm|B6{B{YO85aB;9;@Hv4&GcZ z{!jbU8{W+J?W`9&dq?M##{X%5JeK`@?2Xs6pP#+)a`y9eO5^|ZczhoIPtDJ#+xPeN z^X;~uU-5ss{+)Keng6H8`;D1BIB{{M$AeF!YtJ9*&GGkbAD+@r{yNf|^@As#JSL^< z7mW4BlO38g-g}$*%@=N)=*_%8{GYC8m+g=LQ!|ed{}=BwzCFjA^W*>g`PUH+@h5u9I1Mz=q=DXwn)ObexpU%%bLHwT@Z;1bkH~vq(+1`)% zKlK)S|Mfh6mLH$jt4Z~{ym`IKG@0$aq1gZF@!X#^eedz@H1q%B*NgvCUH+> z1^!RH-u}JD|EZb(hyPRKKmWPvA@A)64@H~zJnX&E{$Av*Zyxbxec=24^QiaQU3(%s zmiMadJELLspYUE|KCpeeC%u_RU9HDc-mL$N|9j;5$AbS`vw3qgWAf99wN)QmT<_Mq z3N~!t9?iM*8SgEtm+`sqtUG_y@qg+eW6gt^|5Fb&Plo?f%m1nIclf_!om~Gn-uORndp=`k?oNE$ zVs7wy114lg?VjA@J=%O^#U*>aN12cO@{3Qr@oh`X?DrlrK0Ek79gpq!zj#0V)`3L* zCte8NZ>Y^r#Q&-BfcLdIm>63Ah2Z;okG1tdhaU3oGcM`>v|au$-uOSY=KsYT|EFeN zA^uP2=l(`hM2(xTOD6C#qMEsuz?l zxUcrS;Qd-Qs2u#CI?>^@F#k{8J}V;{^H&+)ziW@q(Y7Wh6b#uoZ*jwYj}?sRn(A|g zRow{!h*PKKx(2@qg+tZ_xZ- zyvLgVQ**ueKQ-Qu`G0DBAnX6Cc|Q0*Z#*A5e|~)PU(Ekg4=}HY|5In# zdd>JhHQp5er)GWVNjD$semQy3s=to)sNCG(|8#!l+u{Gz_(J@j8ebUy{5pMJU3&NJ zoSm|Ny3fPA#*fGP+3`-F@0ULR?tg7hzn=6?KVEvXo_73t2IMAEdRXVw9+I8<{RVFt ze|&nUd&2Zi_jc)>?hDiX-w1ns1W*{>uH1HT&cL9_d~__`n+G3;#ag5#OK3fByAD zMNOYQA$UO6XRS2-SU0X&HOl$tgTB3vtzW#q@cyC>mC6Pm$ojyg&YDwnOlgFYG;>C?FVMh_WkAm^mxtxi#PsH zjo-un#e3XosXd^^Y`;Ip*}wNQAGymrviW(e|GTD1h2%Uy^Je(J>wc?{oCj!)|MRx_ zfNPq}_WeuRddB!aJsuB;|5Gy`aKcNoQaY!}u`XvG?WC9P^zA3u4fwI~u|D2<^NV-* zcKJVDkNlsyr1>EHpZY}nkoiA#&5FtOf7QJI@PF#sRg>%gs+(7-6umq57C%3IU!!A< z_nSWVX5Y@&3;s{fzkY?1(HUEA^!InY@+E@*^Y?qXr2kXfxaQ#h^!38~3;(AsZ(fr5 ze`@?5{x9D6KQ;5y@P9f!jsH`#{xAMd-Kun{;Qw^}?dJEf9lLr>jeL& z{TtalN#_5l+n!Q8_&;^GHZ6ny)A@(CX&d~XdSJ_p;Qw^JnHjBu|5M}lnE$7)WgZXz z7jOKZ8eiG{j)~r_TQ&{;PurOXi2qZ!we#cu)HyXz3jR->!Mw@bG5-2@JE2VQf4crW z`+oP=XCwUi^ZpuhXt+1;FZ`eG2ix&~YPK`~Pc8qaZezX||EFeu{GZNG=Yszm-KcT!f9i~ut%LtlH?{ea_&+rs5dWvf3+7Zf?A<=I zVRYt^&%OKg=^Wiwc*whst$)D$KRv##t$%?3QzvZwU*`X*a|SmL{!iU)Xv^UL)Lm`; zTl}B8$wZqMX8uo|IjvXlf9ifyy9NKJ?tf1A;Q!Rw=O%*xQ?s5d^Z(R?%=a<>FW&e+ zb;5rCga1?K+j_P5KlOk~9fSW<_qX+Nb4zUW?exLr{~w#9&hV!9J_v7pVj_8*SqUQN&n~9TkQYh&HO)a z^GeMBQxCeVCx1Wejc2moFZ%WLGjI3nW$zqo^J8^~yq(hcKV2{L_Ws*xeoEv2v>m^P z|BLtBR%lAH|J3q-YUcA*tT)FW-_QJChu`k??r&ZX|EJ^ge#HN& z``h*6|J3q-@&2jfEZ@%Y@PFElFU0?;S>G4`r)GU${GXcph5ys_^ZsQ1pPJVL|EK*2 zneW8^shQu0|BE;NPmKr6u5oor-?Dn9H(qq>m6v<-{y8<{GVeb2_0eGdC4N1vM>Y!n zk2O2-eaF(q z6aG)V+PokBFW&e+HJ_j2|Kg4R)AL9n;-dn+k4~DrS{!iDp z`}<#l|BE;NPy6Hf@PF~f|7m~uKW)bc;{Vk6KK!40-%o!;_&>G$pPKcF&0qL-d>{T# z=iB|S-|XvSkM|bye)vCqz2W`LZ~69hcD(wB)_b!)F#b=+TVby!{x9D6KQ&(;_`i7L z|8%{49*_Ui`O&@`Fs5F^f!ZN zdG9c{!jhVhIRNCzdsL{ ze=<+webYxD1plY~Z++*j;Q!P&yzy%Ae>(qNue}=lpZbn@FXPu1>HT*3Tl0heQ(ybR zhr$1;Z(p)D_&@di>vshIr=Gj{6Q1uP9sjLQj^OpYSDBw;{-3t5+!g$u_iFQX=6x6H z`tbq$pL&6LIsBgFMa;6@&A2|0j>SHabvu zjQ8Kpz1QAvXL>(>#fA3$aGLl1=S&R#Pmh1|+(EJhyRN={!jg}-EZdq zsTc1*991s=z8{bEBJUmhu{S;h|EKdYPZIy9USYlm|EK=wGuv+S|KiR3KXswagT()- z7n?W1|HYg6e`@w;{-2t!FXsQn8~>+X%XagB>NU1rF8)u=^LgmqpS^j$_&;smXkT9s z4g0V6Ci8IkKW$%O+wp&D=5u|}s8qscWF_alnV*{3uZ%aoCws;T-pmvG{h{*STWucN z!i5#Rx0wIA`cUPR#{cPj%v;0%sW+Hc!~dz-KCpCcZ?-f4Pp>!LZR5yOd^_j6=h}MS ztmlgV)Ben#!~d!AU(Em0`8J#XV*Z~RkB9$L;|=kDYOVhp?=>~s`txOe9sW=Elg9t4 zIez&&vr-!Wr|p}VhiLv!jn^9VN1ivY2mVjz-(fx;|EK2XdHkOmFNgnAZ?(Ulsrq5> zW5=_`|LJ_6+VSvz>V5Wj{GXb6iugY>Rmt^Qt?_?q?l=BV&Cdh)KQ;4)@qh8g|Eckd z_&+uG5C5m;^~V3{dU!wJ|J1Bsi~ox^{!fjc#Q*7j(D*;~2K#!!|7riV=Ev}V>h;za zuesQ-2j7PO)AjN7i2qaL)jnuH(|gU{&x8Ndb{hYu#uMWI;*I}P;{)-3>J8=r@qcRm z-U$X;s11e)}zM%squmMKQ-Tv zzUp+h_a^)I7yqa2o9+8A{!h((XZ)WUe|c~1If-f$9}0eMlYKv(-{OAnjrRQ)|EK+T zm{-RCskfWYw*T$D?UVh%|7rVXTi+M|r{1{xli>f<>&&y`|I}-@?+X4;&Gx-3p785o z{@))vpY$%=yfyegUH_Ub+k*e=zU{%_|7iT5dh`0V!T;&^36DH5C-^`8zU{Hodj$Wd zzOZ%e;Q!QJaw`S@rykP(RDS=K(C-(s``PdB&Ht&}_iPyapBfK{|5M`y@qg+Ly-x}L zPo34bUhseFrXyMf|EF$c-irBu>KyY?_&;@l`8)idTK-Qh|EC@>DVN`m`u+na=kfQ` z-lw0LAN-&8A7$&wF#k{8_srz{KXo7TfcQT(ehUAm#!un@)I-L04E`_P_&+ti3jY^x z{GVF>Pt80!{GXcb_&+uC>F|H*p4QC&i#PsHjSpo0U%am!u`6-&6VC+imt$TG|EFes z8~mSosChR0pPKb&@qcRO6PD_|FY#XGXM*RW4^G?f&Epr&{xqfWf7&14hX0E<{_n`m zPY3_U{5$-gdW2ms^Z(TNH0J-s8~>-~{-vPuDZno?pF-{^i@p*u2Bv@B7J{ zd51gR`Pmz9I)BG6-n>8W`sG(|?$^{>zo&H9&VQsd{!iD3kL>--zY{fndus86wH_=e z7}_Fgxa2?HgNHPZ{yg|+N`G?PU*4^{H;Uf5DJszMDx6j#I)2~r1^Rx}zDk)e|4-lF zI#ewiJ-?}R!H;$42EW&&PSXFix$uSH0lRi=5&WOJO?JCz)qQ1s|Lm@*-X(oL7xVMR z{B=%&JO};?{}*rkpPKn__&+s|$NzovS=lfTDmS}B@PF!@taicwsqtp`KQ(>~|EJ^O z*O>q3+s)tM|J3+B{GYn3%~!+!sqtj^KOK+8|HT{sr|!_KMeu)Wyc_;c-8(BM_&*(g zRJ-ip|J1`;+j`jM|J3+B{GXb6fcQT(^AhoY@y7qD`?hW!=KsYT|EF$epI77m)Obt$ zpPKc9@qcR0kN@+w^`G&7@y7qj=k#mUF8Dt+>qX=L)ObStpBf*D|5M{5FM0V`^Z4Bj zZ#}l%?oaNssg3{h>#^&_|EZZji2u{^IUoK{-MMA+;Q!Rkn>P>sPu<4u2mVjZ{l)*O zxj*J=N>3p z{Y%O4??dHsrK6eM?k}p;vSjdp<;|0wb>zOH5oeSL9uVJ$|9fce@xcSq_`i5F|1aM7 zKQ-(5GXF2$_&*&VpN9X7H~vqJ@5BGaoB4m<_IT$1#T);pmj6@Z`|yA9#{cR5$p5J$ z+aLe;dgHQ5|7VT=oAN{1;Qu&2{x9D6Kkd)`!vCr9e)vB%z7PMW#`od>)c8L9pPG4$ z_&;@I{t*A?ZGPwV#>YCW&-~);zP*C^w6hx@Yu1Ox|LOXxRZ99lHSfoN&%MJE zApTFydc@5C)AQB(zv}k3elq?~jenf>!A!rub!t=&{!jO}e(gG8{-2updicMZn@$KG zu)fW|!~dyI%V-hS|5Y<@j`@G;_RX6F|EI?DG5=4;Z(;NNnE$8FY}_>XKXuziO~U*? zUH>Uf8-@9Qdj9oWB-j5{E65_@PE4A%u=O-|5LZI?+5rlJzwT|;{Vh&YPsOpH>k3pSt(7F2Vn)yG=>@KlMQKeE2{0AoG6sKXqbCr{Mq8%-_TRso8(n z6&ni|p8RC+eFN<8LuU@%;N5j{(*J3DuXA&P|5M}pnE$69aDH4=LG+!W?rBD{i|;uK0QD9KW!g+Uef=m@m2QwHQ&GA z1-Zfh>H1h-)&4%$x6}6byD4q!d!#h}FaCJ^U%c(_hkbv1nEie+rSX4$eRe+lpBnFn z|I_P(@3Oyd_TvvUzcuE{H@%tHcir$eQX2oK>%ouV|Kg4RQ;)IrW@|2*m(uwUzwC{_ znmpqr@4j|@_P31Q_%Y`H>3Z>a_&+uC_5Qu*Ip3eQ-+g#%{-3^n@n!`-JnfI?eE2^d zub<6JwEumqi|7AoJL}Wp|Ge$-_&+s|A92egetzaHUN!OIlzuk*A#Xg|s;UpB^wFdD zdvkxPuAbw~yh!|?&PU__;*I}PGoKRwr)GcrpPKu{{697G3GsjGe$#sd|EKO{>sRCd z)cx)I2mVhz+}5AQ|EULG+9P`Z(p$V)e|g`4o4vW8_&@E>dcgQUwftYa@qh8g|HXUL zcUSoR;{8%*?%%w5KjHthe?R+r$N%a5kvXD4@P7|~{y^}5bw_1H&qik!sxO~^TkwCZ z;fV*FyJA`Jf9h3V9uEFbz4P#w!T){z)BVB!?fvST;Q!S4Ap9RD2>-X{==Z_@dE4i0 z_&+uCz3lVD!n`u~htH2$-_$-|^j>d%aOj+#-uS;c=XdvBYoF(B?%CCw^{gt@FYso) zE&Ke_dx?FXWuK3FFHO!*@y7qz=d0f9?ei;Jf6cF#_0Md5HgDEjv-vIF%MN`L{GaZ} z(t}^y`hyvT>P0qh2>+)pwC(sm^@=Z!2LGpCbp)T)$hR*vZ)l%SdoM2bf7%~Ei2qZs z|LXfN|4*;qW}BCW|I_vz#r{t%{}*rkpI)!+-zWWFyzzhW#{b3J{FC>#?|upXPsgXv z|Fe`|&-Q=*%=&`fJ8V1tPy4ezG5#;!d*=V)z1e&t^Z&Gcs~yk$!(v?z>k*re@WvyW zpYYynKG1wcO5^|H$FuoN-rSD^b@zC0w0V7X@7b}~@3&nK{!hK$eC3&q*Zcl!?EQUc z+bVC~|7YE>ET!>(dOY6K=2Q80<^kgWbbWk%;Q#b|Y5bp>^?dKCJI|Z#l{UWMz3LlV z&(PMg)BZI6PtE$meAXRr{HaL-u_O4uc-#APk@_WDPt&}Q_lxV++x2f=q~kriVomUWx*qz? zo8MTZzIVksX6<=Dv~COY^}L_iv^V%aegA)X7whc~S)_h*=cmE{>3Hvi^?A$r3f z>*1Z;e@LG8PtN1JG^OqOe1GNx+WqmyGui#~PR@fY^j>@DFwfV!=)fW7fqF0h{0Qqe zd#^Iju>7>+^L4#TZGN0xzc=guF1V(e_hP%BHlNk|{Vj)?FX?^f+@$~0@y?z3Veo(I zwq34gefxaf-yWykZQoCNd5_6@F8DufpE5e>|J0YAb9eB6>Uq=82>ws~%;ZtQ|EXV} z)+hKs^}Mrt@cW^By?@`oYKqN+yVd*GMK1;ar|oaASrz=BdfDFHVg8@Ga948u-+0^i zA3xrQw%vTPKfeX$1Mz>lp2aqg4*wT#{GWQ!-h+I9^y3xU>w*8%`Bs?++3@B^`TBW; z9`wf|Z`POI+;gcn>p>5lv(mfJ=KXEozc!^uHrwRA*yd60zI2=SB7C3uKb;>hivLqH z{}TVFF0%I%{x9D6zhiwk_&@a$n>RN3mhb(1%r`u;`6utS_WkRelYfu(SGJz$pWbWi z>$l_HD53kY(tOV^|2^J&wLKpHr|p}~!{Yzcd_Tqi#T)+@Z~UKn%a?x-{x9D6KRuuI z=I!u*@y7qD@qYL}HS_u^wm#V#ABO+acCHWqr^crZe6fM|X8U=y(#D3~%)7?_X@9&J z{!hKy9)Igg&Hee%y*9M;-el|lmi@7nH+~TRr{{~eTlPq1!e*8QAIIO@+_JE}H}eU5 zeb&*N`GjRkWT*7nCY`^KnYs&(Gex-uOQ~A3UD@{O#MB&xilh@#yLe z`uh2}{+&JgdvpB{pF7Z7{!h=3`-}fmYyMxn@qg-7wm<$a-uOSY{9nBBe`;QD{GYC$ z#{a41|Kg4RQ{&4TR68%F4`omHUT0qYpEq3K=VQItx8`2ty}`a;;Qw?z>+Smq{!hKp zd@lY^z24^I;{VjE&D%5oPrYt$(*Jqe`q}uuc;o-n_+b2>dYyeg!T+h5pN{`i^WQ`G zKRy3d=G&JoxYf7QFKoEYd!?<{eanH{y;s|R58?lGyiK+p{}*rkpL(nP`-%TkZ#JKg z|MRwg|M7qE#{b3p!m{@z%=`uKhY!U6saYQw|EFGK-;cNEKH$C0z90WM;6d-L_Wj@N zoj3FSI$ZRy_eS%8_&=S0gRKwG{6F;?o8OB6Q{(+Ue)n;Iy!@Z8XQ_EU{GWPBvHw%A zvw5v~w*Ier?WUyvE1Yv*@PL~(Z;al(`Pqc}<#{g!|EJ$yJ$us?(K)5xO6d1z1KTu; zy0x6|-65|WzhCq2JG5T#f7-uGzm~!Osq=d`3;s_n|EHG!Q#b2fKlnd&^F9rN|5LXf z&@A{rb=HWsQS{q_MC}Ss1b>!mzi-}m@*?loV3Ebzx{st&CV;m`<{^<-8pfU_kf96 z!T;&{Y5bp>d2hAXt@Ztx2luaU*LjaLKenmL2Jhj;>;LNU%(G+uU%c^uYWY94{GXb6 zg!sRBuc@%Z&)3)1|9zqDPVasbY~GalKiz+PBmPf4)chmp;c<_C6 z%SNAgGY=5|r|rxO#Q&*>Psj=WFW&e+HJOppV{GXcpga6a@^q-jYf7;HxKm1?3@qcRkBK}X!>x=(W%m1nIo%laB zz7GGV#vk?=_@nozF`2>tY5Pc<&w&3^4>b>n|5Fby_J3;Di^l)O``x_X5-(r&Snz!K z%KIk#p3>)C_lGyvkN?yDJ?-M~dqXmB)>#Xed!T)J{ULq&V|5K;?7Urk*T{yKsKBIrTjOc;)&+%rS z>i)OR^=5t2#;;CGY5boakEdb&pPKn}%>Ps4{qTQkJmCFzU+9f5!~bbJ^9AvLYPRG5 z;*I}PGhYz@Cr?4+|GZmghWUT${ERli|Ec@8>KOc=dPuv@!T;&_!`dhPpL%fHj=}$V zw`m*vpSr)zZ^8embM5nV{GU3%wSB&9{!iW8=I^lnZ@lq;>YU7G!T-e@|EDf!*CO~o zb=M9V!T));P5Qrh)`*??b~Jq|EFgDB>qp0kHr6}@qqY0HShn7Yi4;5>697# zpWiQ=&&T{fb^3h1|7)lFzFwX4?6*lvuGjzTotvN1>GSr|=kfio^@G#b?@jOY?+*j* z>s{Bv|Bug&cl!Fc>GSvgm%mG&|Cc^rFMYk;!RDLe=O1LRPrTFDQ|{e4b^rA3J+tlS zuh{*@Gsio9{pEE3m)_~#@Bi9(x%m0h8-Ewyo<2XYPPOVO+nJvh-@j~C^FTKL@0mM} z5B{%IS^R9VfmEixhKksM!U%Z+Br{?{Q|I_m;U$av1e`?mZ#{a4DefU2${*?89)yyYc zSosFO|JBQt3G@H-^}zbR_&;@??a%x_wfvvDWBJm-|EY8B@%TS=wmp7g`zyWW|8zb0 zzq{X>>DSl6=4T$6e}y;4&wuA~?*`Q>Md$ap!tW3L!h2Wv{cUk#_2B<>|2x-j6rJ?; z-+cQ?=A{O|b(wc<^KY#Gd*hN)!3Q!AaM^2@_;$S8e_pvbrSX3{KJ)wVf9f_38V3KT z&N$Wne$Lka)$3XR)P_;5uIGCG_s4kBa|Om$CN`{!d-cj?etRcr*V`&HE4kr{?{K|I_)HKZyTR=i9u@7cLm= zuRp#p{_jyU#{b3s{l#y`yQ29<{GZL}3Ldar!-m2CsjIZGzkjm%e`?;p_`l!odNlaI zS~mX=|EF%5SwGDG)BbtgGQ<2ob+zHGg8x(3vib7(KXvypZG!((53zZBlP2#kG(!}; zT>EpnMt9`z^Uj{$D|)l$C*EDo?HcX)VUKryvH#QYdQUaq^3pEf-s|j~sP_#!Q=0XE zwSUhk+0g?Xw)=Ma<4W678vm#L3#N1q{!iV-<_F^c)cn0D{!h<`zbD22squl#|5Fd0 zniu?^y6-gm`xx_o>i*|<4)g!ir(aMI{NGK{BfWIOe}C(ZkHh~R+n)4)@y7qf+y4I7dw^ZP{e7@^ zf4hGCpZ4ec_&+t*hyOd)dBOjwSe$x0qHT&cL;*I}{H~vq}_2U23 z!|ZzTf9m139sj4sU*iANJ+4Ru`d;sDw!ZEyBk%Fld@UM_$k+I;HSVZ@gglNAK|NVehwTm)!2n*VnxRZu1^|ao6aBCbxR`H}8l4)BU24 z-*;2W_Ga(jn9_spy}=v*_w}~xQo7^q*LWA0x4bd;D({4OOZ=bi7k(1|7jOKZUysd) zJpaJO-t9*<4E~QbIhp_0Y}A-NFAYDfWNrPa^7$P4I{3eM z-N55fPbHy-^CALZL==KtyY9qZ58yiec0 z-MoSMU2oPm#Q*7dH2zP$-F%y^m+ig9=7ELzf5rEIqpdd_=KmEp{saG~`?b;@Z|^tn zr3VfM|EJ?KZ_GUCB3UE=Tp#oQ)a%T9Q&~Q@PF!$?fxw{|EGSx*#D^uKRF!ypZde?p9cS@er>~-!T+gmo?FQC_2XS} z?ZV*yw7pxO+k*eo^BK|X-r)b#=j1*g{Ga-g({JSKBVT>n1rG)Pr+)L2vxEOrKQeAm z@PFzLC*|3^xU2H@e*I{2e(-Ew%N5@qh6)|Ll)nY+e=rr{l^0saKf4!T;&s|CQ$P z@PF~f|Eck=_&+u4P2>O6OU#qt|I{n3@qg;|_Wld=|B9c_V*C0G^Z#OP-w*tHm)h5B znE$8eZ;k)c^)I&fUzq<_yuHvo4gOE(tVj#${U(`ud?Td|I_v3?eKqU=Fj2(;(gp@ZTx;Pe-Hns`zimY=K10O)Ob1k zpL)etMy*n|5J0l_Vaa0f7*^;$N#DEzK7=B;?2(w_&;r5Q|$lLOKdy-PtErm{GWP@9q;Am?o5>5 zIXn0~yx-b)X2tsN(bvoG^4`qPGv@#Fcsw8ePmR|c@asLkKd%S=PsiVAzS69m_Y(8} z_&;r5YClil|J1Dai~mz^weROPTQ8A4bawD{o9*YZDW5;&z25xa$QvH<{qcX7&w11v z|7UCWddvUm_;mU9Px$fHY}p>Q>i(qn+O0dn{6F8{{2%N8>Uvgh*b?Udsh6)$`akvi zi;JRr4!x1k@5`QgZEo;?>K56V!T+iIv@IL_pL$Zi(}Mp~_Zg7%f9l@-TLk~7?$+nD zF#k_o(6gR>{eO^n^O}c)-^=K6YBXc^hu)ce8%F)-f8?EQ=Q|_w&H~TVxf0m`~CBGk1g`I&diCboWI<=pEdqZ&j$~P|5M`)r`)tUr4ui$@g6#{Q}BPN$f|EJfF?f5_Sc=Lz&KQ+&{;kAnB>)O(n%7mWYY{;Y3||5MBVsky)Szj)*S;*I}{H~vq}@$i4%c0T-{t{?Bm z{6B4H{a^fFyzzhP(PNVSFW&e+HS_tH|EFd?AO250a7?G*|I`CU+xg7@squZx|5Fbc zl^Oh>dgQ32|5J||-9F6!^Dg#(@y7q<{P1A#e|SOspL&>GFaA&6dvwR(|J2=vwGIAn z>IDx5|2KGWlL-H(9y+vH@PFz7L)u38KXqou8d3G%N*BD|`^m-QraV#5q;ARRnS0B4 z*Q*glEt{70Zd<8TRAx_^g0fwn2p%v|w_5Oj9Tz?R|B-edP*RoY`t~;%P!Lp-A|MEY zO3pMi-A&FkISGORL`1TRIS0ToJEk#?X`FEsvkcJW3{B1gW*y8q&FKHR-m3fQx9WWB zxX$`!t+Ni-+Pik`+EvxvcK!N!g9mKfv_bHH>Q-%<2mhzep1(!o|Kv09Ecib)^R4iI z>LIosD*jJBC_VpA&Ac!CU)=b=xbc7L{C4ew|5NAXvg9)F2<$EGcky<;!+W?o&LGiPNq>;LNb_{G->FZbqn%>UDNd>Qlq z)ObGppSo@1l>bw=v(KCHe`-7${x5F)U)ptmmU4c9e>jU>)k=e}u)BbtQ zQ~pn#-=bAm|5vw{|5I!IUp4C&$1Oo zupV-J{A}-+?E|yDUv_8v!R&c{+5RxQv;AInXM4Tu&i0Slojva_yUW_Vv-o=8=l(B^ zpNseZqt2f9_eb*q@m4M0ePHp8fBSV&y(3F?EMLBSGWNWZ#^>Sxemm{IiQ2!c){tj!L@PBdR|8)JiKm6atb(7%#=ue;hQ%2+ev^_EJ z*m=d=#g{+#+oH4XEZwp6k!6DaQy+a;nc)A_Wl9|p{GV>m^}+wejsJ@q|EK2p!2hX_ zwt05=KXs*J%Lo6bKKA&s!T&XXKM8)ZQk4qH$@OmW{i|2568xX`uTiCH@PF!)PdG7o zapR5t_-dV4EqQ$Q4Sv1KS352#SGJ@}l|MZAKYzUTf_nd$>wSOLpYDIhb>6J+i~rO0 zFK?cyf1PW+S$`M*r|rx?!~dzZ{;#^3&AVj&pSoR{)cikn8(TjW|EE65=Kr;BbD4K_ zdq3d+bpB1uZ{h#cE$sb?|5MjF=IG%6biGbBpL=T8Oa1!Rw|?99*Y$5-r&jQPYCIqQ zPu;|R9+~scncl7J?;G%c+Ri*a{GYmE{n}yvpBnFm|5G=sb87NTr^$XkctHH0&bLmT zI>G;`@q_q3bt9W6i2u{$ZP}=C@PF#oO<44X7GRNHswzY{!iVrR)gUGbo?_K zo*Mk0x>1wUg8x%DZ_*(6KQ-(5;{Vi5Pp=XDpSn@KYQg`hyVa?l+_!U-pMTy-m6FeP zo$1}ip3iQ3MtZj`e^m15-Vxp%%9crf*f-o84_LT=n0IsYc+VXe>fO{{@AyAG-YVAk zKlKT=KmJe6{`fz2GxL74A2UE|0jGQPi6&+>rf z?dw(i{qOj)<%0iPa?!oP|5d7dV(@?Jx~HBV{Ga+{TMrojXKQk%=l?Yb{!iVoY2D!e zw12z2l>bvV>03AWKXtp|O@jYZcNuY7@PFz-6WRp-X9g(vKl~N`FK+ywy8FcZ;Q!QJ zCv-@DS-;D-%l~ORjsH{Q?)}|EFfY9sVzF=KrbjZumbn^Yrk4YOX*2FYeB_75U?1`vv0{dE?daf7*YP9UuRv zKGQrF^Z(TBkN;ES=kR}O<_qHg;(oXGYen5YzdQVXknKnQ_mzys|7m}GAoKs?#{cR0 zU_1UVZv3Bmpsn|c|5M}n@PBINBjW$!#{a3gKKMU1j~D-^?s8$r;Q!P;rgRPdPtCkG z{GS@HhyPO#oYpz`zqs*#apV8={$hXppSs_Sj=}$_`(NBS%>Ppt&P@5gxbc7LZWnhC z{!jPUb!N9P|4)rK#Q&)W&L~Lmf9laQx`z3G>ND;9?BBkf`GxpDZKv^nYJ401PtCkP z{GYn(q)x&Ask>d&Iru+y|BJc>|EDgT)HV1&b%zTJg8z#f|EK2tg8x(Zo00N=YP{du z$xXgp{x9B+|5Nv!(IvtEse8=m9Q>ae4~YMZ8~+zK{!fk9#Q()TVZ=;tUSF>sGu^w{ zkb24QOQv|&9aJv(KQj@*|K0YlndX^B7crv?-*^9lSCW&vpXt5yqy54EX*=s94jMbO z2-CxSzuorv;yrB#d-HiSgBX@PBGPZ)E&^Ft`G4u=^G^Jq9xwh7|5wr}|EFGMzQ*Rq`1YmyQ~poad-1-M|5HC_^8%Uw zr+&fa1G4_FdcjAj`G4vqpMDqopL&;FPv-xr-?sU96MLNCE&r$U+iCOh!u-GVX{HDU;E+J#mEhKD$5W|LOc_{GWQyx2gGm zapV8goDcK=)Vs`|vi`3cAISQ@akKufdabQ@9OnO}&v%pgK>VN1pEjS7(dIY2cbYfE z|LJ%;%md>8)Wzxfe`@CaG5=4Ek7NFyn)i>bKk3KcU~TJDdapMRi2u|1t+e@@Vg6tG z{8!oh%`pEj-F)7T|I_|Ec)u|JFTI`jSD617b(sH`Zq6^v|4TRTcl@7jzsh_eRw8cx zt>*oS|5I~3{GS?+hyRNk|EJz$kGJy53o;u2r|VU09uWT*H}n70oG<=Q&HdZ_G;e$c z{!iPtnlHfrsrT9K@qg;Q_IU7rYUW?z|J0l9>m~kA=g<0-_`kTr{J-?|Tx&iM|EKM% z&BHPOPsd~49R5#Vzn9r|{GYbV|Ecjr_HWHMyqa&Pc|>K86e`9JkNqx%H^r=B;qUGRT;eZFcQFwFl;zkcUkeqL(+ zU%J2k*VDoOX@B`Y_2NA{ga1=6+mW9Cm%jaqUHgLn)ApiWsr7%=i_QDl*RMSFn{2P~ zH}Cm2KMVh-?LPl6eSG;pZD(F1{!ickY5ZT@_&@bB^E3Frxbc5#<~`#7)JttWPyC;H zwY|SaEZ*tO>uYb>ect#~{GZNmnR%oz|1W+1^w`fo_WgOkznk+}M!)p*mw9Gzg3n`n z%g?^`W*##BPv^79-hcSNxW}B6j_U+tSqd*cW3f7*@@#Q(*O|5M}R@PBH&*(Ytw zdl%dK?5zK*`={}LCH-0QpGK84I?Vq|Uyn`p^Jtj=mu`N(4DRtBpB=i5&n`}G&PtEP|e`@Aw+Fwa0`1 zQ*-|KKQ+%E>;J}$|5M{B@qc=Jbp7IUeLMdDdF!?X|EFHCc2n?wapV8ge_g*V_&@bC<_Veq zr+#zyhr$2p@h{weDEL2ZXT50rpPKo`_&+u4^Wy*FX8xa=_dotm&3wvR?wXx%{};U9 zcKi7U{}(s@Prcv#FaA%xhrgHD@h9)?_VuyRN4IOur-lmE&dypSR0?9(v^Z zJH2<<{Ka=0-j%<7-mQza)VZyI^_RQk-tEo$%TM>d$9tP~on`m>?eTvXOuWyx^YUGB0^#@{8UhdUP|d z_>y<4{A$U-*XMb6>Qg`XKmER~d;cb3{-3&Qzeb7u{?7Mr-?u@spzG`2tPhO;)BV@) zQX_f((>L;GOujq#zNUTaB{x-g%e#&FLj0e$=M**${!g82>xuT;`mg*)Kffz@u`aeA z>*?Pu@MeAB!>cax&a?S+2iq2Tce3?@@qaoV>jVG!$|b%X&o}+ir5TO?)BbG#^!61Q zy=vY{Z~Wks+g4>X{!fp8@Y(kF*VWeg_CfaZRErMlyzz47$F9%lkFVe0-P_iCUHLFv=h4p{c zgKd5!{?FTvkN=As|EIbvT0JF zZrt$b;Qt2R_CWA}6^~1j!LOAmxVqc}i+aBMa6xi(l8otdl=n%eR!=$&JGwyoH$SaT zvhnkh?r8pR#LZ=Wd-i&l_#OP8e1`mA-1t8=^TP0dYWY8PZkx8j|EckO_&;@iPKPl6 zPu(fEAoxG^;C6Yz|Ec@7XcPRO8lT4eKQ(?2|EFd<{x5F)pBlf1|5LL+{!h*NxA;Fb z9uWWMZT<@Xr)E80{9oMoKehay8qdZ2KXu3EO@sea546wM@qg+8O`0aTk6lwBAA>JE z@_}o;@n85qZO4z{|KfhRi0juyx*#pv%R@q_&@E>`oj1>H9qk5XXp6-_%U0*(_8*e`)B*JZ2y6umb<|NA+p{}+ z|3C7C|JV6~?2rE|SpRMCe;gnGr#_}aYW?4${O^PRqw#;*Ufnzj{!e|9c@_Mh8t;hz zi+lXE%*Ow{e(5*C19JcPzqW^c9sD2O5&!qronHq3SMKm5g8x&OG2e#&Ym)m#@P9P^ zPmN#0|HX~})9vN|)Ob4lpPKo4_`kUEe>$H0U)=aVwLQ5B{x5F)pPJ(z{r>EXu6#je z-?Q{ji}POjA^1J!`{i}c>_f|L%h>)vm(0fh>GoxgI3oBzHS-af|EK2q_2^#G@_#RP z{mFj*IIJU$|5I~5_&@cLHeV3`r#{xa5B^Vm(s3#Or!HIh_@whQxA^vBs#XgAPuuZ+ ztp6K#>3%o)`LZ4Vr}M`P;{W{hdg8Ic|EUi@F17xz_CMC-!-ZB19 zeYp8M{GYm}`91t!-1t8=^UYZQSIs;&{GYe^J?8(ZPcLmh&zb*ImpQCd@PF!ZWsV5` zPv>7XJ^wFm{GXcnY|Q`D^`r5B>NfU%!~ZpX>*qy3oPK!6_7y4w|EFesVEmuDey!TU z|EU{Ps}cNP-1t9rljQ1Me9{iuqr*oY%g8x&WeoD&!sTD`&<_4j-Ql!;`L80}qP>%HUu{Qk{Dh`w2FaA$mt6a+e#f|?{^LoMm#f|?{*S7P)|EW(l@As(r zKV1*j3ugXb-1t8={xJUj$m==onnz@Q|Eyo3Vlra-zl)mmyEAycdKFK~*uP2jy2-Pr zeC*q6);m4;KkbhPWd5J}^hT-qf41gk@Pw^$8io0P>dswG2>wq!Y&n-FDSh?>6VQO@1D}#k=i!If<>G;LYuAeFg9S z<^?DHd!u*Z`MJUW>3sT|PsIP}@p1n6KXq^Oe)vD{3)=<%r)C}?{!iWRg52Q$)Ey?J z=KrZR|1WO*pBkTr|BD;{r`GzvabNY}BHzxuLFWHy`zTva75}H6Wb@VVf9eT#e)vDN z{GXch!T+i8T=x6HqJ3xG9=spk3;(CabK(Egc)EsrUiKa^v0dD#SJs(_8 z{9oMoKlMP{AOEKwWXHq*sX0FWPd&uWAOELj{aE~8-1t9r|H)m0|5Fc`(k=Ku?`bLj zrygkj3;$Qr9fSW zf4jrG=ahor|8zX&|Lu6~PrjZ0&z-k<^ZH@_pYLy8kokY=Hj{IL|5N8oP0jyPGanHD zr|y&Xe`>BT{x5Fk|EckS_`kUEe`@?5^Z(+;|Eak>{x5F)pBgVXzW8E)ym-QwZ<^uF z`quwxKh3*Uzmt=mUr+X~Gongz-*c0^?^}1Pd8ScCm>fLco2!>5TVEXMz4N1YY(C9! zZ|1w;|Fr)O^E3EAHS<#Ne{tjg)XZ1G|HX~}vo)rI|6_g#{x5F)pE~{dWJcrvv|avB z&F4}0KlMiY{1N}B-fCV6|EK2jM*N?e^?mVwI^SaRC3Esx_;%(~*!peWYs?Ga|Fr+I zo%@6TQ_tVJJIw!6zqF<}_&@bO7cFOfIluk$^B0Htf0O=ubMTojEL;}+pSq}cd+>ki ze{9(q=KrZzfBsGIf9ic-d>j0q`hfX7`~2MR58uZ8Kb;Sa|5G!c5C0c8{!hK%ydM59 zZv0=|_`kUEf9khwJ>B(}9p=5?=KGnK^5*{kJm|MY+Mlj^*e~Ale|mg0{x5F)U);?9 z)A5*hi2sY*{Dt>sn}3M^({>vFr^fq@HUFpMZ~x*O^RLCe9shUtgX_H4+UpPhr~R4F zclXarefxHse~JIo@mXIR|EFfY5B^X6FMI#t|I~}j3*!IO@0y>(|EZa0g#S~A`G7Y6 zPrb!_BK}Xk%^Lrw=KX{JQ?IrA$N#C<+1Cf`iW+anzvIUL#f|?{;~(*V>TPy={9oMo zKV3hzxt11OKOH z{vrNPy}~>M{!d+G$HV`r7ufyb|I}-3z8n58Zv3BmxvkG=uMh79+ujcI|8%}DZ2Xwl zmv6uIZ_9YR-d9{*girM@=zJr7)q7y82Y7vZU)XOR*T;L}lskg|)A>x9neuHF!E>sBTw+{oYG$eP8DP>3DD1d?n`psaa1K|EGS#u0Q@SZv3B`^>vy5r!KPR zkM)1mtPhR<)A_PKH2zPGpTqyDd4J&l)VzN1f9j<+4-EgOW1pmi;Km4DXd981>{K|siPupqyU)=aVHP;*e7x%i|ee+BAy(#!FuE#OI z7G`u|&4Jzwsa^}zqBci8Rmf9gGU{^S0Bwm04q z|EKMEMf{(7gS}qye`>y8)Vu!zKi^_o&v(LG7kcyG1ApIpk@s5j$DjRYiZ}C08`qld z{o=}X$<$6Wy`OsHwJ`rr_jk`TPX+&{e&*?Cga1=M@|Q>L{d$$3-<)Uu9{iuS-}};Q z!T+hBTd*vw|EuP|SD62&-frLD@qg+)cuMns>TPyC@PBINBjW$m#rE^V`Pbg+kB2tP z=e@GibB=K13PbiB9i z`MI{no%wxd-Wa?ejsH{g{U86QW$Jl8#e|2 zr(UvZP4eq0Px}6EzWPe=fBOB}z3Judh^b?3sm{QfOpT{y4_zn{x!{GYZL z^ludWpE|#=Veo(Iw*4Cf|99kje+vGO#{b2Q|5LXqJR_MgZ+?FB^ZyjQU*~@Hga1=^ zHxG#aQ+FKPB=|pdPxDLoKXrSX-}kSPi@kHr>*4>j9S?~AQ}g%VeHJhCX1$mC?=H`1 z{GZMj--rK;`>G#Sd*l7^f7(89jQzgS{GWQT`7``q-1t8=-VFbzW_?=xUrD!4-fX$a z&kyf+@6gTO__8Upwq$g#hqij-|4v=7&3n+Omcjq&dJMAr!~eyN|5LNRE&fl92gLuW zncs*1iyQx^?rR>8`G4wu=JoJ@asSfuK>p}Mw*{ZZ_8k)sdgBA<&3z}M|MZV{y+@?| zpN>c4|J2+b{}(s@Pc8qa>n;DM?d|M(;s4a_%}?V0)Lei3U)=aVb$^@R$NWDv^8oRG z>Ox!3m-Tw1>2B)>o@P59(9tYSN-nYy;-H;|9&jKC-}cw_Hh{gug>6mg8yTAEc~Cke!V)u z|7rg&w%!>2Pd%hvi{y^;Clu)O?}z`> z{@oj<{9oMoKehayn&adD)c8I8pPJ{RRfXB!Lz*-T{!jNmsFAJjYyMA-zr5(BlIDDm zYdFWZ%l~PA8vhq}{CRb@-^=do`F#ED{gQEen_m=n_PoFBd4S9(jQ1awlj#YEWc7#+ zS>7!-H{kl(;F~0xd<}u^`BfpoE<>}hD&-8!U^Z)whWgdT2)_TZi zX04Z;egD~wAC1p9oK z&)8tgpS?MM{Gawe`lxcr-QV1s(JP<5XYu5x4+Rfcq0CXqi@ok%{Aq`O2M;L!H(|%e z!2@dk-@e;E3jPnDhX0Ej|EFeu{GV=*Ut|5>xbc5#d>{TVZv3B)C;z9mCo^es$DGCe zI)Aw6rX|1d=14xNRMPDK)I+mPz3jR;qPdxF&;Q!Rj_rw3G@qYL}Js$Z#HT$#vuUhN> zs`+~f*8f%GA6fr5Zu@-3yY!Kzlee~9=Y7P{M+E<;*SGv%+`pOsQ{$QNf9h)HW$}M% zJRts0jTglKsjJ$T2j>5&s~vqF zb=R6Tg8%cj^?skR`F}c}PStA$|EF$PvsRe@7dP|&)JZV7P3G@HdJm2^~HS_!Me`=10|5H~yx^(b=YU8!R|LOXiU|(PGf9hK1!SR3U z%H=C0YjgT#bo~9Ws=dDAu5wJpjILF+Mn<1eyMFM0>;5@6_`oW48U+8RKCxco;Q!PO zZ9e1KAHG-gUF*5Q|Fvm(TJV4BoQ~y_ueKj7GE))`*ioyPx} zp$`6U;Q6hC|5FdXpl$Gf>YfwZ1pgOzhvRnn?dAWpoyPyE`;N2q8O;C1jsH^@jL!-F zPuQp!T+h5Z;Ahl+pMQI^Z)RF z+D_yD)cCzRljeHkP3>I$d^=9*5d5FcpJx7_n)Qb9f9mdbJz4)(-Sgs3!T-gL|5Nv{ z^^);_apV8geQZ1aPu;tBD8>TVa>-!q&4Q`hfP zE%-lmhq0}K|5Lxb{dxPmc~nvBJ=X<)w|vW{q}qogytlo3(B{(&^Je}7{tvT*7i4}I z{!hKpJPH0!jkm%7shQ7mU+KPnJR1L}``>Aw590sS93TIu4xdNb{696HH{$=)Y-j$T znt3DmKQ*7f;{Vj#9{;E2^HKbtdV_r)i~rO4Gj9t2r|qoghyPPAPWwOY|Hihx!T+fr z-?At8KlRlwy&3$Udd|Ezga1?CGk=NshPr(hBZ{P%gm|9$rN>w^z$yLM~v zf9i9;`)}}n>issKj`@G;gXZJ#f4Vr>jR(a4 zsadZV|EJ!V_J8Uvw*NhCxA}G&|EKMnY<*??pBf)`e6LmBctHH0w&Mlye`@CY;Q!Rj z_rd?Em)iRW|EFG&_J8U<_I||wshQu2|5NjRW&U5>_&>Gg|HX~}Q}cN6e`@9v;{VjU z&C_8s;^yCKydC~8Zv3Bmmz^K}PtEc0e|kM{xBJ8Y#f|?{Z#A!h|BD;{r{@0ge{tjg z)LcLOU)=aV^|nvH2>wsa`jzItd^_t~nh*2dddTJ{ng7${;r94HHQVujI^IURz4|EIp}%03nGXpBf*C|5GpB&-d$j zetYIs_CD{msNXkF^;VwE%nDwP=XY-Jh2Hb+^@IP@`7N-Yhwy)Dd>;NUZv3BmwQa99 zZ;Ky~`M;0+xWoG`n-^HSV6XQ=+y2xo2fSI|w|?<^-b>8eJzwQxZ|3neI_pz!=JkE{ zpD*&RDRW)$SA4&i+UZ+wzMtU#^mv!y+syyPjsH`#KmIRn{GXb6p7=jCz8C*j(uaco zQ{%z#e+B&#sgNqX}CA*1rL9Aq&M>%A6zrao9B1$p|iYq+vBZS{_Kn%+w@#-{O6Mc z$9ePLJMYgtzogCo;{SBMcys)pdb9oa0sb#;{GWRD?ze;gQ@^-)dGLSgTVI=(ymH

qw)_tGNs`KXid7CA(^KYMY zP4IcllYd~-9B;he&j;puGv9C27q@wDv#-A+&$-=?x7EHrpIrV9-;NK&|LOR4ou{GS>hi2sY5`G4wl`%?Z-k9X_dl>bw2+O;?MKXtMBcIN-Z z{qo9({djA)??@``_>1@It=p1IK6s?0ZM|RopY9(I$oxO`s!b{Xr(V1!<^R;LznSuX z`hD8qp#y^dQ=itMT=0MD+yS+M|5Nv~`Ca(Gxbc7LuIBH)ede|NhlkA$zKOR)^KXsvbK>VLt{!iV{)(@qg-}W7`M+r)EAK{!fih!~d!AXZSyLA6pL@|EKel|5LMGE&fm4Z=}sPGykV% z{aXBA+|2(|53ud{zqs*#YJ4C5FK+ywn)!tIKQ-rr|5Nv{d4TvobuaUh_&+s|AOH8o z`L_oDN8|szZGIsBFK+ywddOM1$%GB>WinD{?6 z`{V!A%=^Rt>H6Rk@qcmS|Ki5~o$%!?sd;|3KmJe6@$r9Z&KLiuWmf(!n3hy8r}NI_zszrRs*RKX(^ z?+8AycHL8g|5LX(y>60wZCT$xuVs_q|MYn>>*wPCSx)OebEZlB^kq*d$S|FnH@%T~ev$%8Oo4gaU+ z{P2Hj9uNLcx2N%c+Ro$0|Ecj+_&+u4=i>i#`}|hTga1>rzUutVvwZ(To6mRS+RMCI z&ldlu{qbB?7hK`n>4UFc>5V`8`wLfj4{X{x_&=QwjsH_KkFb3CYYOC3m{&OB@N2#C zd4K&iv+;krJ@;Sz`|Esv9{-YQ*Jt!QuixPNvmO7Z+v6$me{tjgbUwU3@PBIj9{x}J z^LSbRSIzn0|I{ta^D+NV-O4;F{!g7_uLt~}x}CjV@PBHK*ZRj>3gl^W8#PE8%(&IN zO`|h{|I_*LeB=Mryxy4qr{?*_|EaU*`DJ(Z`n!19`19=S^?P}~;_WS(X3qb^&&J!c z?=O4(*yek~-Lku1eus?v>)$ayqq99;wy*o6`FYu%F5BA;Xp?zrDBKfl!*uh(kt9KSwCng9Av&ABDl&p_V6>2v*hC$_!Mw{tQY|EK4J z?f5@$yFLET+q~a*t7b1=wfdvr3GshV^eE|ac7A==-0Isa+VlBy&yr@oB>t~U$4`PE ztXQ#P@PBIN^)dfX&HBBp|Ep&H9R4qE{GZOJcJ(S@{+}AJ#r!{=f4M4^!u&sVa%5`# zU+sUay?*e2aog`sy;;8)|EKN8*!(o+|LJ)6KIZ?aE0rl7*8f$Pwe@@Pf9eY6@9=-> zTK0a%|HX~}Q!{@J|EF$l$H)Jv8<;qzzOwT)Z+u&;&QrbnAAel(S*I!9U5>93{GV=5v;MET zk#Hz+Z&%$HJRISqIauPY6kzO$KS|)9>xEud-m)Z{GYmiqh?|LpSr%S zhkg3SbA5m2=UrcXj(4|8$0vI>o$cMaQpMo^bo(}yD+T|j&Z~NC@PF#|Y5%7#Jf>Xm zf9gKw@9=->0(*Vn|KhH2-*A8adA>fnf0#Gx122APsCSq0WrP3I?K|4{3;ds&+q3?! zn)Qb9f9gE@{(=8f%m1lM+v|<_f9k{R_0If1JwKI?Ef@Tsx_Z@$!T+f%oLDvZKlQQI zPDpOZ>Fc-W{U3jSnuI*Xx3m|5Nui@5lT< zb=M11{!bk|q4_^G^ZuCsrCe(-;4 z=EdRv;>Q1}huVBY{GWQb`953!q3Fnhn}VOi|Bbt0bw)G)Py4g|#r7+GJ05R))fE|y z|I_~XJp7+}?6j`I|Eb4J?Go1iRpZg{f9l?L`_~H=`SJ04`>HR@X#AhfpY?q4e`HmyhSe{tjg)XcBL|HX~}Q}>%w*OJ@!b`d)E8lt~qYvHt7w>_Wb_@Pb#~)z(x9RR@-;g}uoquWfMA|EYUV>k#~( z8o!7CiyQwJH~uef{9oMozqrlL`Ss-ZT^^k6&HPFHpRPx*>8bgD>cUG?{!iWGk}kpj z#f|@q8~>-q590sSy)Nz={9oKR{^LqNU;Je8IhT8nm~QL+o;b^!d4KpnJwE0E;{VjV zzwm$RMgwaF|EHdG$uQ<)6ur^%vhex#w*5uS&+uNcdw1}E6RKaHT95a@f#Cnt%um4o zVRZ0+e4c~vK>3B5$PtE$8_&+u4tJ&v|etvv@XrE7d^ZBpM zFY(6z*?bdk*5kGLC*Ewg_0hcXe>OkGoBi>Bx_`R&d9A!xm?y;lX*=_S@PBIN3mx@M zWAA^g-;#9S(9rv(*WV2OPuJt2$Da)TPyNr08-o8+Z~XkT;Q!Q{_P-zepZXs*ACUEb zch9>b_`io2uL}N8y~O;Y`4Zo*`G4BJ-`4A8{a^L&uYU~wPshgt;{VjF-^=_z^?N`5 zC#?Ug-t*J1!T+gu|M-jfkE8wZziY?8talmjcg)Y>|Fr*yc6|Jw`s43^3I0$0wr$7% zsaYQw{}(s@PtE@LKQ*2Z|EIZGMyYMq6(f|EK+n z%~#_8)SGSoBK|LK{GWQg%@4%?sW;hr$M`=ruXp^Pnt7J^KQ(?3|EFesVdnp-xjp_* z%{)K+pPKb`@qcQ32L4aI-kSM;>J8@o@PF#C-Ta@L_dotmz26%Dr+(XRkIhjtZ;*e- zjsH{cGrza*{E3V7dVTxzuY>C^+MoG<_`kUEe{tjg;x_;0 zz4p`3g8!TQ;FZAx()d61x{nS8|EEsP=PT>m@zl)!({{c-;{VimJN%y-kH`Picq!YS zt6pTjh53K#edY~W|5wfWfA~LtJZb-@mj6@Z^YDLa<`d%o)az`1AO0_H{GXcj+VOvJ zCZ|I{z0=l`kaKEFKpKlNqTE)D)q z-8TQa;Q!Qx&F&BWPkmmuf8Zni{-#}cXY%j|BmDfXp7jXtAK(7O)ziZKKi&T3bB6~1 zr`O{m`|lz9cb@t!`+VDMRi3^cE|@hc_&@b8Z#*3QpZb**MZy26SEc=*dg+dx!T+gO z?cEprpIZJ;J%7&uo6q)?-~YmW2W&mo=e!r&yr%9O{^7mUyho{vU&_!*Hq z^N-%E?B^}~pYER?WByN#AH@H~UAph#`8pmyUv-^wr1uW<>$lu>R7u;{&$X|V^~Q&l z+i{FH>-F~iv4S^W|L}jhKmIYCIkD|Ki5~mGtMy)auRs@pC=# zf4aUrKK!4W@8|eGHIEPfr`~0L4*#d-`yKvIy~!RA{!h*A@qaoWZjb*{Kfe{tjg)c8L9 zpPKV|ZqzyXT^_qMcs2UamFIbLevKa)U()8)@PE2J^8oRGYSyR4|EXC|7XPO%-k0)! z>Q|R64gOEPVa4j;|J2`q{#EdQy1u`EY0vNQEBtzYV}GB;{6F7*=;Pr3yuYz|iMIZ) zdgbO_!T+fjuiFy*pPG5P_&+s2uh^_TKYzR{{!iz}cKn}uoBjNN|I_u{WdFTrYwzY? z_thoA`{DT>96LLIQRhqS^Psr}bh{~YyzzPau9}YC{qcX=&d&q* zKlO(9J`DaZZv3Bmt*sA?|5I-;AI|*0xbc7LP5a&n>;J~xaQ6Maeb?RtVg8>U|F)ee z|EJz;>)Yf1)El?%Oz?j?-rAkJga1=A9}xeiUbSsU@PF#1HXjiGr!Gp*|5LxUdTp5h z=e=k_nE$8Wr;R>mZ18{T4sFW@|EKQXyJqlz>Hz~%^Z(R?1~p4gyz$lirt5DE-jDfv z_`kUEe{tjg;>Q0C8-8Q(fBA!(1^=fmu=PRlf9g&Hn+E@<&g<7O%>Pq2A8=~$f9iH4 z%#+ysKXqrD&&K>eb=R|62mhz;Gdkt})P?5p@PBI7_htT{dSKfBsmGm{AN-&CT>E>df@-m_%-}r-1tAW*8hzg|EHG!Q{xTK|7dUiweQ~$ zJRkG&I+uCdyTh0^$;qeh_r?q2|Fl1i|BD;{r)E82{GXcni}*h^9<%G`?|Tn4|5vNR zhu#Cm*!n|FKJvy7;{SC1gGbx?A?E+o{l>Np{!iW4&L965H~vrE$6kNT|MRx%&HO)g zPxE>BKQ+D%{}=Ziv%dE8Ycow9|Z|48htS^lJiyQx^=KS%0YWyMd|2F@6eei#y?e&NM zQ;!_cGWb7r|9;Ja|5MkjZtDrYofN3++j?Rj6dql0?8kG02khGH^yJu&OS+-04~qZO z_Qq|R1^=hdkMS$`Kluy13-kZftj~%6Q+F+}^{Fgb!%H675}H^cyBy5 z$(#FQ{aQ{xfwe>z@%<7UDC`F3mkpE}Rx4dVZ_Kl1?b ze`-7*{x5F)pKj0f!2hXPzxc6XH+kdjx@;|Jd?@};$2+5K>)`*?4RUP#ZS#NXCY|z= zT}y89)*1`X&^V-|IR-6B)^Xrt~KKMWNuy*Z&|5LMm zF#b>dNB#>x7=K*03qkh#8W-_DE_TXL=bkH@Ef^Z&bd$=p87-mmfY zf$cNr-F3^&oL`si?>gpX-hX~>=6t)h?J^%<`>gqbz1n9UKienbd*k!VzFy29jko`g zZk>64g{?C0kM+#s+h;fL|9E@0$K>@LZ_l3JSkOB2_I!Pa_s47fUmDLA@Bc?#$~;rN zf9W!rUNC!pV0Pp2@P9K}z8(A@9uNN)_uLQf&uIK#ydD3i=6J0Ct1e^fJF@<7-1t9l z^L_ZgxEEer(s;io&bVjsf#3HA4@mdkc-P{=^Y#P}h?kr`X{HRpr>Q#0QW|EI?L;s1`we<%1q=KV4MPhGWY)!_fs)v8rX zp6_$B-~Nmft0%)Y+?3JyKOMi;NtJ{DQ_KJ9{P9KQ%HB}&c+&n)`!i1x{}(s@PtE%m z|EK2h;s12}+7-(O|EI2D>tp|B^Z(RGo3FzEsmq$L!vCq||J0|Lx5EFa@n85qb*`;P`##LQG^6ovqNB8`K zsTo~r(G>4a_IU7rdVV|GdbapKb-wwqa!V)q{<+5-m7KTiLhn|`R!9~tpXlBCxMPzl zD=+YFTcvWC|EKfMt#)GYf9h7J+231C9p~4lpher{i|OZi_ixZLS#|Nb-t|kB4gOEJ zZ)(p!{!g86ujj(6$NK)AD;=BEziv!M|8~P!-W`uGpX|JOv^VShvi`4*htIp^wljS@ z*JsQfBfXiw*XHgK-pm8U|LOV1XX5|Vt?lbK{!iW9p1=Da8IsZXKiz*5TYnn=r*3Lr zukn9sj*tISx3I6j4cia$=a26vAGRClecW-!1^=h#7oW@gKQ-^qrzZDbeE;q5hWU`p z@7zDB(7R6c8cEd)`*}C5Rx{)KTcfI(-mhBS+8Ntxol!rd8`eK9%>PTKULQPQgL?Io zcE@~Bbo%et1@G7Vj9S6}sXOL03G@Hd`Mqle|7WHp_`l({elGq`-DX1j*=!oueyt^x6AxLHS_!Mf9j6sw+r+C)c8L9U)=aV zHS7E0|I`C*y)&5uPbUd_S)e4xP7&CYrTh> zm&5;QJDv~!r^fru8MDfJ^puXl|7rWE$pyjxsfXEoxnI6n=KGJZ^+IcJTIxN@=F4^a z#}e-mQ#vIV-n!U(nDt%f6?qT2DCPfj{GR6R@PBIN590sSeJ0uOzs&!|jsH{2|HX~} zQ{(yYe{tjg)XeY0|Ec@fd^Y@_xA{K&pRT`IpWy%0_&)rfx{s}&i~my(xA}AUzqs*# zYSv$6{-2t8YxqBPp*8+5Zv3Ab-^Khty&rmCl3M>)Jz!>!F#k{8e@6GP{;zs;dj6k! zlzA`wpN`LbKm4D1fO$0hUrDF@U)=aVHU96osSjr~{!iQcUD7l7KQ-(B;{VjWY(60V zPu<(RApTFy`QiW6{cOEl=KraCr~RM0XWIXH+w+J2Q{(mUf9meGzB2wVZv3CRhpo4a z|BKsZ-FbJh=YR4kv%S08`Q7`UTfCXyH-Fd7-aJ0DdL_^2rCo#n)AQ5Yy1~R7e1H7q zfUehj_cgC+`}*xWSu_7nx9?*6&W|EXu)G$Z)Gm!6&){NI)X8-o8+uid#T_`maRnwDCR_wD_`|EZbRfd9kf;QyG1 zh5u9Yc`g1=t@(dyd<*_h$D{FoYWxlUPtE$B_&=TBPW${4|EI>|;Q!QoK8XK|8~>-q z`{DoM#{a4DEw;XzxBQ>ZhxPXGf9f?he+U1kF53T2@PF#(*Q^izPyOKQ^Me1=^|^j`MC=jOMndvCY- zFSb6O_x^8x4fFqWJm%{$|4+Twd>j6+q<;whPyLShzXc1*`{RHA=UmP|J0kl_&Uu0Q_KIU@r3w4 zHS_fFe`?m-#s8@n*t{S7pStMN?}GnRZ#wjK@PBdR|J2)Uz9IfkjSs~CsquccKBqrk z+Sc#%US?jv=6iWBxBIj8KfUn>tfi>y#rvJvOlppY?NJw-ujAipd>`}wbUwSxQ&y~h zwm0i7+j`~R+sp@=KlbMK_&+mZ!OQNn^|A4P-u8Up|I|C|^LPB8daL<9{GWQ8ZO8wq z+27tTet&pC*8kP{(yafhW`BEqE>yD}|EI#f|?{Gj9<8r)GX2{!h(( zK>N2h^8w9=d2g`!fA)AY+WeaLMq8iH&S!y+N89nei-Wf-o6+_kAlzrT-kSfXUS?jv zZl9~(nL57rj@0owX!}OvnGn^Z(Q<%|EdIuX@d%l>bw|zWYF!|EGS#*4Lc% z=wI{n{rjzb@0!PY*85-P<*#Y<4{zoH;{UXNQQH5hmzvjUeZ!l1W_E(Nqvx+$;QddV zFPK+uiTA5%|EJrpvh{B9e{tjg)V%)ie{tjg;>Q1}`S}C?r}J51?+^T6-1t8=UJ(DM zUSpmqr{))VIW?yQ-?YZ&hZddnO-AGYv_I>A_tsCo3jR;~GtUnH7k8td zoA~}4?fWJEPmiC*|EV{d_rw3ijsH`#{xJSejpxVzsrh*s|EI?5;s4Y;AJ;bS?9KDF zw0~D`ex5&kMt5(1e(!c)Pj7x+!2juZTwna3dX2q)@qg;IY5%8QY0nS-PtEHK|EK2p zscil)Zv3B`*T=zM&dk^Aoq2$#R6ommr#+wJbH`>h{!jZe?-BnOH~vq}_orzKCwSx4 zUU_?BM&tkdeBS*i_&@co1F7|Y)vJp)2LGpCx^_eGf9j9y=Ml4Ye!Sm5doTDuy?*wu zTasM1?n>YO-{R%T{LilT{(bYx#AXY6KeKFI@PE4f!aeT>|EJz?@a^FL)O$Yrckq8Y zpPh$34gOEP`!l@nEq?snHeVS3r|Y%jgOvZ9amnNi|M%j?i-P}S-XH!?z1_Y(;{Vj! z%unP0bbI+fwftY)_`kTB|5wuQhxvc%jR)Qd{!fj6#Q&++nFqxGspbFT#{a2zr2U^B z|5lr?$ojwPjXQP+{}(s@Pq$xh+nN6tH~!B%?f=xPH*HDYx#uyzUduKXCpSF#xcAZx z8-xGT{>zpx4gOERPn$7wdhmbhLH(Nr|EKQK@s#A;yqEKDz4n^m`#KlaOY+Ws#k;7Jfvmtf9m`JO@sea zpE0mr@PF!NY5%A0II?;0f9fvg&6xkE&NYw4{6BSp{e1)ePc8qa9yBg5DHysUzwVN& zf?peXUO{rwr7OKhoSUD#)qS+lKU=L<2~q{+ywupG&|EUL=FJ%5--1t8= z_s{&lxbc6wet19pU)=aVwfvtNKZyTRvmO7Z9&&bv;Q!P-fB3(+@qcPOApS3I{GS@1 ziT~62<1z7n>S1T6=KraOjAjC5c;>Q2! z{FwKL|5Nw0=ePU(Z@uOJv|avBT{to)soUv?{HgC;8GK)V^MAje{iC+nl?**y0w&VZ)X1G{E6om=<~p)ZCeHZr|#S)C-^`4fsU=( z1plY*(I(~p)Vm zdb;>OHGc1_U6*UtcrygRjZ|480`tr) zy;`>K%l3iU^ZHmXJU)K5ALRPQ+p~K>+symt{TT1h`~Uyac-wgY4lOeMUUv6y+8|^9 zzKu@H=sfe(@$ovh&Rm~4y9-)m9uIF7-~RvFf8+DED$*}Fg|Izrr zxbc5+!W5DSf7(vt|J1CvjQ>-!J}>@H&HB;!KQ-$|B3pAZ_`XiR&H z|I>Dw^?%jfC*}wL7dQS--TA`&;Q!PG6H@+9op)ZF;Q!S5i+jw~n~KJDyfpZ|f#&^g99ir=*!Pp}-w^*7H~vpO%ASvp>%HK|qsy26hj-!3PQm|ae>@xh z&)d8n{!d*vy<39+Q+KrWTJe8+|8zBP$NInOffx4-{!cyVl3q!f>3{XxkF##l_et+_ z%?slHbbRLZ;s4^s|HaMxzqs*#apV8gctHH0y1zB^|I~Ok{GXcjf$@KFYg@#a(vypygS)?!1zCHXFXp0pPJ_%{}(s@Pt80({9oMoKXv!1 z?SlVP_qjMf_&+uC_3(dj+w44V*8e^HjvKx4koZ6C&-KIqsr%UL!R(!PEAxdp-(T(B z#%{lH(-r>unvH3f!|2y{c2^s!Rz1e)ogAWby?K{n@?3y{q zo6l>j6b{Jfp{Eym^LZrxPsiJC^XKq?>Q(mnCjKvO{GZN``C$0JxGR|dQ{#*9e`LQzei2qZsHvhr=KlRJ@c^>os)Gxg8 zLdyS{VZu*dc=3fP|CjEwuAZ3kf9dXd!H|^y)BYFEO8LKZj~_oH<^R&Xa>n&3|CjFH zx4)nAf9c*}zAgB_bZ`IV_muxj_j@+K&(_!T^F8q0kLEKfdcSX;?#g$M_5SdOUxNSB z<9q+dpMw8Wzx(|U!T+iEegAXte` z>OXrkzwg6M-+42?@VuM8^2QgwoAX&lkNx~(?;YR#oE&)a{fr(x?4b8fo9BoB)BV%< zKQ;6EcFo+H(YF4h_g3?1wmziy7JQn`|HHKLde~^MSLXkzi_Nzc{<6^bUuN?GH@x^( zM%((8-miZ7J?mR~zxnOY%)j#9@b9mgkCo9jKg$~*VC!pUw5`AC%{)K+pB}ILpL(Hf z$N$AW?yK30^nPN0TTd>dSzAuqd4Do{M!ogx?-D+XRu`L}y)qUhscv`}!38U%Hvs z6Z~Jg@quQ+7V7aA+t>5p|I*txn8yqLFWs!?9{gXrS&uUKzjSXh4-x!dy0?Tj|EK-! z^L_rOUT0q~?RdFr?l1Vi^#1GZ^M5Mel4%(kS_M%1|^!{L;U+{nF>xIt?{x9m_ z|I){I|Ces&6$by8Zv0~Kf9c+6z9aZQ-QN6r@PFxEZS#kM|4a8e<~`y6w10a3pL$t( z{a^LMod@xwzW=-pALC2C=RTWS|5y9ZygBXv(#LPxYj(>2rMq|jqhbD^_8&dqC9Y4N zuGjPn?o9c=^!2&%iYHV4FWrB;c2>&&rTgv+&QAHibiX;JPw;NMZy26i}!2`{!hKk{{8^}r(SLIvRMCD{o3Ax!T+h>G|z|s)7J;) z@8bW|i_-p2jnBvbshJPR{6Dq)pRM^B{NFO0=Y{`MFFg2R@PFz>wjL<+|8#rSyT<>i z*PCa<|EcBw)XbaQdd?0%{#JW^4}W%#_jdbx1pJ@wkNJN1zqs*#YWx)bPmR~Z|CwP5 z{tq99|5I~*_&@Ex2H$4>Pv^JJJQe;=z1sH2|HaMvziQ?`ofjO$LHrW{GXb6f%rc)K8^W*YW8RTpSSt3Ju9mF@$r55Ki%IV zJ0JX?y2$o_ykQ-0uIGFGPW4`IULOCa{qcbKKXtKrKj#1G{x?`3+S$mrum9xB1plY~ zSJ-y^U)=aV^%}cB{9oMoKQ%vpP@yj zG5$}D55)heci7iw=Kra;q}TsdueR?m_&@a;oA-zRQ_KIUi*0}WpL(-wSi3Pf zb>0)+%a<!W@@uPCFpY+3Bx)V$RT-z@QNY3tF>uC&aXd2Z*mTJAk~ ze9Hgn{`!wk`9F2xxcubD`&aq?gKR$F);CvY^gnm6@g8E^=ls0Zd+@ooUd&1Bz0W*5 zH|dzW!5fcOee_1}A?DG3x~kZl^@F!Py2*Q>`Mnp5HfQwQgIm1udH6qFPv-qG|4+^B zYj)n@`_n(4yECKlf7&1K_R`b4OSW6zwsMa*_lN(}_3Ak$C-^@#>jC5c)PrnZA@l## z1I@SL|Ge#d@PFzN_V+2w|5Nup$JU22|EKO_J`n$>9%k1U{}(s@Pd$2UYW|-d-_ZvN{6B4%|5J1Q@PBIgKlKpvam@cy4HL_dhyRNk z|EHG!Q{(ZN|EKO~eh>e5*Sj-<|LbJO!~d!K3~v?Y|HX~}^S0x?_wLX6`;MLwJYVnO z&67pRuiky^{r7OK|9JN`?}z`>{`f)spPG4r_`lOyOb`CA+o0yb|EZhj*9`to-L74u z;Q!S5`I(-kW&3u?)D7nq$WOG&H7~nroOjop_DQmIyf+@O*MjrC@pSjTJ|Uy=fAR;c z?}`6Y7pCX`>HhF~_&;rD{ulmFJ=nYx^Z&Fz^VN>4J=wR*|7m|3|L4v8zXzuj$YbF9 z-nw(D_kflu|EKN!ZT<`XPrd?whyPRKv36ISkV|J3c9GzG{AP;{UWA56JvKHS_ZD ze`@AMGXF1b{GX1;dbjvLHC_$>r{?-H|4+B)`ZE7d&GlpbUp>F=nl=jlPd&gs4`%+K z_Ajh|dhmbhehnK1|EKPLYQ5n9)QwI%CFAqumQ6Cf81owA&!2lW%6xzJYLe*%vzvL2 z@$I`e%v=w+d6P_U)~b2t{@KT4eeU>p*|*PLU$~Qb;duZ5;r+6FUe9)!-Yzt=4%)Awa}w#Uo%e%bT+`Zv$K9^Gxd^!R+3{~34oyuUwc=BLHC z&+b3;fQ%1}<~<&Ec&UueJ|642#{2)#{6MxpwdTRa*UsA*d>DOf@65*k9lC5o@PTZ{ z|EckK_&+t2sP)1Bu|NJ#&Hdy57Svtm^8oRG z^*>t^{2$x#e{tjgv_D=B|EK2p!2fA~{2TsHeOTK6sY}@az}|np&9|2>by)K6!E+bS zEnXe`9>@D`_Z)A|-~6!e&-^~~#Tjkuk9)Je@3}Y5@$+MU*8kPxm;clClK)f7|LOUl zzwA19aYdWaaMqorJJNqyIma8{XrCW@^Kz3AJ#)C~Sl*SAH*O2PlBPpMQP z_&+uC0-67(W?mrvPtA7b|EXDDH>c=Qe?N4x^@s0Vc8NFh`|y9-AK!=nQ?nlM{hcoM zKI4c|$&{`$y(^U~opkRp!@ElP!;_PHPxt0{KlGjE%{;*3{!_j2X!t+fUkmeZ_&+t? zZPDa1^=f$ z(XKE4Pkn+tzxY4BzFFTI|EI2Q9u@zm#``h#>=ia)YqH! zeUF^q+wZ@z&Fee3pqKY)wKIRd!VAXV-%4fmQ76~R*xvBedjD&;Iql@+lTq&$_56Br z@O^zcv`i|reaE}Q(3Zjf`Sx+0ga1<(Tu>1FU)&$PzqjbFQzi#rH^kPDD!*h;Mz?rm zw>Lg;#AUm@JB@3XTs>r`cfQT{d#c%vj9zohcJIFDwoX3(WUKdJ^M{pIZt)&IDKE)+ zaU{9@NxJ*b)k8qzqQ`zjkha4enUp%|Fr*rX*Tc7{9oMoKku~viyQx^ z9&LUJ{}(s@PmLdB{-3(g<^$sY)OfpY=Ks|FFUU!rIapM*XW&J_<1t@x-NHrQT<S`F!twlRG3gRd_4vJbu5I(fB{zKR(OW2l2*p+4>>g zg;P85`$g~m)AIQJqjxX!dIMjd=Z}xR^zN6u@qdp@e$ktGeM@`&(|eG4Ec~CY59{gT z|J2OWWB#9Bzcl_&&3e1|KQ*_<|EckB_aA)5yRXgvTllZ1z43PM{rM^HL9@CC|EJrZ zb!m^_|J0)|=^p%_dXR0$|EUMh>X{S|e$>x@pv|NEw&^1oUG12^cn`4kZ1X>P$a~EN)e^1>qCV0T5 zJ9Y&BhpD;e^FI}A{@{Z!|4;q@D7y=2tID-+F(IXPP%K;p<;JpV2c5Y z-Fj?~t;hDLM`R=2z3B!4F%hxryRT>M|Gl5N-fz5Tyl0FvhS!*L%{A9tv4Qp5_p@f# z7s3CjH+=bZ@PBH)PsIPJ`92W;r(SOJOz?kkrvwW)C=u;;s4a{FG~AA z_4EIEEBHTVmf^k5y21QjwT4CN=dQgz_`kT#8~OH^$6grxpSDl#GBEf*b?S_hg8x(B zy8j#V6DRojeE#Flshh4o-h1~izuCXnRrcQX^RL1G>3rEA|EJz&>-pmU)LVc0HTXX@ zUXb~JYUcH^{;ztY?a%zbxbc7L;{Cq{|EFGM^Z)RF>NU20FaA%>ygvM&dP#}@Q!g|B zhW}IJ0r7uv@bhQ}ceq|EZUm zpTqyD@pTv6^uScTU*_68pfB3r<2}c={!h((Km4DXd5HKwHS-eje`6 zcK%zf`G0!-)A&F22Kzpn`G2lIklw|1f407}H{Q?Y zH6|MWr^mP4KELpPYCJdoPtE#$_&;@ViT_hCHxGgTQ{w?`edj4Uza^m$^JYFE|I>En zli~k#d*+kb?Q?v)`8%7JnP~i<_FrV)0{^G|<^R-pEPH&uKkKF9|8#r2AM^jz%zMTE zsqv8bKlNf;j~M@_UTE_NZ9Ze^{cqoi-}GK+>&4pho2T}TsXw{yq~QP5``&*z_&@c3O4k2X z%m1mT7pLd{sb{ZE`#<#uHebm;pZt72viVH-KYczh-w*#6H}n70({0{U(_i1p^FRM= z*=FRpf`oLL<#{cR57TD_>|L1MKh53K#dA6P<{!hnS zVDp6Wf9i#wr|18vKi%x}g7=$i^XTw@YSz!i|EXE; z6#u8&;{ox1IzP_;#xkjVZD)Sx^hO7Iv&rkTjxbc5#=F2hvPrc0U5C5me z3*!IOc((hh9Ocb=4*#ddx8whGeCFTb|I~bb=e`axswwf6as|I_xcp0W8qHIEnnr{?D+{!h*C&*1;moG<=Q zjn~BgsquyQKQ+FuL;JjZJ^%D|BMPFn`M%>jC;EWLyLzwX&kG-SPc;5d$7dcO{x5F) zpE~?JH2)Vj{!hKa9uNL6?#fRL_4`|6*JJc2!@XI5`Kk3Iy;s=l|4FpeZzdu+r0Vn#el81`SDiS`|r}d6TR_z zvbapV8g ztnZ8eiyQx^Ua)3e@PF!gE7I%#s%I}v`#=5te%`W`!T+geEm|7EG{~_o^QJpSpcv{ow!9jS3qF|EF#;q-pSf>UM)|K9a5f ztL`wgWtjh0^Og$|^Z(S{%>yz2PmNdVzv2^be9`FxrsSXd-uc1%;rsA^apV8gcqaT` z-1t9r`_Wm!|EW9JdZhS2HS_WCf9gT@@6pWvQ+G3O#{9py@qg+;_WSbqKQ-$Ixi2qX;nrFlRsquXHKlPAPJErh|>d|9!Q)i`CdXKX8Z#&m2 z_8vJl?f(wilN8zqs*#YCItG|J0l>{!h*PLHwUu{!h*Q z*?wN|e#{HR|EYVMx5WRc@q-&C{E}$=pSBOO`I`8@UynX7_&*x|r^YAZ|I|b5{e}Ni z%m1mFABg|!()HZn{|4CiPt5;QckkCY_&;^GPK|^AQ+LX(ALjq5+nR^lUHQNQb$gp{ zhX0cv=-STKJ2L;L?$jpj|J2=DcL@GZ-K$-0SpQeeJg<7MpXaw9T;l(XHI^3>yEZ#s}j6 z)OaoYpBnFm|5LO6?VEp-&pkA2&r`vaE&^Y+Nxbc7LW(^w!{}(s@Pu;O$ld%4; zt~bs4zv}kQ8VCQU&T7&y_&>jWxt%>Yn)%OSjv4!L7Sb z^6u24b?|?>J@Xdve`-7@{!h;zey;Jj+r4v}H3|Mt`*S_b-}vom=KpCs*O&Q!>iP|n z-%mGh*(mXSbLRT8ne+ZKo98$Femish*-Zb(>oeXzw`GPm%z^cssAZxc`UG%kY5st9bwaYcqc?zI`g=c=)w=`yuAt;>L^N{|e^L4*rkE z|HX~}d-=&(!T;f-@PBIN4dVae#{cQ|Y{&m;yZoP8{x5F)pPJi$@zaBe#{V5Ud8W?; z9MK}#6N>MfcFD;zf(PXGRYxWp|EKNTKmIT7Z?@l4+IIc!I6K*OzP#JF;{m5#lPogh^Z(Q*mM znFomfQ{(ek|5uF%{ByxXKR$kl^?!9dybtsL;>Q1}SuYs>r)J(D{!d-*$g;uzsShlZ z_J6v6&HqzZD0^7&f9mRomJR+--Jw>U;Qw^Ip4QC&)AenCRNDWk>mQMx|EF$vWZM6! zHUCeI2gLuW@n85qy&qWL75}G}|MUILYvKRYtPhO;Q=`T4e`;HPI`}{JA+|sMPu;>k zuke5BX7+J||5Nk&!2hXFu=BVK?Pl*3h zGjH$1BhU2f)38qU;Qw^JvRXC{{!cyZxXQu*se77d#Q&+=*?dU+pE}Df82(S)#DFaR zPt82OacxfWX8mRSpUw}jhyPPEUl9MNZfEmK@qcQLkN;CQJJjZ@n*UR`vd?4upSq=e zp5g!0%=5$lscYKxWB#9-*B|~*eWJ~8#Q*8_&FdBar*3gvrLg|5-Var)Rt^3yZv3D2 zZ(QxT;Q!RkYMc=KpPKoe_&?o$(-Uh3|EI25vu5Jw6`vRJ&#%<+-k@%x zPpDffHDki|qVWsP4Bjul&auJ&sYm2CPZeIirD)25X9mC5W<<->RRcGBcenL$pK7wn zyT>`5Q`5_AOf>#aw;yp%LGXX-VfOoz_&;_2xi(MT{GU3{=KtaU)U4l&|5LNxFaA$G z?5wo^Q;)eIC-^`0Nf&hv{!cynf`Z`x)B`Um2>wr9cvXDar4fFrhg_m~= z{!cx~{2BgFU3h7iF#k`D=fnT0hugd}{9oMoKXqU8P53``FY`@f>P;^?Am@zW`v#rU zE;Zr6&%FDc(K`4)ZSQ9D5b=NN-gdq5e`-9S{rg%`kIPRF{~p)#`~v>{&71jr_&@DW z-qXW{?i#{a4DdH6r|AoE`MKQ;5?@PB&zH2zP``n@ZP-}L?IpWpqL zH$JV}eQ$UVwCAhyg|B+9nG;%5Gz z8h>}nwCDW(>06(C)_aiozgNdUlW6>(9{<4cY5x~@@7td6$2ZWt-^Hi>Bhe4#KknUk zeD~DHRUh+aecQLLf7FlP_o`m0;*pPd_qx1$>bJHJd-HtMJnA8D{2l&JkFVWD9fJQ; zcf2$w_&+rs6#u8j1LFVmc<`P0KQ-?M{GXb6koZ4!5A%NbKXu=WbAtcV@dw-dJ^Y_q z{!cCc7k87YxBBteUikCP-gv*OR!&GX{!h1OJ!$-(&Zob<{_uZl{3!lUjUUDTshKy3 z|5JCmFzx>)Ts$QBzv{LgJN{4I{EFVe|EaHd_L1QKY^Fx=fA4Nw5&Yj%KMza$zqM;p zr&JwTq+YsfXUhKDdxd>}wqfNE?_&FYwaPn%-uR)BcMtR~Hh+iz8#!%w+7sILRo(jf zcD{eCRI9f)-U$Dv`={}L>SFsollgz@Rpy!Se`@Aw*?f~CJ-+4N?dSVXZ+sE{Py1{B zpPKKt@PFzx=5g?UI)B#R#Q&*z{P;ibFZKlg7dP|&)T`GNr~RL;QHuXtZ{PO?|5wt# z{ry+k|3w}AUrGP<*I#M>SJEGU{IPk66aDy0r%Xv5FsqvP-+%lO{GaZB|DS&b|EK=; z=bwZBQ}6ugm*D@@@_*{h=J)V_>MiC0S^rlp|EHG!Q)~WT-1t8=^Zl6rr)IvN%^xa# zKFt4_PnfFb2mkkBn_s-=miRy2e!>3V%#VHN+u6VA$zLTJ|EK-&f%rc)^91pK>h<5J z{a@VpKlMuUe)zw*@qg;2_IhOgpBnFn|5Nk&#s9^9XP-~~eCL0?&%El#-V5ygW%H}N z@oqNX%A5H|=3l&-pJP78oArM2f4V>B1>yhV#{a4D2lziV-{<51^nBnI@PBdR|J3+5 z=Krae+x5i%sb`z7#Q&+M+vCCisqu&SKixm`{;)ynHRb`C|HuD%f33CofWiNj^rr94 z1NQFW+c)mT)8%=uvfBs$SF%4|IQYMko@pL1_`i~#T{8bq_qW2%&%CUk4}Q=5t2grk z&9f#N|EKe3ekuMhZu4-T>iDb=9QP=AH0= zo2!is9uoh6|5LBBd1B@leSf^4ozE1V&kFM}!T*)qAM?Cyf8S2?Kkd)@p0+(ljrR%u zujKagZN0|e|4JIqV*BT6f4oQVe&c0HviB3sBiyp z+3vLeE4lqcZ$J* zu6~X8Po7?HPu+Aw@PF!C&N?IbKlQ&${Ga;Wb9)5;r~crYwEt6o{chU-sWtyky==p( zF#k_2|EHe0dcFCrC-U_Ef8XXQ?H~4x_rFW#|7kn({P2HqUFjq|EFGK_t*8ApS+p> zclCnb{rGcjfBc{B55J55Q}cO`|5NjR!~eyN|5NklEBv1tKZO5N%m1n6|I{n&{+H(* z&4>#)ObAnpBit5|5NX<^Tq$EKexw& z|5LL+{!fkf!~dx_+jjh)dZV2`^Z(S`KmJe6?eTwVd>#Hz&ChrIpSL~!_kQY-ujiNR z@l)j-ZyqoHPupqypL&Tk{!hKst{47Kz25#jj{j4yvp-KvTHDi``C5-dvv}>I~2Cd+^ZoJU{E@okx1(2l0Q}&OBeU zQr`Gh=KpCs^Dyy$YUcgn|Ki5~sn^-<@qc>!>+SZ;|5GzR@TWg6@aA~`9L z|Ea(D{`=ItXD4`nwSRx`e>&dQ?|%sXPrdm&`+Qk;tM9+wUVr#M9glf`M?N^Q^!j}9 zW$=G~y{vy4bbG%3{<(VR?$qOB??^Q3|7tt)gYkd5{W9}`%>OIxwExrn^XHdqFT2;z zXN7q_=KpDb8vmzWQZoNf&7U9ef9e$*)ARq-D{Wrv-KmHD{ED~jNHwqch&R5E`G4Af zk*!zH{694wkokY=`PTS9HS62s|I~BM1LFVUX8m99<;AJ|+n)COpSgHhnE$8iH+$Lg z;Q!RD|I7S8_1w90`S-DW{d?N|_urp-^XIp`uRCLK>h=@f@$TB>gy8?Qf9vj5ga1?K z7dA)@*!f<*{=Kl>fQG3?Wj;vsA&vf>=&gM|^v)TQp8u!Y_bhA{=Krbtk4XDJb(b;e z^?%i@-;4jd`;F6r|HCWc|Ki5~#f|@q8~>;7ZntOtU)=b=(#{J0PtCkK{GU3KA8T!_i$Uk_x^4Byzze*9r5BJ=kU%A?; z>3MzT@h(04$3*v=_>=blJD)}`{_KqhJY?oCiN^owc>QdiCjL*2@5BG8@qqZhxS9W_ zmj63x=-A-@m_LaBQ}-F(Cip*f*S>9o|5LZ@P%HR9HS3e&|J3c;v`CdLdv<}ouf$Ki zbI>{7_%!DK$rs?^nE$87yKQ{?TE5_;@PBH&9R5$uys@UX zUa)S@{4)HXn)!A3KQ;6A@PF!#=IvJh;|A}p4I8GW-*=;Tmj(?|Z%n+&yMgt>yb0b7 zZGZfq&Zk4824Vi6y1lKh#`?eN);2Hg?H#3^)uev#f7;IcJm&wY3tO}d^Z(RZ|2J;@ zpPpZQB>qp^@n`ryHS-sl|EI=t;{Vjlm#p=1X)|APPMbS?JM$!&|EK+F{GYmO`;Ni? zsd;_j|I~TeN&nS3Kk40uWG5T{8h?L1D5IH28E@x&;?DGUnd{x+E93n$Z=bn6vorT+ zJ?i*)nLaV6Rnq7E4{w)~oClbBy)yk?Z}S=P{S9i}EYXA8CcR*$2Q2K6eEdCfZ9TWh zANJ{#m*{hHJ0<$;9GkZh?cXamKhb>N#M?8kM`mYwK73Yu`~TLNx6kbV;R_E;dce&6 z|9_4D`+L(=Umq6#r{?_df2S9HnwbBmW;^~*ji+P%Up3qDe{nPaPmOP5{+}A(hW}G@ zd;Fi8<5#*S*`0oWz_;TQ+q`%Gw4x8E1Rse1J0dIDdp^3)x3fO+?CjF!_$N%d&yUCb z_b6N1T)z=B@A2EyZF(fT;{3aPJO1*^zNL--o3rFD-_GNIzA)K06yI68-TcwW5v6^Y z%_C#}pB~>q=8Gzt|5G1e^WE@&YR+#+?aBUl=#Q?LT>AW)Uu6E@lYbTk56Jqy_&@a# zhaD39pZZu^&z1Rq>M}>A{a@Vpzvfw=1^8(>H6R=ng6G5TIs0Z|I}S=o+b1D)cJNk_&+u4>Ei#?jqLLk z|EI2K>q+DP)JK|k#Q&+eJ^oMUhu_2hsqvW)uO8#CFZ$~>qrLHi-Peus#t%Ndexx_+ z1LOa6JmxXt|J0Suv*Q2M#~)rU_4k&ce*5E&JSsJE+YoPFulPT`U+}m1KQ-?^=KrZ{ z)TojAWY<9NTD5A0^?&vLX;!0FiuHfvuGn#aH$Ic~e|0>X^?$uJDQ$g@A~owHtEf9k=Pbq)Sc`wtn{E%-mR{GVF>Pc8qa;|;X+en)=t zsvm!pt`U`-|h_|J1ApjQ>;jyP{|Cf4YCXApTFy z{6PF)-1tBBu&d0Y+Wfz`@qc=JctZSN-1t8=>;2;Y)Prn3A^uOt<9zUc>fV=iOEq}^ zA>Y5h&1>v;|AXFmyYAmSP`bbQzVqkbpXmEvy3f0ty+8kb^S$2PZGZfq?ys-CAMk(b z{^oV@e`>rS{!iWg!kpm$)LkztNIm-c?Y_OI&3BwKX;Nw1^SkZziQdfPJG9_7Z+ss9 zPsgM2e`>GsT@#Q&*-$29+^F0l2vS^rnv z^t?R2-zv(V+&6qbmVezqzW?%`@XS+T{ohB=?H|0~Cu>&+|EHe4aYOKb>Seok1^=gJ zeJ%W-dY$<={GXcnD)>J&^Q!E>y_s)?|I>CF|EK2rI{cq{r5z9dr)HiB{!hK+t9`-$ zsaM(hsQ5pdITCy$jsH`xvH5BEKi}W(kNJOUzRxN*xm}T&#o!freE2^#J_rA&W}XfH zPtEs_%>Pp}4-5aNUb^G+;Qug5_@v#x{}KG38sE2Mf4!o(@qcmOQn8jFZ{NOs!T;&_ ztM`5#{GWRF-+u=Gr`~J#$NWF_H^2NE{GWP{%>!ipU-fSDfVTdgUmyJ6Yhx-V+P=T{ z>x-%rFeqqs}iMI6vz1iQ^7xb3@)AO^j#Q&*T&lmrvUT$8m&DTG8 zuQ1Pt|BJWd|I}=M?bzMkYi#}B`b)Ma`h`iGz43uH3)Uz4sh?MQudws6`A&(p`A^<+ z&HtGXnX1<#^Zd+@c;oqOzEq;|e>z{ba}*h_&?o0>!aiU)JwkkF8Dw7GCN=VpL(r*zmETl8~^9Wx9#}9xbc7LO<#W-{9oMo zKlKvx2KYbqJo`T0{@Xh}53lK`W&(o;TvX!!v_HNG|EFGPUJw7L#&_WV)bf97*4xDY zC3~_r$HV_=d;0i?<*Ky(i3;(B{W9!4>|J3+E{GWRMM(g{I_MWpYtk3TK$%^#+Kkfg>n=^U5 zzWwUE<_7<#?d^I`4E|5uJnO08|I|4p{!cw}*loo)AmQs zJu~<}^#>R94)g!i@0`;;_&@arcfiVA1T{I)T{;zt?hSkCUskQ#Edco!` z!T;&~J=J_4{!d-BCB6QydWLxq{GWQdc|ZK0dgjKo|MSmZd%p00>RILi@qg+$=JW7> zYCH<_|I~OA{GWQJ`A__xn)eI-Pt80({GXb6fA~N3EPH)EwSH}$nW^CU=9o{ZRdtj1 zbbCF&GG?3iXSN;xr~PM}=fnTSjsH{QUGaZ$cQyZ~o?$*1|EKez@qg;s_I|+ssX0IV zU)=aVHSa(CpPG4p_`kUEf9iSm`N8}@^#c2O#r!`t?|=NCn$H*fpPJ7f{9oMoKQ;6D z@PBdR|J3q-YJ4I7PmR~Z|Eck6_&+tjkAnYG;|=kDYL1WpQ*(U$pL&IT{^9@B+#dg@ zW}YGbPmKq^balIYJ%6igel7k_&Hng5Z}WD$-_6a}-w(JRuP@8@#`|6LT_^8l_IO$z z(bap6_5P;ay;s}*ANB3&&GU2Z`Mte)KJ2~{jsMg6$p5MFh4?@9TD!ejFK_ujoj;BL zQ{x%&e`=l&n|+pl>92jl??>_T%zi)0oAbl}Y5z6$dcyyyxqtkhdW-%35B^W*N8|t0 zct8A~8ZX$P`o-S(zw7cY_1~)f9mgk*q@qIbhU5ayFcy! zwEe3ee+m9i{f+&84*pO5oz3^g|Ec$w_xtkgo4vQ%pGV4nc8m9xZ}$fOr~R4t{?;wG z`Sn<5z7PMW>$Bb-AM^jzYj^Jn{!iCm{x5F)pL*5jyMq7I?P>gr+?ph?8(Q1|5IN#{=DG-)UBGO*Z)|QB#`OJ6o_3wZALuv>A zr*1#6aqxfYb^{uv@PFzywjKYcZZ|mX|J3H;u%{(;xpBjJ2{6BSfTMzi!S7zq#`+P+3 zd3j^or-sj+m1z8*_Rlv@hyPP|HgET3{dvAW9&k>N`QG?5{GX0L!nWi8)U0ni`sGF5 z!>zOCEcPCGR(|TJT}!+R&$NFZKV(^=@qap>F{ft-|EC^h>q#*G&)d8k>;J}$|5M}P z@PBI7BgX%!HUBSe{GS>>hyRNk|EC^d>+9nG;>Q1}@pSk5-=N_wga1<(+WgOI z=cfwP0}8WJ?@dez4&(bbv-8l7U%L9FTK}+*H zHvdmvfX4rMn+L@IsquoW|6BX9Pr`g9=A*Ixuexo$I>G;G|NLrog8$R@uC*El|EF%! zv_XxnA2LGp)|5MBVsqljx@5al# z<^Q%{@^SEiJU-_Cskt8bKQ-Qp`G4v`w*D^j|I`Cpv<&nA)Oe_k z&shIg&o}e*SpQee^SAVY(q{eVwnyCI+j;)+e>y(TKmJe6`m^{yHS;6!f9hWCvxEOr z_szEXBj*3qy|X(czHiQ4|8}^oj~#n2JYw8KZNBFJ)|vh;bDm(P2h8+)nZ7WyGuPkE zJb&hU#^*P{<|)RF-;BF!$K>PdX6xz2+k50E{o~-AWDn|?+`lj@dHg{c{x8!n{>(YKUa)Vg$Wf<@kdB#HzNZvml z4F6ZO|KINa#-8!mv=g^|5WFA05dY_GkB9kxYR(7$7dQSdZv0=|_&@a#c6*(^q z|HaMvzw!Re|5IljSuyxOb@s89!u&sV-O5J=|EFgD8~#ttyglas#f|?{l}S-@PE2} z-D4^T|EF$v+zG+|sq5JK*7!elJzHNF|EI?L;s4aNYu66`@0Zpe2mj0Oli>f<{JshP zPtBhn=XdDu-MC);)GZzQMV(yFm-k!z^Q=a#r1xvmtbSs9P5bj|ynnU&byLj$TY3H9 z;Q#tGs~r5_F|!MU|GQ{V$Ke0eokzD0{!cCcr|xooe(-_Fi zdk?)RKXvt&OTCBKe6pwKF7Y04aeiv%i;EMz`{qU7!LynF)A{wg%;wpd|5FdYut%8x z7dQS--S;A!=XJ~6L^J=-x0{#4|EYVKhdSzlnSTFxKm4DrM_==J_&;?o^FYl1Q}?#@ zds+WiJ?y;f;Q!*r|Ealt%>R36*r4G5Xy*T^hugd{{GWQnMcJ(1;m!49{-2JAXT<-h z@p|_A!M;Cjzdu~s^<7%F*5&8`_s(-Q;)bLJ^xS5 z{6^;gshK}`cJJ4`3+?$GY5q^o2aW$zv;Oa@tuOihc*EbPzL@B58o%iKehUAmW}YPe zFK+yw8efY4Q}cer|EcBw)SCaN&bl-=_&;^WD>?=Lr^fH$|Ke`3@K%33c+sJ+-r~*r z($`G9*}IQFTbY_ z9#hYI)vtfpe6~8?-`hMt{GX2ZgLy&b|Ea$=@7JbvH9vpa*1z-q>i6G+|I_|o{PIii zf9f4S|HAj{em%GU^fTYTdvCGzdF}i8MC1ST`jG!qeaSC z{!d-}{V&1)#f|?{Gd~dj7dQS-E&r!pw)aQYfAsBB?e&8H)AgBV+wp(u`Q`)hf9iR* zzxfmI#peIar+6>2_Xqw@_s4p=_&+uN4*#cSejolXZd*Uod#=47@qc#5}|EHd3eh>c__l;#Hcys*y6UTdVzBWI{8y}4S)BWK; z@qg+C_I_g4mwMs;pMw9>`7&E&{;y>FbUR+~e^Hwa^ZoIg_ISN{{>-m=m(1szqT@3!Ecm~Y57%-ae6uVj0=&Ht730y|#te$Gs zznx!Vd+>iczU?3UUrFOb@PDiky>G=m1$6L#+F$-p$G7=_!T*)??5(@g{;#C*V0Qj_ zI{$?>|1bEzlI`=>ZO4!LcIN-t=Y5`@{|Emylb;{nm*0_||EJ?M>2zb-|CJoCW4%Xs zef$3XI=ss3-+RRH`-1<|@vpz`gW&(vk4?TS%>PqgbHPQy|EZ^5GA#H%^#^D73;s|2 z))hm;`oHSkZ{8F9pZc@U{$ulE@A325v?=ZXw0-{C_4s1nzRcF=W&WSu&!3sU!2hY4 z_s9Cb>LOcD7yqZ8X6r@b|I~A>ng6HH9~%Ex+Fu0!r)FLl{!h*Np7=lYa=SnLpL(Hr zLHwV3k$FM*ZI%2KTmFJa-=uDEcM>ezCYb{MI~=MApTFs$9K&?x{7aK zWj?H2o2uUUwE;t_d*kgMxV(lpo~-zxTHb4{D}PYOdxQOa99>+`oArL5+TXyNdAs;O zoe$m)|EFd<{!fi(!~eyN|5Nk(CCxr;>&NHkA^uO-kNLCsKQ+H!Q~RN8zkYbTN1Nv6 zpLSc9;NiGF>y7KF*?!_VoxJ&d0o&%y`M&ggw?yOr^n9@$|EFfYu-PSVejnk0SNkV= z)|`Rf-2V2Rg^9-h>G6bl-!}hG$EWdsYWyDlPtANn{GT2l&oBN@&F%4j+8^(S|BD;{ zr`~R!vSF2TytkSE`>OqU-uO`bpU#)Y|EV|I{B-TXDW};tD{(d;L%cMjz|4-MO&rjz6#f|?{ui3UMwc+|Zy;qyZ#{cR5 zSicwl7x#%3?)6@|vkHf9l27Uw;3f-~W;l|EKd?XzKyv z|I`aMYzh8PjrYUMD z-G0W>?p7(y?_1A*`)4xAFe9wg7 z|J3bT)J{GA{5$#j_r9i`j|~1#-FbMu;Q!PG1Dgi_r_Sr&IQTzx`vLWW|5JAy)F7Oz~KFQ4Qn3!pSrKD_ly5i_p$k9_&;^ulWg9V`9HP% zU)=aVHC_q-r)GU&{GXbC|9+O z8!w3e)Bas-{aO5|N+R;LQBs|8)C)<_qzE z>S3pK2>vhb`Sq6jcD&z9-B);zKCNTw=Cf9MkFoiGCr>O+bjO!gdE?=ZoxM8I_&;4g z{2TNC)U3~o|5Fb(ABq1{7utM9{GXcR!{q^NuKVN#oVf(y!zkJm22k(C7 zY4Lx0eX&3OFK+yw8jpwniyQx^?qlmi;s4a!AM^jzBSxmz|5XpS`JT-GQx}%_KlLEH zKi2h^|JSZ|6@H&{GXcjNSXhq{aKHc^?$XU{aOE4o!z!W@PF$3 z4!ObqsRy;o4)g!ieOjjH|Eb%yYL>d_@Js!8?c25t{x56lyTJqEgYbW9d>8&NZsz~p z``J6e|FIqarykO#ZSa3;)(^)2sS8`R4*pM#2W0-An)O}re`<;X8xagOzU>R|EWitU&8;XIX?bR&GV1{Q#0=j|EKPp)js$?HLnN! zpE|EY$J8S)mNp&?|EKHC`mp#vHP;XSr{?5k?fCvO zJJaiB&dVE~W9x%Qek}9xX0Bg6IOF~@Jz-`K&hU`~Gkhekhxq<^KH|>whpZPJZ_k_$ zn7KaikoL*_GrMPpq-V_hyu{na_t&dga$aGk_sjHv|5wlV-}cAD#pjcGf0^gQ@$i2) zmV3+B|Hc2UKj_Wi|KNl8KlMQe9}xVXcZvT~Q2QjsJ@q|EHG!Qy*0J(BS{n2becHW6S;i`01smmUad6WB5PqPvig82bVo4biT!3W~~ z`pvt2THN?Qb+zM;3jR-B<1tU{)&okr)(KU^{6C#fqpE5Dr*2aH_%Q!Z zeQb^D!T+gKhnEfhPmi~pc|ZK0n)!eDKlMQemr0$|yR^$!I5IWx-U+4WSF>hnO2yKy zUq9{tbbpQO)d>Di-Lyfi;Q!Rk8rBZ}Pu<%5KlA_8+0E(({}(sw|ElxMGi9~A+B>I7 z-P92s$9s3Fadepfr~PwmJyiUkx^|_s|5MjH?&#qE;_kloQokPck3S~$^u|lP@rU?7 z?N8(X)XX2m|EZZbi2qYFpAY}1#_Qq#;>Q1}Tig2w|EK5Yc)LCRPkn-|kBt9Qw=!>t z|5G=&+cW=9&3d=Y|5Mksd4Tvob(rS{!fkH!~dx(9)4)>e`@As zGXF1b{GT4*(G?C0{!fiB#sBI3(Wv4v!T+hVj;Iv;pSt~#mBai$HS6c%|J04DRuBG9 z&HDxar)E7~=Krbjea!z;%!NL&KI8ecYpG z@NB~_E=YaUW~nzGaN|)+yzy%IKiwX`g#YutBsbOPUkiMHJlZ99&iBSQJ$&vwZ+z4B zKh5>q_rIV^>iLy(5Hh&HOr~Uhn>lFN- z8eeC>U+mkp{;$qg{!cCcr^ff;|J3-tCMW#MkH>t#LBG77=qp#h=FR%8_&?pA^Si75 ztKRs)cMf_b(fB{@j}OED#a;8s7raN0OZz`PzoRbek;4C}@pr8MtH$4bQ1My6{UGyU z>%M+E(SOZ<%A0wD_&?o0jsH{k8`n4ZKXu>B`UL-{?q~iG{}=bBUmo#hJ!Sl#&abDv zfAD|WpZR?FKebt`)VPZt@aFyWSfBg7d3}A_;687B-?oGA^~TrY|8##N?Df-R+Fib# z^|A*&b*Fb9^P*Q?GugZ6CHC*5!|(9!WY6DcZEpAOaz%RnpN`MtKm6O#>*=>UV zQ`b4IUhseF5s!=t{?80t@P7}#_H6Kf>Ny*h2mhzW|5dteM3K$R3*K+h&Yi*ksadZL z|EFeNm95`ZWHUyB?_xfl&G$&O%_{NzmzpoS{lh+q?*4EuZ~WiE<9c}G|LnU@??vDJ z82q2^pT_^GSDK$<{-1h9@KZV7>+Jh6{GT502HTGRQ*X0*Vfa5a^Dyv#7@-Hhxw`=W zH{-EZzMVeciWc7M?E6>zpZ4Es>(}D{)Z5L&;s4ZZ$N#BWUl#wT-tyD$!T+hh`R(`M z|I~Z`{L4JViGKgg6U6`N{CC;@_&@cRzu9`YUmoYZ>!+X0a~#SFXxN@Q{(;cf9f?q{ucb7_uij^|BD;{r(X5#kHP<`*X;e-yxA(>zQH^k^Z&Gc zy}cgIfB5+=G#`rp)A=vjyWiH=o9T~liM<}L8!^qB^?`q?JjI*!fiGSCVWQ2i`0?<6 z=35f|>IbiT;|1zo`m#6kHSvEs-#O+P%-49&{rU&|jW_Ra{Gaxx@qcRO1LFVm_-Oo} zdb;h8|5MMf^TGeAIe+|L-1t8=o)`b8`&(_-5C5lLYU};t|Keu$mm05&HPZWs_b>k) zH~vq}^}_$LMlk-5d4Bjm^&0bl1<#z|`}28-|I_VRKOFz3UT&W+_&@auo4SJoTwPDrtG4Uo&H38(^ImHAXV=%8`K|ar9dE(5^!mT*MJ4`E%{({e|HX~} zQ!iybV4MG^Ua)=}ub(`f-zUp<1^=gh^j|ZA|5IN%aTY(1eE+7o*9HHl<2A1QaPWWH zzjL!Ug8x&G7UT^0pZbCGE(rcl{pqE{ga1>%b7r65|GY0x`#<%b zf2IAOdg{~nU%xWU|5M{5@PF!s8#f34r}uA>t+$B(Q_tT1dGLSgIXiX+|EFfY zrG5V8>GNY*iT{fm|EHd7UXS^IYUV%M=Wm{V{w&@31)tB}OFrMt=ePG9+dgUS+(ehF zvdDY39shw*%My+M)A1LYkHP<`7n#4q|EXt~KgIv4XWHxUtlvJ*GvgJ!-%Rs+_&@b$ zHZKeRr0mKRte$`G4wpc0A_)so9SIQ!m=JhoA5HIzQTe{(H~2 z$M<8)!@apZ{!jaJ{`fzgAC3Q0XM|5M}HChe>2jR(a4X*=`v@PBH2AO25` z&%^)4jsH`#KmJdRC&T}#@pJe;HRrRXQe*G=w!L;%Q*Y)Q;{SC0_qKO-eG@UIcn8S-uS=9zfSPx z_YW48xh2sTSH9Jod4@;UyDic9KfNCK`yu`>Zv3B`^^x&^>eV*y6#u7||5MBV>G~Fz z_`kUEe`@w;{az+XXx<(Fr=GuhZSa5UIV;otPd$4@ahU(7p1EvA@PF!g*8e{I+5CIQ zcASd$n{Qqa|EHe5aDMQA>UTc*IQT#Pd&8@b-xd6yx^t_#!T;&s=Njae3;s{tX;|Ih z|J0oeTLk~7&g&HO(#o(lh`?qll#{!iW0{8z&(=jLD5zI*U}xnpfT)raSKcRHg(s@C80 z^543>TkubP%**{*ZGm^c691>$^ZWEyRb1@1A7sBTKcx8*?;+;@n)hGoJ^0l2Dg2+# zXXvR}!T+g;pWZ(BKlQ1nO^Z#`H*pB~;`}Ml(egFRE zAt!d*kZAm$_GdmH{!h((zA7(n_Wg&QlAHQ*<`!=oZJomZ>3l|+AN(PEn?HW$^(`H> z-J9d%|8zY$KK@UQKg9p(cr^Y`jgQ3tsYjXTduRI|Z#>|tR$uz@@Ph9S`pSF6NgY%7 zUh=i~@G%{N|I_hU{}=zK=Ji}>(RaQ--VXn#^Tp%g|J1x*@qcPw-&-&G!Cz0z^P76t z{zU)dwI36G)!d)F@q&YQ{+ww1pN=1nXZ}x(S7iNPHJ%awr)GX2^Z(SnhP4R(Pp|(0 zL(=pA)P=*-{?B_z$FTmdIw!AASpQc&uvL2fUv*)dq*uwDS4HFh0*STez;Q!RDAB_Lg{#oX)@PFFg!8{cHPmKrc)!;(!z6G6w|I_xdxdp-hsfXHp zK-T|Nv;HXlPo3YkRq%g14}3lNKRh4)PmMpq|Hb|2mE#hP|I0q=wcr6+KbZM{>JeGy zY0dws@mS3NQ*-_Be{tjg;>Q1}@l(wIiyQx^mj8tK z@PFzu2c`X=8b8MTKlMSjo-F=PZQLyQzqs*#YP=x+FK+ywTK+F?{9oMozqs*#>Xgmr zWB#8S56JvKHNFo2r^jE`=5OKu)JK#l8~mU4r}2Mk=JPTCPtEc0e`G8KXu4?dq>ZX;BPn~n^?S6e&uXp9|le}5q7ytJ~^;d!qtafbW)Ej?I z^zC>*{GX0jty;C<|J1A}n)S)8em-q#R!g0lTiVU59+$eS=oa68P_@dbk2;lhs{EnB z|LO6u9xMJ&eUx24{GXcjeer+lnnza({!iy~RPDOK|EZ6uoA!Td=9@A9Pu-|dqu~G4 ztsB+}{!g9Nq<-*!YUb-sYI&{SKD$YyF#k{6n>KG0{GYm|{XPf&PtEO_|EF%(pkDBQ z>gx6E_scq8;oB=!s}cO4wpTmxxD@_RkH1RQO2PlB@tXKQ?O(O>k-`6|8y;IO_&;@> zBh&N$)XW3K|EZbJhyPPEpAY{R_vTa2^XC1=`oG$Kbh+|j{a0 zDy4E(o#gKi=I7!6^nT&>!~8#WSMzkt|5JCWQz!U8HS_TBf9eLcs|Ek3W;^~*jaSA0 zsquXHKQ-PD|EF%#pi%ID>X!EUXa1j>*FXMG&H3a1)a@EKO%=v%Z-~BDN7Hw&t zAADTDmX%T;RM_HuUjJ69bzg1r?l(HU{_pv>7X%+T!u%fV|EgI(7XPP~|5NuqColNF zm$u{w|JUp6wEt7H9sj3hJO0o6{LaDusry{mHP!ncEByTMLl=)$Ho^pM5mf`((Qw zw*G@R^Yl)*YIdUWe|kJ@|LUGu-UH9=5d5FE_d2g#@PF#w=eJKia@}WsKCJ)y$*5`G zct8A~_NNc7JToIRX`7Lj@+|CO z;>Q1}nGc8mQ};GcIR1}+_~YaGdusjTiJt!PW8OSJJ0E>C(T898h<8t$XLsQ0hyD27 zZ2evQpWmOofAD{5?hpT`#s}j6)c8RBpSrir^TYqC``Gh!==Qt4$Jlzq_&;qQW!@A2 zr{?vC|5Nk+#s8`MnP0{KsSC~1?L2alH_tczPuuC?BX0G_Km4j5sq3hXDFyk~A$ni}!)DDThKrv0DxU$A{A>u(i(`AF;F z`#>vMVYeINc$+nFDQ|5M{hY;7iQz7L)MOK)$!FP*fur#Iinb^W-zH}gYmmW4O# zr526v?7h(Dxm`D+z?=17@qaph+P+Km-e{h1{EHnEopnolZ#*FW@3tvzf|uN6o(unn z3Bv!e9sj588_jp&|J3-efKlN@~ zpZCLSYWnf_{Psuif4cwAfBBX5?fmi3w*H+r^Zjf-j`voZKZgI)?YaM^FC3F-*8kP^ z^>#k2|Eu2k%O9yP+E*xT+g`s?Id6QP&HwTHW4@ow2l8gVAM5|>c*W-TSpQeO$~>X@ z1K*$HE!h0qRK31vn_raZOFI8BRnPxMJD;!r_|}`_pY!pT-W-3&<-5G`fn!^2_b#^i za_hg`rR z{!h*NxA?!fzkKAqM4vV6EpOJx#sBI4@pJe;^-}Wz_&;6mY4(1^|EXu#`vw1}-e~Vn z{GWQgy`S-aYPI5&x&# zv;HFfPtE$r_&@a``#v83r)It&^Z(Qw5C7+FpNIHA^%{FU;{VjVUhsc$n}73OWY_zQ z+b&Hs{;y)Wtl;yQ&xrq1<5ls0>X~+Y{GWQ3JwNzA^?bX2_`kUAFCeU08;*~Uw(U7; zyo%l4n|XuyKW*pdhwY!MW}cNjAGvyb%)7GrcHaCvvB#Ha{Gayc=a0RfbM<;)zLm{~ z^JcrPx9!b*G5nwIe}&B>Wc}Z`ng6F=yyGjL-#p#llF!5ZNAF_h8Jhpo{tGv35B^X4 z&sdT6f9j|H^%;-XZ$II-8NvT)dxzX>@vFYQ+wp1tr|lz}yb}DMdgzb`g8x%rckRc) z|EXV?ba$Blr=E1)CBgrx<^R-go!$$-o2U2Z+vA4t{`UUrt@~{K_dD`*y{An1zPrbG(TsbpLzN`WxZefd`&d|&$pXb!T-gL|5Hyl--iE-8~>+feP8@v-1tBB+>-f! z>N&Rm$eT9i9eaH1wC}U?-TdiRZ#*CVPur*1?eTx=|Cl#?Yw_24U7lzayw|7p__E4= z?>*JFti$jPuGVwfA8lahv%+^-Oy|zS!sJM4x+JCGSP%1Mz=4KK<>>$NTo>*6+?f!5a^V|I_|U z%=h8{;>Q1}`Fz0t#f|@q8~+zK{!h*0!T+g??DGfzr|ZZ1xA?!fZC~G?KOf`&bbCA- z{!hKpJ}<{!(ZL@dUd?P!zMlWtcK`T4^&GoB{!fh$#Q&+~|I~b5GXGD_=PmwE%{)c? zpPJ80{GWQYU2puKdadpMOPhh-Jf7UbLT|j|go}rGvwh}W!@O79JmfO3jVNvV`O$aI zC~y9L!u&toAD*B2e{mmo;;G)u*Bz5{x;OK6@qc>#aX$DzHRpr>Q**uF8h(K{{%_os z7kTsi;Q#b|;qCB$YP=u*Psfx0Q}4EUdaV6JecUaQxE&?XRlBDKOJwD&HKausTW$m@bsg8d%DLPkCnE0Km4Ee zU$ACf@PBIgzqpzIr=DB9I`}^|^8mL#_>6B~xU4w%KRvz$OVj>O{pq4b!T+h>o;EG` zKmGf{lW)Ef{GYmBdt1-Z=Kty6$LeJt7W|*OU}&A-|J2OyJMG-}^Y!ncxdZB_@+N=a zUC-wK;s3O~@sP&B|EXJ=@5BG8TbW;C{-3&Vc+=qj)T2&m8~mRdKZgH{8~>-qTjBrW z#{a3A|Hk~kxM!R*J%7j-xxxG4_waw}PIkWdKXvO7O@seaw;k0y_&;@L^H2ST&&j{H zQ*Q8noy%#(E_ zHS_xLe`@Ac;{VjFXN~{U>q-7k&3eE1KXveW=Ks{p>%;%4xqXX+e)Z<|QUU{aq<|Ge$`;s4ZlGyI<#UxxpSoArO=X8xa=`^W#O zN4CvQ-BsgO@8PXG1plY&&GD~1_BP+n<2nES(&q7>T5h6mr-w}{ZLVM6119-)y5RcK zX8s@kPv^t>%=kYweh~ks^T9_l|4+^P1OKPy^@RUZkFm!azkfz$c)Uz+m)V)#FVnYW z`oGN1oJW_r9&YCGGUw<0|NL+Kc({IXXWqVJyX5@5+>S{P*(WEt{&By&q%XwR#>XF; zG4F3=`{d_SW@q}r%+Bcd#2aR z^naP1Io~g{nSU0a-~X@MYU{3Y{&np<^R;o3&j7a@l5zXHMhtA#eMZ-cX^jN?BL-4p1J6$-~kV^r<3`A zYOWvtFK+ywn&$)mr{f=PUW)mD>hd;E4gaS;*5<>le)V?m`jwAM9oQt<_&;4Ad>{TV z?t&YVjsMg38pl@&{x5Fk|EcR%KQZ_}ollb*Cj|eeu5Ihp;{VhYjy^p2KlMRnQ^EhK z@s0RDHS^c-f9m7Rr{Vw9jci_8y~l3yX1>{VPu}Rw`lSPF-{j}pv~iu_|8)NJUkz^X z?X4Q5=l^MY%lfr~|5Gy$4gaUcS26!j&3rWG|EZaehW}G{XwW$LKXrDarosQIo7Za+ z{GYmEje5cVsky#AdXDqsHLF!EtpBU+%}%Hs{GYl(rL_N3H$J*z@PF!h6%G&c|J1Bc zi~mzMJ>=lv|J3+P{Ga;RGKZz`f9i6!J}>@HUA}zU|EZ5T{K(+{)RoE|mBRn2Pb_y# zs`4dgde=RwO7MSrzL}qg|5G=pQZ@C=_|trU)~jazpSIKZKQ$h<{)AI}|3*h0oBHdP zlfA1PeN6Cwem-`4{NKMCJ{x>2uXp^Pn&%h)r|!_8PVj%~jt%Pu|EFfYB>qp`ypjF; zgsuOp=JkgEiyQx^#{1#_)J^Kv3;s{d>yh<;)y(t5|EYO>;{W2t|EckV_&+tbXZ_#7 zO`i+?uTjG$!T+gS*xv{0{CmK(7i#=->i$0u?$o$d%f!#GW2;q7blIxMCpyyy;uGVa ze>DE@kVaX-|K+zkKKMWNX`^z2|5FdJzn@<y)#|oB3pCp0Ln+fO*5ozs~m_cu}|D|8)D|=iBFb*7nldc|LO5`JufTxKXuQGI;OU? zFY@j9EBv3fKQ;5<@PF#Q=F#wf>Ry+1 z4*pM%m-Tw_f9f8#9sj51`s4rN#{a2%+4dGg9!~VoRu6gOF|V%pV4|P?=6>&<7k5w1 zSa@HecfWS8cW?89|EJ^c{Pj2U5GQ)$1Mz=)JiC5Q`#&}F`S5@04d&sFIptVy*7s%ppSEwa`^W$3 z{ zm*@`Fzx7^e^ZMS~xW{|-55KW~qW2oRJ~m&;d*!|#nZM+{s>J{4{MVW<#s8_d*!|=G z)c8O1AAWn*%fRxa+r7T5$a}iI9&11JiT6VLe)p+iA9^pa z_ZR+8$HU*^|I~P}EtOvPUTHoH|EKel|I_m|)qF;^-B0`WnRb7V{qrB*d|!ObDUW#b zd2nBq2fVfZua1x3!~dygnrFlRsb`sYWB#9-&kN@NskuJ*KQ&$t|EKd^|Lu3d|HX~} zQ?oz*PrZ5H53DEdz3v;lSFZO;n}>rX(*896t;XZw|Ki5~#cl5wZ*G6)-m>0HZ2dp{ zpFU4k*zs&W<)^y+a(jMk-lX?Z^9QzmwD(+_zhgcv(dO5@7n-jy-{!s8dtlX0SH0ZUN3{R;=K9+6o2%=G7kvB0OT1YR*!-C{ z{s;f3{h8l||5G!+2>%ziosZvNv0dNb|4Po6HoxiH7i~}bKb`O59cllk#{ZcQ%~Q`` zhi^L}Pxm)-)q*u$9R2v4{iPi*T;Kc;UoB1 z?~5<}fcKC0KPTMI`^)?Gvo7R%dVhGq0Q>&qYVX&_b_xDZ@6UHHDdhc~r{43*GP4s|EZb(hyRNk{};D?KIiH48sBE0-`;qOG^?rVf&D-GrbiVVq?h5`dZv3CF@0@LR{mlPqJL_TN|I}0L`FL#UVfng0 z=8@w6)U1ch{J*&Ie`@Ay;{VhO?eXIO;%;(BWpDXEZC`BfSNvbxSAJeC(H#z|;l0#8 zAAYY@E9!4kMV;y-`j)ZvyzyY&Z)}igyDx9%|1Fx*#CxH6?z4t9_v^#w;VW0R^yc%@ zY?$|QYy6+CCm#B#VeR~Q8|?V_KRrHtKK@V7x90z;HUCe|pU3fkYUXh>|4+@lU;Lk% z^@#C*>M)A# ze{tjg)En&j;{VimKm4DX_2}_`YW}?Q?8q|{z2nNWz4`M`{fEx=X8qvv-#OnK&-vEk z3lp97@Fo8IY_RkH^}Wly@q5?QyWIC@{obivuJr!ge%}E9r}JaIVEmt&^@b;#|5Gz> zu*SUW^Ut5yFnBlCLq2oIjfoz5(*$o`FF)UXbD|%A;ude_NoK!#t2e(NvFYEpdGmU` zY34-lVw>Mtd-)`9=KtB>#}j?_*LQfYx9fk{ZiMCW|L47GO_=|uo^9T5>9!|JZ*TJe$9?ydH|zf%^XJpv zbC<42J@t=g@*l3yaB7_mlMCi7S)Q8k^0VHb*?PdIzyF-~N3&-0`?LA__lkeN`8xl; z=G~`DLGXXtUO&5h@PF#O!nFTWcOKL@_&@#oCXN47w;9+t_&;^K!OepIQ+FEDJorC# zmtkrDryew{N$`K_kteqa{!cw zM2q16K7Xxs@P94MXW{?UT}QVM{x5F)pPKoF_&;?&^NtT)wb&c)cge#`yqPE1@4cno zgHOu|{!iyK%+?d0`PvFU-&4#FJ~wZr_Zahg*Y7U&9&Fzaj5>6+_pmcNq}tY7<6U@W zcIwD(YZLv=>Fd1teqsL2>%IG*+BWs_a~r%lKK@VFlRjnhCf|oET>Zv3Bm zpm{sy|EUL!&IMwfvu2{!iU!RI}j!;>Q1}nKy|4Q_KIU2M^B+{!iWg z|B-edz*3cI-|m+pA`(PEl9F@SWRS1}L2}q^vLqu2DoIQ;CQJxs%#JdSj(KLx5n-bU zNX|K%71QXbV;bk&*VFuOp4H!}Z|c-}tKKTFTC3Muy}EaAhW>Fs{aOeArykL@ZSa5U zp`BW#z7HGPKHURy(%+Zm<}?rf@4KrW3LY@ORZg;~^P-m()-fwrcY2K_~i~rO9c(17sO!MP0 z9}WMf>(l%{HS2le|Keu--}x^+7`z|zzL@`~9?>Z;_&@dVQ*(p=Q?ouX{!cyF)-z`Q zpBfK@|5Nk)@PF!&<|&!~7dQTI-}VQB|HF6T|J2>uv`X-Q-Ywe)|EI_IXx%aRKXum* zorC{VcW!rTazVAL{qcCRAIn~oYW$z}=Xy(CG26FuJp+D-+U7sv|Fl2zAn||d0WI4F z{}=b{KV9$JyV>>Q|FoUP|EasS%J{#y@qcRk8vZYC{GXcl2mUW^{9oMoKfNE=AOEN3 z`Q!i8@_*`K?bE((c!#tPE42F`fB&4_+4BOkJA1v|Z2yXxJ3oCtPtQ7EQC@of z;qY$h>lu^v_|ds(uQ|L^`hJbK{x7?;{a^Na!P)cpvOC-JWzYA^UavRX_hol! z^EL7P{D1R)+1v4dX7*D4PhHyP=P~~;Zv3CRM5z+N|EYOC_TNXgo9Dy-`F8Va_&>G$ zU)=aVHS5=Y_Tybg+6La?|Fj(si2qZ||Eab9Z`{oPQ_KG?DZDTEKbrY}apV8ue(Id4 z&F8WHueO)8`DWKlI?~LaJM`&ozMc7Vqoy2b&WHbtuLu99=J`Bc{Yc{>H$HT;Z`b_4 zkq_Myd?1bgQ<{-2(2of9es z|EI27p;ChXQ?s5a{!g7#scP_lYCIMGPmL#J{-4fQp+?o<|I}O`{!d+@OsU}i)b?@& z|EI=J;{Vj8&HLg1)bf97{2TsHU9)MO;Q!R8G^ri@pRSkrYRw@B0pPJ+2|J04@o*ew2x@Dbu!T+gS)vX`=pBmrB z{6BSzT6Kc|Q_KIUo7noWwffKW{hQP{DfmBauYXd7WWdK${rTbj{`&casb>9O?O&r( z<>3F+yuQ!=IK}rrx$;TLQNK=3HS7QCewVF%N?89_U7>!RF#k`-t8er0CQX^-=fh{> z|Fj*ShX0HE>zU^q>Bdcx6&IhKYW$z}uhpbs@P9gg{hVgO|EXIwYaaZc_OEmDDZ&38 z>63#0Q?nj6{%=OR`-A^u-Xi`_&HA?ZKQ*sE^Z(SmzZUEs?ag|-_&;r@@qcRk9sW;^ z=fnT0*&qL>#=A2APu;41!{GnaEo~kq{!fh`#Q&+8Cy4)x8~>+nRJ%^<_Y?Ce3M(5|BN4Bra`S#bN}M)_{g|Bc0P&u`o(8n*F1Q*GtSOWZ2rFY zped&%Z{51D_}?$K2!3ziE79{x`){}=a`1sjfBzdin^E7yDD2l0P;zW68npSs_) zjQ>+JZxH{d=K7fbr^ff;|J3+C`}?2bdk!_r{QFT`AKBK2NOi%8Wk>cmKY333cfI?Z z*D)EeWT`*Dj^}j={!h=Z)0Euc|J1Di%ltoef1Brr|5M|)@PF$5HeU_@rygtm3je1b zWAoGSe`@(ZJwN$BHGT{K7dQS-&3whCHvdn@V?G=HPtEn=|I~wQeOCORx|hw*!~eyN z|5G!s4gVK6{!e|n&9B4%#m)RbH9ipkr}tx#-JjySp7QPZ#SdpZ>CN-U|7rixGX^9r zavt~X=U+EIDJt_<@5?S97W|*~pEkXJ@PBIgzqmiX{?Gn+d|BzU7kKwIuhz2L!``fa zJFM12-mHJi`oB6J9uEJf=iAfP)5ZU(<^STw|Ec@f&jbEX&AdMRpBgWU|5M{h@qcR0 zkN;ES_3(dcUVr>w-1t8=?;rf1n)eU>Pn~P?{qTS4e48hU|5FdN`-A^e7hcjm_&@b& z*7(1;@qg;B_Wr{E#f|?{vtBU%FK+ywn%4{er{?v<|EckZ_`kUEe|r7o|I|Iq12g~c zoqjpNW9Qi4hxVE>-Mi?<%=*8Wm21wwwcz>%_XPjyzUD)U4-;|BD;{r)K?6{GXm5jsH_K9}WMfW?mcquV;t)nfZTq zJ@fL~rg~-7*51s2!~f}iGvCkbgEu}9|EKMEwFWa9`T1CH_k%$Vyjd^UuEqQPAAU?G zl&+KNQ$DTf&HB2wzMVf`_P6!#yqSMz^Knvb>*smn>uh~J@BKF4kM)0bKX#h`WBp(C zHd|kp^?%i@x6As!apV8gtnbVEzj{4r{9oMjh96aI-?;}5x5L&)zU_kF7ps{cSgPeO z-urF+Uh@mypW6M#|LJ%i+x^D>srT6Z#{a4DiugbE7Hj-p-1tBBW}7Ey>oa<9|K)f4 z`Pk}>k2K%mz3bbI|I_0)+PpygpL&C>Uyc9M^LxYIZ}>m;!tZ_z{!fj!!vCr9PA64+ z$s4bQ|I_iA_lEyd^Y}4apGdX&nZLgD3w%4hs^Wv*eE*OC)BgN?_sbv7n&iF3JdMpa_1N6Ol>`J@8t(RU_Pk#Yc@ZI*-JVf^Ruum>V@`wHb1-i`CVk+hvWa$_(%Mon){9a zQ*%EjoRxUv?eKrvzSR5~{!jg`9UuRvW_}d@PtE)&{GS@%f&Yse|EJF{=C|Vi;>Q1} z@uOz(7O}=LzK`dF|5M{l@PBGN3jR-x&%pnwS?`hmQ}ceY?OoNppP2ur#yjHwbUk=N z{GS>hga1?We!&0f`7XD{|Eam3_&+uNz&u&5UQgy3*?c(ft@ix!f7+k*iSd6r-xl*( z_&;4QjsMg3mF8Q_cjl>=e_-pI&M57@?%*NbA9*_dvK{XS|EGR?(`Ui|sTVxAJorEL zyc^%+{h6oh?~y;7_pf*NhJWJy?LD;P-+2Ff_a1x?KOf!`r@qY3kN5nm=LG+!^IdZG z`N99GU!T&KpHJWanXz4h|I_unJh^}Hf9gYzT+7eD@Bhkc8ULs4J9cdi{!hJZ_rBo& z)T`|06aS}v-TVgrPyL$BbHe|rms;ch)XVJWnfZTe*3ZTN>GP1r|EZb(XP>Wm`h3L$ zn!om5Wu6ZIr|mTUPtE$i_&+uC?eKr<^|s#bvK1S=*O_<2|7kmZ5dWuUeP8^a`Zat1 z;{VjI*!dnA{ZU?n7wQDxw|xIc=8-=0UTU5N|EKM1tnq*9)w>S{|EJ@sTZ2hWd5J}%`H3l{q6m%&AYszyr`CTWZy5ENP=HH{(wRrRSi2u{|uC~t){GS>Rh5w5i|EI>+;s4YeAOENO!{;IXPmQm`|EW3u zu8!^f@ihKV$K%iE<-a@Cub0OE>3-t#w*0Yc{^)9Tf(PUCy6Sy--gxM7FBYWwFKfGd z^LhXAr#(~Mv_x-jyxg=}eZ6n;BmH~vq}@$i3Yo)7*{&HDrY7dQS-&A;!$|EZaui~mzI|F7ZIH|5WMvUc!k zTkX$l$K5j5d$WDM9lC#>_eT4CTle_Q-kaY4G*9+~&R4 zJm9FEw|j52-w&NXzQddKeNXxBPH*P_{r>xW?=^c5ChwQIJJrjo-Q&I9j{juCd%aiN z`oMGB-sk<^&b`S61@}k2JNfL52mF4lu=#&CuXxb=-5ooVoUMQIUb1Ct^20?B`QzWQ z^?!F>^RV}#bsLg}w=VF0XZ^-x^U;6Kf2Dlw#V3xQSFmL5`s9`Jk9gz%{`=G;`FkI( zwfNm1<`%s6?y{u5c|i5EFa9m~KmGkfw?5sI^(9}(*WcfD?Z|wL7rloKuA9v1^OE=A zqL#t`Y5ze(a)SR;7Zf#13QND5ufGqan>T&UyGK#;q*TAxy?YIBnS40;4evr*4|K`g zH@!#M{JV#qUg$0Vr}K@rf1l3$KXt!J1;PL6{Cy|p2mhy@VBQV?rygq_4*#bfF}6eS zf9hd2zl`~R>cOLPg8z$q=Bdl`R}XC#ykAfAg7`mmw-GIZ|5G;^krVvi?+cp-|JQtU z>)`*?_(A6Xse6rXALjq5SJ;qZUzA?Evr5z zb?$_Y!T-gL|5M}f@PBIj9sW zHT`{BwlB)|KLxE@2LJcu>vyO8-}hVYO8Gx^N1LB^-nR1!)c8RBpBf*C|5LMmUGKNf z_r|y3|8zdqYsLS?jsH{kYiaBMn*Y=BxPJU!+|2(|Q1}$JjhO{GWQ1-EaKgoVK>cgw6kx|5NjN;Q!S4 zxG(>Dr9Yl#{-2J=JVxgKsXNlQ|Gm475rb^_&;@kmr;k6OTaVQ7vd@?82Z!XQ{ojzR=bJrW@PEDD**-7Z z^JUNb`~TY6>-lE)|MGvwo8K!}?*1hwthzP$vC`)EKD*;SZ?-S1c%+Xjc~tVqz4!Wd z&d2;eTk|&fK|Gt;7;nyx|I_y4Z9QE4pSqL{sAK+L-1tAW{Gaz>|EI>o;s4a!Ki29l`6+dvcF7_h;_nJA6C$5C5mf zGk*^M7dQS-&HZ}!(5>D)AN-%LkH-JSjsH{QNq?((r16@K|1!_F)6DxY|5M}pK3saOZ)d(D{?E5t1F|EUX_+WNk? z&-Ux-kW)YSKW%T_q*h|zZ~NmLHK`l?pSCx#`G5F7b-Shw`1^@ew|(&s-YuIqPUgLO zxpz*pM#2B-e(?BC#h3ba))T&C=_RRV{a@|hvO(?O|I`iZ)JX2zaFOrN`mkSZnd#lS zX7#ZCudcVrNhgN&f7LCjR7$=-IL-HORH0n(f7)KNT>0St)U{8j5a$2s{JdY7|EI?L z;s3P%DK%;b{}(s@PhHcz*9#?%G`{clN$2_Tn%lou!T;&_H2zP`{l)*On>T5Y;Q!Rj zYsCMln>Vc&=Krbjh0Ooc_2A{0|EKQUq*3sH+P`JZlY{?L*Eu=k|J1CXjQ`W;N%R_waCke$C87PJd*WH}n2_ zKQ`1G&sY12BJWo9Yb8HEH6+y=o-OodJ>e(+F*w!uKb;>B82@=ByYZ{>_MF;vQ_cFw z@%9=uYNWdKDb-Vbe9iRsI`vLYZRh7RK3;B@s=@zVe?`5F{~O;W_&;^gq#nWl)p@9X z@P9)lb`SnfJ@nk%;Q!P`=X6c*f9k=Lx+e2`>?|%SQ$P5=A?D#;t+T_sXmUaDf7(8D zO1GqY-L1ts|F8@5l8MO{Z`R+%|7m~L^L?&(qi?72e|kJ#5dWthV)M}Oe`@?7{!fjE zV*Z~RUx)uw_r0KV@PBGNBmPf4$ktE5|GoM}-QfRvPwX80pSq8&---Xz{>(eX|HX~} z)AQ?Y^S*3-3g6z#ypye8;m!5h`WD{!Mf{&0&vyKun&*rEQ{%U8%30`-r)~WWZ~PVW z|8#vc^Z(THf9e6|T$L|{!cyDJRts0&HfL*^0YU{!~bbJ>)+!4)XdK-RrrMWpy>mH|I_y2 zmkta5Pd)jP!sL?AANBpunbAM_(|dpMX8qr{pLoQZ>%sr&@%S+OpSu4=1;PIv>5TtV z_nVm)=KrbjcKAQF{GS@n$oxMwz7GHAZSNoapPKg%{!d+K^Y!q5>cRH@#Q&-BdH6py zJ`ew=#uwuM)ObMrpPKoC_&;^wv~I!wso5X@r^YAZ|I~vn>K6Q;n)}QAKQ-?+{9oMo zKXrHWq4+;_5A&(`KQ+h0|HX~}Q?q_E{!fi>#s8@X+xo%yzqo(C^J4F!OM4}!4Z6s? z*ZG~3+e**y#{X?!KGhrl$NImv25j(tH$9qJ|5yF)zOBLksaNjWlZ;t7ve?X6#`}Ge z@qcR8&%^(zx7+tS_&+uC9*%l?P_eDK7W@`oBY)liZ+ss9Py6HV@PBI7L;b!*FW;YT zUB0I`K5yzb-BOMJ)8p}k_&+u4kK+H-%z0-Uj{!j0p?RNk0e`@X*{!cCc7dQS-$74JGPtEn>|J2+M{GWQg z&G*Cqski*==P>_I&HBgqzqs*#>JRLE_&>Gg|EV|G`wjmWH~vr8zxJ^Ii<|j>YWY7k z^ZoFD>ecpr@g2MWk!t*(&bQ3IZ^!?|z4h)#y_rXZ|I>CF|EJz)-)HySe2+KYuXz5Q z-gvQ2MYno$z2<)w>-DGce{oMZYxZLO{NNq%f7;G^efU51ep~+z|EJ#dS;qgVnWts* zO8xw+ZT(O4$5DTZC-%nw+2@1z3- zdE-U!e+7T85j-<~6#u8*@MXsTm1}u&X1<@TFNptB;|uYBapV8geE*OCQ?IxAPyC-6 z?}GnJ_dM^FHopn~r|Vf|^8n3H=IZ${AJ9B?s_}o?zQN`r;s4ZYZ2e{YpPKn*_&>dV zcvJkJdZ)dA@qgN%w&$Cx>)mEP2>%y1{!iD-d@KB)n)QJ3f9mxIJ`4U&$A52U#{a3` zT9@&E>bo9a68xX~iW@TiPuJTn_nP4U)cte*9Q>bpWanpt|5Nub%J@I^`7>V${!hK& zhFgOF)A_Ep`G5BFm#6KoOza)}pZeLcxxxRbU$gDZ|5JbU@KwS8sTaQbJf9DF`aIdU zb2FbG-s|`5?DpZGuZ>-#)8{9CZ}rw!^URC|Plw+ddcs2Q4Yoi2Py5sOKQ&(O^Wqi0Kb~*K&#S$eZ}(HX z4c@D5fBc^w&-w9xYSzoe|EbqoSFLr>AHUZ2$N%Yi@hJE|HGT#Er{1yeK=6O+joWty z|EJ?GvGpTa|5x{G(Yj5+|LK0cvubVdf9l1{R|fy5{`>MZ!T+gWTC*wmKlP(q_5}Z@ z^Sx+4A6MN{CSTXH>iv&`|5LwbpU?O|^^yZ0C-^@#_ZR=CX1*c*Prcf_ko~te^9k{P z+WwxsAMk%_j)(tKue8rIvsK=FeokIjFV*-zJs@v(NF~Ve<%c9-ipU{hRsv zc}Low|7)A4cym3!eszI2zi;q=x*oha{!h*QUs-UG?~nJx|LK15=Lh^>-1p7D+?(}< z@qgOR`os7?HLnlz|J0lh|EK2o_&@b_``>f;KQ-$)>*THGaP5%sKfN z6jTk~Z>Kf>FK+ywdb@qz;{ViJ?DPA#IydJpc)m*TY@5woArP3e>&c}{T~GXr^fr?|I}>9|EcBw)Xek4|EZbxhyPQv-Y@=7y?W=q;Q!QX zc4qva?hot#;{W2t|EZUo_rw3`@ihKV{qDxi!T+h>wt0Z~Ki#jzhy9%{_1ndzdm{{Uw>aWtf+tRf9givn2+(IZ|^)Tnbp*!Z@|Wh>wE{l}c!IT`lZ zB5(eFmid3$pTA#b{-1jEq@Kb5sfV9k5d5E-`Eq-9zmxyj*t)^<;icaAd8v1i`K)`Y zE%P2^UJw7L{rlQ_rnfw?Jio@;I>Gn#9@Zi`@7)#Norh=qpSE|k^@W-Lr)FLt{!fhu zWd5JJw|Oc2pPG4q_&@J)ZG-<)4?5H4f0_SN%m2mQyX~g@0l9S+_b+=_0p71(;bw0< zU~=IW@9{QY@S#52{CM=`6SsRa|8My9J5t@|(VgBLzxQ{GYmLOxrO3FK+yw8V`&AiyQx^=KAn|YWcso@qcmS|J2O?duG$` z{(i#)-uU%@y$6o&n!I#lQlR&1UcVMeoytdf56f$x-2T{+9-g1}E!m!Bpn0$O`!PIJ z-2Gd%3iJQWBn1E0tySAF|4+^OxA;GGZfo<7*Pd7K`LLUVucM#8Y_d1U!~bc2&UeR4 z7kIN?>#k=mOm+Q7r+N>ud4i|)n(D_J+_GuXvgr9(^Fld@eFUgA^uO-N8|t0 zTo3*)Zv0=|_`kUEe{nPaFK+x_-1xt^@qaCEpBMZe_lNm^YW(6+&t2jBvmP$~PmibZ zf8O?b;Q!RDw~PPN@$hT-KQ*2S|EFfXTKu1Sh`m1snEz9AfAD{5u9x|LIv@9w^?&2W z|EXCYnfZTeydD0}yF-iM|J3;%bAtadUQ(vd}aHGWb=GzVJ zn!cXw&Ypjly#AAf9^|EE5>Y>D9i)QP=( ztuDOPAJ2TmKYeves!L5zH~vr0r?kCa@PFzm=Hu{x>e`jc2mhz8T-kh{t^XT0{!fk9 zV*X#;_&+tC5C5lbbW*k8|GaJe;1}E7cx1b^{qJXQ)&nlx=}6b9UL(x^)8mh-Q91ZO zbyD`&;Q!RTzhCcmoga_;jsMej)?3E^sVkH|KKMU%6Z34W|EuoTre&D_r|!_UW$=G$ z{22aE%{(^d|EXIyZy5Zax>buN!T+gS=QK_5f9lT7ngsu+W*+kUZ(f$#j{nnk_Q(Il z{ppH}y*o8+9Q>c&Pk2K7pZ0HN>&fE()NSi${GYl-%}T-lsq?Cw5d2@<%>Ps4;h6uY zZrZeI@P9gg3!ATp|BJij*bBUKa&p4@zuMl?{=CNeziRFu>;J}$|5G=!`Ed9@b@S%U zga1=ApAY}1=6djdapV8uX8xa==ZF8(^Q%{{UhseFCN__e^?!Z;+SP;qQ=d|+YMB40 zu3Eif@PGQeC|Rw1@PF#EwNDEEPtAPDj`K(R@#*sSjPkD8xIyyCeIrx7Nd5~-jDko?_Z}*om5xK@_tq8rsx0RVdKYlvH!ggcc0U$1^@Td#nprVJIChlGyhMG zS7ZKPzZ+@<|A%K|{-2uveb4+qHUHl4!gF^OU-nz|;Qa=OK+y70W*;Q!PkC)s>+ zoByXieM;xx|8#!V@5TSAN18vo`M@UciRR1jf7*Wb)Pmsu)ObJqpIY<()V*yzU;Ll? zv-XaSv_JC# z@qcRO3C^vw^hjUOCHOyWA2c=N|J1DSi~m!zzOViJS8x1Z{`5uO_^q=Czva#S!T;&; zcuD-9n&adD)ctKeX8fNTzs3ANb^n>&g8x&WKJ&ET|Ki5~squXHKQ-PD|EKPE*#GJM zfyZP1pL(dR7tH)WHS_%Nf9kVsejxr&eda}{1^=fWGOJJUf9k@EdI$ff#{1#_)SMsx zryexDPw;>0!87^>|EC^i$HV`rhtBL3{GS?ci2qaL)$o7n-m~(9|BIXXf9io3^$hd> z)Prn2;>&(}(6@8F_&;s$YxkS^e`@(ZHNF%7r^a{U|Ki5~saana|EKOhwM(*k>Ye`j zb(oQxd^7M4?^A6aAO27KYyO{__YeM0J!*Q7;Q!RD2h99GHScfypPKcf@qcRGU(ElD z8~>-~{e}OF8~>+fe&6Fuul4JvS3Wx1d$@VN-A7&H&HE4kr^jpkUp3wj|EKPM>1oMt zzg*&vr+dFS%Nsv<`(-n|dz$~-(P6rG?iuZa|I_i#zHvTG{_`h2pyD!ZDQ?EXl z@qga-{X728%vbP#yUl;F{;yi||J1CPwQNOU@%zmy1na+_k^uN~$CTm0P8d%JDN|7kn(?eKrui^i6|2QB1PrcuK9sW-p z*3&irr}N?O{y4L|_W@fUxKmMC?~i`^Ir*XW@!t4F{GXmb{*U#4Prf zelY$|z4@CT!~8$>HuIr2-^s6s^?q&sllP{te_%e8_r|ZjxApawE;i#3ya`@#cfaCP z#@r2C(Q!~E@|EJz#KmYhY^=JS5F8Dw7$L0Z<|EFd> zVf>%Y&w9i7KQ-$eVMYd15wi$@|&OJM8{7^ZxsqE&M!sKfivvd9vz${@2!R zW?rWEORLu7*B0yZ1rssJtGQWra)Ar(j{ww%DT`wLG{}(s@PrcgS zFZe(8Dtmw9|J2MMWc^HT<@m^>1@bG_n{K}mNg8x%5 zUcWi`KlL*Ui-Z4Duf6|%TW|DRzuu*{-4^_xuK&VY<^=zz`$e<ag<>iPRW z4gODkpRKQr|5Gos`GWXA^*j4N3I0#L+8Y0-UT^a`@qcPwFZ`c+xp`mwpPG5C_&@b( z`#kykp$6XkKK!OsV{iPnt>x*B|GTV5b8r0LTW92Wzi*#6_&?nr=DFejbUwV;9P@v1 z?UV;>Q1}c|N6=4o@}yPuq8zcgO#!@p?NdjrGRs;s3Oq#{a4D zfcU?-@qcmS|J2O?!~dyyeei#3ydVBgjkoJodRnTlZ!p7~{cpH?X8x$1<%5^oZug__ zKW2F|U$Xprmw5Af;s4^}tX+=-ejMb_&@bp+aLd@ zUT6E`|8%@H=8KvC7dQS-ji1Kw{?4%|EI?5;s5mbl^eGtWxsgHpC9Y}e)HqQ-hBS!|MdJ9uGtXg|EY^@ULgMO z*+b=m|9kVW|5Gnp_LuSk-25K?PmgDPT>M|$_&;^O5p9G2Qx6!`KKMWN;E`>TpFeyfzvRSf!QbJ3wjI6D zyU6^~OLgD!WkAe$Tr6b4OGSp0AH>zxAi}-o0&J+?10xdJnMqhxkA3 zUud2W|EI1GQ;q-A^^G{EOYnbjz5CDJLr%B#M<@J}>WWwV z>dm~rf8PIFs@J{ppQtnbPw%(>quK=jr{?nl|EKOdyiM?b>fwEC{a*8b>Y~${B-@@i zxwZB zf9fGETO|)posw$&pB~Tl>8D@d+l$Nto?dvNcVU|r!T;%agYEl0{GVF>Pu-_Qiv<6t z#-HK;)LrfSfBc^s&xZd~+feOmlq-1t8ouV?3u!T+gG>vC%Fe`@Bd;s4ake;Z)_ zPmM>z|Eck9_TS!kxs%VmF4br4Khm5J|EKGt@qcQr@60kcdb6GNf3^J#ThE#Gf7N4c zek1-*&Gq2_)Xd+*|EY)D^TGf5`^|hK{!h*Q#s6u4o-h7So!dF>>+-s!*Q3q$fZ6Nw zvR-xk^OW5^vgQG1cbD9>pUcfpd%fPd>F$%4o;R31KQDXUU+)g-d4&I~@umN_=aW4@ zFnc}S>>k-Uef`ldFdyGON8Zy(V%{d#44%Ix`!tOp(+KYM#qdq2e6o7wv-?rg7@ zJ)bXo-e30q<&I7JKRi=>{A};Xyt8=w3Fgh>#z)1CpThtBr|%zw|0`?r?3n+jW;^r$ z)W;v5|EI>sT~X~`-(JS97yoB7&@%G?ZT(f||EZ5XF5~~yC2YN1{Ga+LyFC1#8sCTi ziyQx^X1!bH|HXZw`9C%D^YDLa?l=BVeS#eT|Mz?2tAhWd@qg-y#~d5{U)=aVb)}M} zg8%!&Q&$K7SNYiE5}SRsM9uoN2a9j_=6>E*aHNkt_SmHJ+qe04{3HHP$7lW_{x5F) zpPKoJ_&+_L3T4U$|EI21p-k|9>e?rk4gOEfd_Vl3n)O-ne{tjg)ObDopSpV0Q-c3f zpIp6G@PF#M)oKO*r>;}AX7GRNlTSW5_&;^UiWP(ZQF|GQJRtM`;>Q1}IY0g{Zv3D6G&>*uPu<C zr}t;4md%6zQ=e+<=i>k3K6b+SsmA|lJNF0w7dQS--JyAA{-2uTGyhNBp=tA^{7L8d z^KWPC;ZCf6ws%gGreXe{_NVcGYUbzR|MdKrpU3<^HU16%r~R3?`1^I^y;;w9`;Ftg z@qo<#)8|8#YMJ?e>KdnG;gE!~dySPZ$3eH~vqJmt+2)x_0f_ z!T+gGs#z!La88jwpQ^R%CAXe8#JhocM*N@luX{?B;Q!S8{Nn%Ar<`(1g8x%=7rcJCplbSuY z`T3X!$oxN@pZR}J^x9nf<5wpHPsjYfRSh?Jk2C*+|I_|s&7(2@PtE)={GWQ@1$klq zpSt&y%=*9TUN)bQ`G4vT=XDDHPkri?F2Vn)3nz65{x9x--?zda-}}7wNsUXFd&~c6 zf6kBpQ}?mIpThsCndis+zqpzIryel1SMYyvkmJ9`+VP@#{cQ{D=^Q8|5JA}pNIeR$J_Ck|EK2q z@PBH~$NWDvJ`w+??mNAA@PF!lGx`Mor|v(qZ&I=M96vwXJ2t%08-F?Wm>ayA=XcGA z*LlnT>H3)$i2qaL`|y8p*MIv;Z{9!WU;W2aznpuycORSoi2u{$`yTdxYP=x+Pu*>D zhv5IzEyp$r{!h<$?A&2CzifQ5t-%&N-@Ly(klb_Tm}2`*Hh8`F_HVa&Go!s%oBu0c zf28*go3AzCnBm@A?fcA|J}&Z>|I_i9_kjOX^L-ZnPtANV{GWQG&FjPespbFTKI?`a z#Xk-y6?_!y{nk3KTdMJY+8^Kd>5IAE%mb`xi2qZwUM>Dl{h`g1!~f~^_~5&Y|5M}dY<)RD zKW%HfdE?bOm8k8#)BGL&PtRZePkq3=9sW6ZuNRMq|I_vE z`*+6wspbFF%qz72_WgI6$7BAVwzIx3{!hK(Yx9%OALYINs~_+Oi+#I!Cj6hSZ|k=| z2mhyDXV-7O!MCrs`;Y(A<9B|WS^rnP%kKZgUq15vx!<eBnTLu0iyQx^{aH^J{}(s@PmT9u{$JeqKV9$A z!~ReG_F@00Wa`a0wP{CwsE@qg;gHV+Q}r{3`Cq2T}2 ztS5*6Q@_1&d+>ki=T~nE{!jh473<6=Rrmd$e&_Ar|8%{7dGihYt3RKcU-*Z4sl@xn zzdarNpZ34_$!CK9Q(yVqi{`i1E>d6j`r_dK)DLgkfp7Bdk8Rn>d^_*g?DKlgopZh4 zvhU;Zf0#r(^V|0MY<|wW*gn5)eceT7^nwRmZ2Q}Pd#{!M`)BFQ`oQJ|g8w_*ct7U< z+5cze2OggPr^X-P|8#sjjQPB-x}Nv!{b=(JQ*GOFwSA?%fAD{5d>{T#z24qG_`kUE zf9h?v9sj4^YCaVIr^Zt-|1WO49`8*y?`_=31G#?v=KJt}+8`G4yEZ5|8$Pdy?xF} z_&*&#x%i^s|I`(3yCwKPUC+b?&jtUdzUtK#!T+hRdv|^Cf9eNzeH8qk`gQwx!vCok znisU$YThdjWc;7DvtBU%PtAJ4_&@bZn-_@xQ!_6T|EFGSz6}4Tmj6@Z}{!h(3?)zHgdgJYP_sjR@&-eD{ z>r~_a>TNnUctJk@@qcRmJo0&QZ{L51{r<=QX*-SoQ{xTse`=mD{!fj!#{a4L_dWPO z^?qyopL(C|kN;E4|HX~}Q*Zt(GygAc{GWQKc|iQ1dY8Sv_`f6lO_=`|H~vq}>w*7M z^LpX`;>Q2QUHpgX`8{VI8@wOyAN-%1e; z^ZM3nd9^q1mw(lt?Y+mgZ*P6A_fGqKd^7JlZ@k|_{jX2;Rike3X8mmZpRR9}`REzn z-k3k*+mgZWv3~E+|IG2`cpXa5J<|61T^Z(Q<%=ydVBg&rkkO{r1|-{J*$a|JVDl|C>L*Wbl8i56t?% z>g8`QOnMbR>OJ|K@xlM;?^_29?-u-@x^s_~!T;&+A9@UH9Q>cQ_Z!nP_&+s12mcp0 z{x9xsPrjC4f7%Jb_YEA~A*s3ib#MF={!iPPzlZ-*cX=+2mhz$-=AM_#$w-I zWPjg^|I_wS_V>B?zqtSV*4y60CwC71PuoY>{`f!j*vVaj|5J}SuXFH!L%uE_{NE_^ za`-vvcr&YP{a813Ucj z%o8m7ZKpRLFsJ%%?=kjzmg%@B)t?UC>&^VYWz+Y054HJzkKMZ8ySr__`k4dXJ?wn= zKiw~_|EnH8p>u-&Q_KJ9_0{}8_26;sg8$S0Lu}q4{?FSyAoKs!%-h5Nsd+!(|Ki5~ zdE5Lw{9oMoKQ-&?;{W2t|EXCYdeCLx`tzspe|kOewD`Zc@qg-}wjKYc9%f!}^jSaV zFDPGr@o&$}FBolo$yNXM9%=sX?gxMJX5JtEPmibZe@8mw|Ki5~sfU^$Wd5JJ$kxYZ z{+}8@i~m#ixA~gP|5FbgloR})dO+_+!T;(0^y!+O?{`|KwC^jh^=4DwpV>UOxbbw^ zz2}xm1!mxa_hUQ$FK+yw8Xt%Mi~ELi&iBUC;s3N9e~155vpz2K|J2Nz!~dzde&+wh zjsH{Q|9UN(Uhvz^7YA>L|J(G&3~#P~>_29Db3LCtdXYEt_-5WW%bR&~c5FZXp!T*t zvH3rp4_}G@Q+IFQBKW_!TP*#9Z^!>tedCX*#{X%5&WHbt8~>;7d1}W0sZX=@X7PV| zzIZO?|EYVKmty{(dRWJf!T+i8Rro(Oz7GGV#>?UV)T|$j|5F#)@$i3YeAZK=ulF8q z^9sM*e55&En?X1DcFu?Y)AJe8u6^)->ftue5C5lT{bu~1dPuuY!T+gwe)zxR`d=3O zD)SBTe`@YO{!jaJJ@`L$w&(l*+S%**a=+rAC(ai)&p+-i9n#*cM_ztv`=I>ve7x-W zd;iCJzggdp^Zt&{m)*?!jJNm9@^#tk5%8&tk3ag@qZ0g|x>Sjyl2NVZ`~Gyhm+th&|CR4>q~-tgc>E&%@9Gg# zga0dic>Q1X3FZZv|EI2K*T?$5M=hQfykDK;GyYG_db0RGHS5vh|J2+M{GXcji7$WZ z_9a*Jn6Y^5xh1+KcKsiByUn-L_&=RLvGsoOe`|EU{QsT%yBx}JHz zYaXBL``4(Hng6Hl%=^RtsVkmRBh3Gc8~>-SbaJiW|J3*)n~mn%@jT4`)AqVGP7eN0 zUBWyO^Z(RIxl+kD*WKXHud2O%tpBU+Rm?}?|J1y`_&>e>ct7F))F+k7tpBV1PcC;t znE$74QMp?1f9hU2ZG!((*K3jSf9k4rYX|?QX8s!fPhHPEoY^q%#^&Mhf7;%}{=9+z zQ@6K&&w&3^x3homfd7jd|EKQQrfr!2r{?n*|EIPrjYn}0bIzNA2V*X#;_&+s1@TgxW`{VI^tpBUy zvA!<;Py5sOKQ;3Xng16z{!fkf!~f}cZ5uTS{!e{sgT}%CX@463r;f z^MwD48~>-q`A3PuaPhH7!o$dd!*Z)mwR7@T3=sML>-MVSo1NO{qo!r^#VDYm3rGn2Z9NaYc zzpp2i3jU9O&xik0=bA_RebrvypRWJ(9`B(xudmOX-Kl>5@tywoqVu~XTd&`d>YvZv z?#Su}**r7+pBgX4{696`5C5mePvQUK#{a3un4iS| z#f|?{kC>jB|EC^4EjM}V!q@%v=KAn|+FoSy@>u`Z`|$d|YCPtmXI}LC&Gp;AFZRYK z;{UY2{9oMoKlKn>PZs~D9%}0e;J}$|5M|ynEw|y{!h*N zy=Of9S3f^}{S}XScQp#@qg;G?D^yWbpOt<{qcWld>sBy`wz1Dg!n%-^9AvL+Mjue_`kSW|5y97 zy;6(YQ`jUHe)IDupAO24*{}(s@Pn~~h@8JK`1()>+ z^Z(THf9kx6ZG-<)x0+z<9oYK6y1$d}Ki}4m8&_;I)D~^3cT2&2e|t3eKlQ5pTZ8{o zzqe;^@PF#fpL`nppSOKqg#S~s-q}y>3X9jh{+~rRynS;4>vz6VWso=X^k)3r-+Qyo zXUf^zH`Vt2p*Q~TiAPUMHU3Y>$4BA+;_&+rs5&x%t|EK?i z`G4NF9sj51dTbVrxBQ>3pZS5z|5I~(=KsZQ7QmZ%i1)yPtANp{GXch*|jXz z_23!te`>rV^Z(S$_rw3Gci8>8=#sCznIHJYsh_7B|EK*w_~(zo|EUj{7q#^lefvIp zeQkY4Z|)ENPy6pU?Elo;5Bop$TAOEx|BIXTf8)0GB~y+6)An_CJ@~)4@qg--_Va=N zQ?Ii3*KrG;@y7pMcg7Rm@7T}duXP{w-eR5#|EI@qHZOqxQ?Iq}qbEE2G zoB3_{KfQiSzO{Lq=Ks{2?D+UUH69TEhly)@+^q$C-;e)OGw+l6f9eC~`)vM>KYq`l zFN6Qn@$g{G|5Lwf^GMAf`}Mu`(WlH4^?q^pzTp3~|Kg2Xga1?i^|gh;|EXVj@R8vE z)X&}hVDNwHv3Jfl&s4$BKlG-#_*d_)*Ik9DS)~1|j2|8RpPpZG_PF5xyoU}9{?B{F z$l(9fM@={*_&@c$iL-+LQ!jbwnc)A_S1nx5{amEJf9nC}!+HOG&nNi0MXXVb4}9(8 zu>P($-o-rPTY5ZgzR(-rVphzX^(y&49S^@?maS{t_V}(k-U@p^*zr?s$II1r-f!lq zQ*GCuYI}a(ykG73-ptQr{a+n#r~N##{;!(#6K%etH|ruHtLta|L;Rl_ z?`Qv=r{4I{m%;z3*M9H?J~U6~Te0_J=0|$JvHlS2OMB10?c0{ z!T+gyenyq%g=Y7`ry4Yga1>%`H#nf|5JayZ!@1CdHQ@=wQoP4FWzepX6FBC z|91}iKlSp%{!hKadWrewz7z`t!yT^DNB& zQx}_O!T+h>G{1uXQ!ljh;s4Z2%$MN*)QioREPrxyUhS2?Et;8ka{=?K2JPGK{ql-6 z!T)Lhzd!M};Q!Qrob`v`|I}r#nr`#RKJ~|!zhzaT`_-TSy$c@U_pkTex8BBl-h91Yx867>891wi_l(OgPAc40(tFya7X|;P{qrxn zB|>rWf$&GYFqVYD~bi~rO4xnIox ziyQx^*8IP?@qckM|4*&?e`;PI{9oMoKQ;e*3IC_wXzw5VpY8|mAN-#h?~ead<0J8Z zYUV5A|J1wf_z(W_2XEHf#s6vh&QCJ_Prci&7yqZ;Z;!|SsrQ)w$N#DM_g?tFxbc5# z=H1@*@eTg^;b-xGdVP1=&kz1jz1uz?@qg;AAAcVFpL&aZ{^I}Cn?KC>KlO%#ne~6w zTMp0vQ*Sn3jsH_KPZ0kXH~vq(!{)K#|J2*}eVA07eV6xoTkrRWTkiH=XY&B@e|r9` z_sjafapV8g>uuiO;DHZ#ui3IaX?^;G-fK5)ODazKllS^9JA(hy^(;3pi2qYBS-&yN z|5GnpyCKZ~Q!ih)G0gu{FSYH=|NG~RUlzUl!`yF@ z%kO^KvBBframJ9O>Q~QupWmf9e}9*+zkh8rq(Sh1>aOPh{@(9p-@pIJcFEkyucZ3i zn_l%EWb57H|8%}Wn+JyfQ{(^I6}*vu!GB8zPgiL3(khI9)0=r~U;c5S_b~Hjs~&jE zyYTEz!T;%aLnn4kuHU-Yx1V)hmt?|s#olL5>YU*JwEyr)nfZTlYg^Q zkNJOU`9HP%pL)2>^TYqejsNpDuZRCrY+Bz5C5kgc6P_$|J0lh{}(s@Pxp)U zomu}^&3eN4KQ%s(^?&vH4jq?S|5wfWxXl04{=;m(AO26x`n~u+b)l^njsH`hZub-a zryga#75}GZeO>%t-1tBBps{U(|5Fbf(U`Puq(Q`#&}NcGEB3yuUh^`89vvtH&%p z)M$PIKkuU&{pLMtbo=Du?*H)~ZtG!p@9|%M{2-h6hyT;{_ZyNE{GWQ@z|8zV^?(7* zlK-?m+V}6(EA3T!^hnRM%AOyVJ&@c-biKK4TLu589?&-9 z|Ki5~spbFFT(8+S-_CqR{GZNO*s*o+e`?lyW&WRfuzjD8|5J1S@PBdR|Ki5~shKZ0 zyw#O{{#JIs57fWPyQ6t1{GYCu`+@&c<0tWdYMvkS|I|D`{GXcb_`kUEe{tjg)XcZT z|Eb5d%lJR_sFvm#&Ht&H|A_xn^M1kq>G^VhnE$8d{e}Ni<3I6#YMvkS|I|Fb&R0j8 z=Tmv|T;Gl_#s6u48vhq}{Czg>x45&{gYDEI?diDx@&5m-Ie)xA^CIJBy~?n$#?6~{2Odl`1`{$&eFWxeKJl-_!-d)lj@${_qgGXoWpY8Ad|Mp<}d5f=S zeAeqVF6;FeX1+AuKfAMiW4HEcZ&>2^^gO=o&h~oQojt!VyR-Mt?riT@u3Wj)^Qma_ z;_!d_|2ro5KN|n1X8l5Tu2`}5cDNNxYR#GOknYBw(U#N#yo@4E5912V4>|7SD3 zLUaG{e>ZQQ5d2@IvgN}3KQ-&i;{Vjg+5N-+sgE(gi2qaL*YJO3^UnV}mw{!d-ELdO58<^R;Izl;A%_>7yqaI<^S~h z;ydww>dMC)ALjpQ|Hd|duG1_r{?!D{!iW3<}2g>)NNYi1plW#wOOk$|4-euWxL@2)O;R)-1Snw zKLs|AuwczBKVFAM=D%$IpY~_HU;LlCX_d0U|EY7E)(-wp-6f}C@PF#gEgA&>r^fr? z|J3|GGV68ZdRn&0%>O(5e(lz(ZD#)8;qIK%D)>J=zN6h={GXcjj>G)F!~5g?jyrCW zZ|~WpNiw1AMDK34e(h@&&h>8GxN-1*Iv&mZKXr>{^^?Ul&q{UWdS@PKTQ8XTf4;vp z{!iV+&ToIe=FNJ+VgBFY>#g6gR%ZU+;btBn^Z)eoU8{P=|EW)|lJS4~ys30j`ON&k z!;fb^V3_}RxaI$}f5Td}lQ92J=d+*3F#qpxob*uWdGV}iq zKR%~!X8m7nXFcM(E*|91pT{4%e4sZ!Up=lGkm~sNDf1KmZ=JpVZ?+#i#^w{ok1uKS z7vpZ!BE7x$z|O({ZF%HBi=KSwo&x^&>nr6B6syme+%4Jl#Xj%TY`xhYrS=xrfBUyZ z_f)&5py!2MlS!ZK_8w*P^ln+cE7kZv?a#b8{9oMoKQ(>~{}(s@Z~DPs7hQYr-32_J z`G0DBAM^jzZ2zj{M(=^PJ}v%F+iCoty05L*i~my(Jhx5of9e6}v=07H*K_K*9fSW< zcd>up$@;%){9yS~@A>ig_oZz=UGClQ!Y;x8Y5zep@`L|VcP`<6I*}6ACI^D zw9nh#c)T)AmU!doY<&yw!fD--VV^BJ(ssY_e|~(s-w!>#FtvTj+&5GG;p8{GIX?6M z^mvZX{69555C0c8{!h)kzq2O4oND}^?l+Ie|EZbpX6ui5GhdMTe>xtG|5F#*`m^{y zHU96+>;C4AU%T@dr@JnG+?Tz=t|7m~uzqs*#YR&&sYyO{l$l>*W)%oXS{GYn5{d;BnpYHEPfBr-8e`cV9 z|9kl57lZ#(FWa*#_&>G$pL*+Op9lY^W}ZZDQBm=8>%I)$k9i{aKQ&$m|EI?D;s4ZI ztnq(pJRts0jqk(%#f|?{zCpG)Elkwf9fsf@9=*% zLoWC~=E33r)ObJqpPKFXKQ-I&e`@oo4&HNK7c zf9ekp`#<#uhy9U{V@vjdCOct8A~8V`v7Q*(U$pPJ*_e;?^@e+vH3 zw_D@?)VzMo|5NWaKZpNQ^Lpa{)a;M{Q{z3E|EFeu=KrZT*zxdxapV7v^bfY4b+I?| z0`Y&^&U(D~zqs*#>eaTsEB;Tt#?~9g|EXEu75}GZeOLUSdhHiq2mcp0{!h*PKm4DX z`GEL8HS4pE{rZ+vn&aX)=$2|J9^{e_&+mpi|~ZZH?re()#I6Og#S~sUNinr z&3exGKQ-%9g=ELIu)T{@I|BD;{r^f%;`pl`eZQdJg zyIHwB?Z4jUi`n&iFFSZB_&;r5vM1yJ)UR#G_&@dR2Vdd&`s2@^knw-o-m%$r!T+gy zw8+f=Q}@jIEBD7AKfK%R!T)Ld<>zMnpZek1^Z5D7)9X2J>ZSJnoaVi7=E&gxv|avB zz3{^R=E1Jd)6ds|`P1$5|0eG@pZg1+58j{dT_60P_FrQ^pZGuZhJzpAkG+?g=P;k_ zz0Br6+2@z{8f*NYu4jY!68xXH&2O{MN8f*)`4r~=>3mDg_u>EI#{cQh1Ix^t;Q!S4 zL)QQG{cS!V{!iPNTI2uJ@0efgI%9pFnY`frmh3qY{Ga;09s7d+Q$O zy*Kzj9WS}`{NVq*$DA7cpB`U#&N;#VsgpU^C)YRlrynnwe|u7H?DyWY9)CUQb=A*) zy?=Oiabi}?`{sYVoHYA6$=CTV`_o^NX;n&iPcUi_>{BXN^-ka?64gaUduQJbt|5LMGI{r`1 zJV5-Pn$JW0pPG4W_&@bFdp!P6z0Uj=^Z(THe`@Bd;{W2t|EW1Y>;LNc@p*{A=|EJz!pSSqGxLN;Kt@(fIo%Z|rqi6c%x9|N$#{1dh@qcRO0pkCzpL8hrKYst? z|J2)T|AKx+-g|An9{$fC|M@q;|EXE;7ylP`xy#3R;~zK8AD8O;|2Dy!d4%JZpP6d> zpFbb_{eu5fbHAAXr^ff;|Ke`n+t&X*{QP-6e>r1ns_}o?&hhYnYSuf(|EYJ|yhi+= zdZ+#GG5nvm`8@oedWZQv{GWQ8yGfN0`_G?$WB%ge&x1F^_r3D)9B+Kzj;C%)HS_=U_)Q;t68vA>%>Pr%|EV|H z?+51p#f|@q8~>-q1LFVGTkY}qKlSFl?+5><#{1#_)XW3idH+4$Yj*5S-ummk-fUm+ z{C(c*cI-}OzjeR&D)WEmy!U{&{GaZp{GZOZdh3qh|J2LYZwmfTjrV(V{sO%vvhgzf9l)sxGS02_PP8rb$?kj{*Jo}uK&aIWblyZy?f`j zP5xEp#r(y|uZyNvyt|-NVWVVYvzNSkoZdS4KW&%)i+jPxulVu$k7}L#p~P$6tOq)> z?(5$2f4Uy|KXuhA|EP4%WJ?|K)VTM+!8jwk;YH~vpO)chOs|I~#OItBly#&_ZW;%5Gzn)~;| zqigbQ&DBNy%idMc*XE(&|I~TIY`szQe{tjg)SCaNW}YDP|GY=ENbY%OQ@)w5Ma+Ba zJHCDL;=avC+U`I8Py6??`Fr?3^#JpCtp6J~^Z(SWmyG|58~>*sdD#D{M;!KlYWY94 z{GVF>PhE6QZZdAgK|emeuhWO`r~0JiL+^2CbV&aG`A2@g>3O9-@z(mkdOfuMubO#( z_`kUEf9g@=ItTx!9zDKG@PFzd<_GbA>cZ1IB=|oyKOgtxedE_l&m8kl?|$Pl{!h=J z#{a2D+Rq#QFK+ywUT@|D;{Vk6J^Y`V?acp++y2{|{eR#3Q~n2U{(BL=kFNR8pS}5c z$Ny+qRB7B%xt%3zVj|l#c#{b2APV@7;hnn}p|Fz8-6+9rm2LGpK zeNOzJn)zq=KQ-&2;{VjlyTkvfSSvme*B-B{qcWl=E33r)XW>i|EZbZ z$Nayz@qg-~b}fVdQx9pIlU(-R4ZfY%V{!Kzy$6}6!2jv~upS})PtANs{GS>hi2qY_ zfAN26Jm~n^bN%?-pT9ns?)c{+zkT}WC%d`d@&3$zjJrpNwCBs--mP8p)c#yg{CKW6 zZaie%**~xSTBrSApO#Hh`{POD$7lP$E-lmN&u^Rda{W7}yU(csWImc@1t$LAO6o~S_S`CqRep#>;I~`-<3YT-J9#j|5f~KaPWagmo1UJ z{nQ;x7IYqxneS)IIX~R^NVC2%{!iOW9Fv*Lv)a9#H3G@Hd z%mc&!sgE)*i2qY3=1cdzdV@FfCGmgSPUHX7_)`3zo-eOI{!iQSn#}*x>sh*F#{a2L zvh}iA|5y7ruURYjKXt|W4TJwvS8C8Gsn_;uKVIX8&5~WGUgh1SQS;#cw12B+&4d4o z8~+zK{x5F)U)=aVb<3vBg8z$~`G0E8$NInO&dutE`G4vbH7f`Ir|weoq~QP5xwWeX z|EKQMxPI_|>U^8$w_xvdKR)XhGyhN9S-+V1f9f3b zYP=)s|EgOzZ;`P6ubRidP~tp4KJxz{G{l3TlsR!8o!~dxpH?0@^pE{>iX8xa= z^_B5|YUUZ@|I~O+{9oMoKXpyJ9{iuWx~;ctHqe{-fU8a&>&-mC=jM*}=U26UjbzR( zW4uo|xnh|Ar{`a<@(IEJsadZY|EFf2AM^jz__)FQM*8PZ-P#R;|I_w5wdx1|r>@$h zS@3`A8qITp|5Nk+_~?Q{zy6LkKhoAO@vdLLe(-;K{&+q6Z{OaeZpQy%e}BMy&G`3U_4;*EUAfjNsjgl>y`FIOrZx|?+6TqEioRU*X03Y*3JSXf z|5xX_FM|IoJR>*wKlSNTdI$ff?q>cB|2O%iL&5)bH-CozQ;)XwWAT4+Yc2s{j@jh^M3dHliv6|{Gaxx@qg;G&1d2N)Mwf}IQ*Yl{x5F)U)=b=xbc5#JRkl~ z&GGPmapV8=^U8MopIY<()I5LupBi6?|5M}r@PBI7zs3Kld)xiJ_W8T~{Jeh5|I_u* z_&;^u8Rl8d|LO7lX6A+Yf7;Ib3IC_&{f7Tj^ZvsBsd@cb|5wN3^W>3ap7$VIUl{+V z{qcGDzqs*#YSwec|HX~}Q*(dT6khA^Pa6NH_a}}2i+lRPE4&9@+$XI6tK-r5KQ;6H zSpQee@p`{G%bWR?tpBU+-Og+k=KrZ%kIf1GPxs@hr~erIpBbj${~mecrQrY6@9xd4 z|EpfPH?#h)di$X-Y<;?6#dmzTCwM>kKlN^#w}t;xud($y@qg;I|NIy0e-+zz*x~!` zt>*n~K1izV`$KQ$G1>QvskZMQy;-lQy$+?WAgLi*-MkM}q&u=r9kE#{a41|J3q-YUah^|J2O)!~f~{cscxE-1xt^ z@qcR8-^Kr_Kl%61Vg8@`v!8zr^Z(R)%*)~b)O*d-;s4a1{+L<+SN-w#8ULr=W4;al z7dQS-z12M3{ToVqZ~N}&;QzFp#{a2z{rDf|2YIu;G5$~6Y5boW4~YL$;}P+HapV8g ztlw-l!+X80|I7S8ZQpQs{a>~GpPKc6?Z170w&VY_9q)(#Q?tG^{!jhBoe%$~-eB)n z{GWQgy`S-a{|{+*9cERz#(jL*C@BgUC?zG`HGv@Aor;*0iU?TPVj>vWsMw8&f=CQq z!wg+RmmNn%J;zhN_xIWS?pbTU*Y%!1-apQD_+D%6wbqW=GtU0Z{is))-^2gK8~>+X zaeV%tdWn7hjsH`xx6ilnf9iajhlBr9ueA9x_&@bxo2P>RQ*W^Oc+CG(Z~gX%F#k`T zXP-~w|I~Ou{GU44whuA?r^aL9|MYt2{R01|#t-BF)Xe{}^+gkn|1)zHJRtMf@PFE$ z#{a38rPeF=^S@@FZ!-T+*R%AUcZ2^^PrqZ5`O22Q{ggXK^Y!i>jlVkhKkXll9Toha z_xKxv|I_&|oAf~Nf9e~jK8uI*>+AXE+rj^7`!!!I4E|63>Y^3F|Eb?uxgHO)A@4Dr{Mq8EA91<|5Gos=O6zUZ~UKH z{x9D6KehayTK-SX`oQ=<^+ualiT_hGUkU%GW}YqnPrcLDE3|(n+U%S+-Vy(&{aMcy z|EHd}Kjr__vv(b}>p9oAf3orWF#k{6?|EfG@PF!CuS)qpbym$u!T+f{UHEdC|EC^O z|6`tCKmM3b&oUn~Q_t7rD?jGz$NPc19u59a+sBQ$HTXZZ=KrbZjO@FZ<96Jvt^Q_ue}<^R-2cjcMynwF{Wx6AkJG0!#KJMYUc&2K&Ly~ft(o-tvD_bQv$ zg#Xj=HXitr_cw3Wo3!^o@Ac;U@PFEWogEMVr)GX2{x9D6KV4t0`91t!yqW)}#wX(c z)XQwX-={5dGxhV&7v@Lsf9ltluL=H7{qV=Lga1?4?bko}KlK@x_lbseKH#@+^w1<* zpY(|Lz_(rt{!jbgnY%jpKlLl?HwOQwe%t0t;s4Zcbp z&X%3Q|EcHM{8ap(dhW)p!T+h3t;-AkPrY!(>ga>hie~Bjug?EG`dj7V-jkl09yQJ? z>3ze5>!Vu-o$1{qqj9u&{8`>5vKmDvJWKUp9pcUX z#sBGgSWg)L7w<|3uJmTT39Y9{Nw-B%;&@Z zshNj}|5I~4_&+uG2mhz$`wjk2&3r%nU%c^uYP>4`FW&e+HS6)>|I|C|c=$iH{GXcj zc=3PgO}1V-{!h;rjsJVBSV8cActHH08ZU_dQ{(;cf4V)skNJOU*7v<+-J`xgebu(d zyqWj+(19u5o9+Gg{qG+4WJEb%hWUT$PD2`p`G4xH zE1HM-fAPlusk;tq6#SpM_cbko|5G!s5C0c${GXcnfA~LjpKCHB{GYn#wXGxkpSs&s zsri3u<_|LePu+cZvoQb9+vXMG|J2=vrTm{7KZgHPceC|d@qcO_FZ|ylH-8=cUniTV zi2qaLqws(6#{a41|KdIItxZ`=c77GSUk95Pi2qY_KK!4$)n!eh4S#O+&am~Ezb~`h z8xMGT!yVrE%xc|tdb2)q+flo```P1h#e)TfJ*;tb*Xz5z`(EBCdMRg*cTanMng6Hj z#{;tdubTOO%>PplxH>ENKXq?g?+E{=W_@G)pL&=*ANW5#-j`qAEciclZ<{~K{J(hH zzrE%Ev|a1}sjSUe_Om};_`oAS|KdH| zJYiJ)nD?*&=A*hD%PLajtKjvR5BTti-xB@y{l9y6H-EbFl|K?~R?nOHp7=i-Bp{x1^V;pHVgOd0M};`C@%--b?)RxQ6wTpWiWm4FC7z?DoO`;dStTYCInP zPd&iA9{%sq4IP62>u;V9|EIh|EW8hM`He;8gGaHi#Pr+-uOSAA0LGOQ*(R#U%YEvcB|k1lKPFJ&wAbF zeQBenQFi;=y;=Vi|EKe@{wV%W-LGk@;Q!RUZT(yPpE|oyli>g2jsH{QoA7_}#{a4D zQ20MJUK0PO=KAq}YSxRz|Ecj+_&+tb$N#B&*t|dH|HT{sr|!$=_vZi9y={F${GT4r zrnVj<{!h(%&-g#J=KsYT|EI>+;s11ed>#Hz%{;;Q*F#2~772Guc!Hn`0>)``=xt1{A_&xu9>!eeYEs${jX=Uq;F&1rMB_^c*}TqGw%`a^soP> zjgpTCukZN&nRS!L?`EDPzCFFu_fPkA>Gwa~1EzbubkEnXUh?|-rg_G6kC?uH`t_v0 z9!@NAO5*;d_bDZcB(|Sy>z~FSk28w>|8=@2OmF-e^Z#<@wMzIubs6(}_&@d8=J)V_ zYWY7k^ZD?9@n-&?8t;eyQ{(sWfAPlusaanb|EE6P{8#7vCze!xuI1v_&igBy`EW;j z7B*h)o^8{7`)LO3&L5cUd3&b%_7hGyAzIaPnjilZ^M?4pD|0e}2aL==wl9+GagR>* z?c87d-(UMOeO}<**B16kcKyu%d+9$}!2@zW=KraqlTM6UEPdSj#M4fV>W!J=$HRN# z|8)G4XBLY#z4WM`zvP)`1plY&EmgW`@PB%|%9c#|zj)*Sv_IQFs8-nWf7)K9beZ7) z)ObSH|5cYPSu*%Pb%_!sg8x&WTD(~Be`;QT_&+u4S>ylWjsNqu=L7$z`!D~e?W~{t zdF%UpfBMMsd%e#-HRb=bf2|8D1plW#ziO4>|I`(2-W>i z|8#qN9{$hUz8~TL)OBlB5A*-j?2rFb%l~=X{`fz2?V44C|5G#HkM)1m6-u2N{GYm6 z@gl+hsr%Kc7W|*Od%bGG|EasyxhVKQHU19&7jOKZn)Q0|f9l5O-)!wzZ@&NH|MdJd zs#z_1|BsQry;7~3Vg8?PU&X$EGXGDF2gLuy8~>-~?<4Sk>Q=U1GyYFqwRWxG|I{_> z*9-Ii)b;J}H}HS)#{a4Lc>({Y=JCM)saX#h|EK2p!T+i8hxk7=9uWVh$D?}X^1=V9 znTL1z)Iq+T^?;i`IncY(StWx1)BYvOo*Vq1n)SGu|EIp-{EETPc8qamj6@Nx+wYI7Y(XbPkg`QeDUvpRVpR> zoU+OFgHJ7YR$~9t&N(~L@_)51+MV!!W3Da;{*V7Y{%6PiIcD~P?;B*l&tUyuHS_E6 zf9fvg0r7w8zSn03|EKP6p6A!2J9F%R?)l2B+L7oMZ*4DZ^Je%z?cdG(7yeJ(X=L-@ z|I{6>Ya0BYy1o5A2mhyTcXjjN|J1GQ_b>QAbxZsG3-kZfUF`Q0_&;@5`};!tpE|?V zZ@~Ylvuync{GXcZ!~dzfnODUBspbFFcqLmuBBycHo#F3i@osx|FZ1qteEwg2f9C(G zJKFK_e`?kj#{a3inm=UzpSu0%7Qz3iJJ|Ed{6BTu>sto@r*3b43;(CakKzB+%;&3B zbDlR|tHsqHh#luWg_E{cGO%J?8&ue|#SP zFW&e+HT&cL;*I}{H~vqJSG@0;7rlF!XT<;M>zny?%>Row{!fiJ!~ew_|EFgC+{-pS z?Z@w6UKjtT^YeUcDgLD2U;2+9r+M>w{#(~+iTzpsSGUIp=^u?y3_df!T+f>|4-fOxc^gEA5=N` zKRsWQX5A81yl=EWe=`@(4gSweQt*Jw%>SMC-hdpNQ4@S$-o69TipTnS@A@|7|FnIZ zeZG0mV?A^1GwtB{@H^(;y|?`Bm+0?(yLxZ^`Pbn8w7>jcyzzf(JQe;g-uOQ?^91pK z@y7q@`t~08e`@9d;{Vk0e`@@neSYf4%Qx?5pRamvFwchn)8obZvAzGSm*{D`>m)jF zVXZ{l{4j4kSi8Hbd*j9Me>(ndYy4ll@qcQ39sW%ib;Sjjy}&v7+7^ZM&`S=e@~}XY+r&xqkBj z-grQpALPBwo`0J!(_IbDY8*k>Zna@cy{!iD3-@^Z?m)rH){4eia=7DWK zm^btK9v^*|H|qi8|IC;LU%SDs*XECT%l~ORpFiXO)N2d&g!z9u|BD}d6#SpM%Zt;3 z|5IOh{guK0siVs~2LGo%WBld8|EZ%16N3NqzVl9etzUn?mp)=%ruUH7J`Mg)*LVB7 z9|!-Zp8V;8;Q!ROF3k=8PyNKM!}zmB{EvBvxjPGj|5NAKJQw_*`n^xz3;s`i$K*SL z|5JCqZbc+j=;lup)QLp~YD_x}XUwHf7!T+hFxod*|Q=hW!tKk3C3-;kXi!4+x zIsCi*_eaES!t=TC>o6a%l{&{>@8$=+mwfjl`z9Lyr|VsAzQcT?_bT(P_&;sOqcZ;I~2)lK<7b+hs_g8x%@YdFWQ zziX!M&vo6O5B^Vm_qDTw|5LwmeEy&MvE%dq)C+DN80P<}KOWI7_&@b$BiaQ2r>~C# zPhTJWpL*d(uZ8)4>aPp(ga6a}`_h7f;Q!R?4j&HwPrcUs2L4aI&gT7HG<&8u9t8iV z;5+kGVX zKYc&>c-x-f|J0LSdpGz$bu{Cd;Qzdb_6z>cyHA(k|J0q{c{TVy_4Lmcm`D0LQ{Ru~ zY}sZ0=zH(a%;)9Y_BZcO@;93=I_CY7`4Q&->H29~t29%`e{bWqsPElTmij~Uf6u>o zqW7Cy3heipCwsrOb$3*G^QqoBw*A^4iX^~OuV|Ecf4 zb!_l|>M9+I2LGonX5$#ze^AbkA6HhAt$8T}>5x$+i|JqUBJf5BI8sojwd}xVhZ}8sr<&V+!kH#kY#Z}`HeZ{`< ziLUzlMDKle|L}jh9vc6r=KkaV;+@g=ZofSq@q~HzB>L#Gd%X+H@2$zd&wH2oz4r_5 z_ul;VchU6^KH!h{#xK7K{!h=}CYzs$|5M{>@qga-e*3RE4=4J9oJYJ_{}=z~``i0F z{!g8E_{-q`)awr&4gOEP)4U)4Prbvwe=z?~uZPX{evbcB%m1nKZ9DV-;?4X&^@cqu z{}*rkpL%ma%KxcZ|CjlHYP=u*PmKqxdEiCwwVSpE|EKM1?EU%K2WR;G$u)0{|I__j zy?$eu|L46f<^R;V_Wobx)0w{isx@oE{6B4fKW*=9>&u=qIoEHG zhs6Ks{^KR_f9lreqws&~OZunQ|MfN>II_$p-_HC${GS=V;Q#0yCvVQG*MD2^U~TRB zJ62(fH|xos*=nnIJG)-n*E{=)CQ;X$wtKg=^>Ri{+2P&ayxl|Z?DS?H-&@OfdE@!; zf4UwT|EFes;rYAwdNc12|EK#W{}*rO|HT{sr)K?M{GYn7t*?Rq)8pUgvgX16shRip zVgIjuf7-6xA>Hi$A`DZT;SE4S)3>Wb^j$e|o-qo5#cd#T);p z?%6-(|I|JD)r;_dYJ6bV-~OI8_SvnAcE0gMHok9Ei9fxWSNU*_e|qCr@qfBK$7BAV zx|_|j#Q&*T?;8K7X8s@kPu;m!%KycC^3^94ZtvMVI_uZMZkmytw~_8;(wq4y@z3j; zHLf50U*?Ersri4l{w@Ab&HA_aKXu=R&4d3td}H&J|7+Yb_&;^umRZ67sk=9B9{itL z>;I~m4~YL$RvX#4*#d~XWINR{GXcnW%xgJ*LsbE|5JCd_4n|9YCIeMPmNE+ z|EckM58pk(oBd0VpXiM*du7Be-uN>7pKhOBC*}XtZ5uQT{!g9NAm#t!jsH`(soymC zzj)*S)ERY}2mhyTRl8Y)|5In%`hDkIb$9mb9h)xh*6h!0JYVTr_ju#4@PFE$`Ed9@ zH69fIr{?v6|5G#X4*#cSz8(Hg&3roipBkTr|5M}r@PF|>aZzEnY*;hu(DXsyp3%5g z^!V(;X5J+8|MdF6i{by&%G(AMPn|xWFS}v#>j6Iy|N2Ou*O%_=x}+4|i zl;YQSNwo@z?o>DF0n+Caru)Qnf0y3r9y0xU(mVa}OrH-p$oy{N`qP?ulJV{T%kQOo z!1VrKw=Z4%^u+l}6-|1UR{j@xciHr~4P#_FltcZJu!E;;DXpc(O^Yla2q|eNvs^1KE!M zyQ^s3;Qu1?hxkAB$+mv)cV9p5ebNahL<2?^c4WQcyD7f?L|eZW|EJsY_~QT6#fqi; zpU#iBWBp$>9*_BddVI^2C>iGesqucVeff}YXPzJaPq$}1U*`X*>y|w)_&;^k;%5f` zr!H|;(cu5oXOuiG_&;@Y+R4HHd7G!i|EcBw;*I}Pv)(oSPxqgBfXx5Xc8-t#Q!}3t z|EI2hddmN)+njIfudcbrx1U%$HUCfBPpXre|EI^RR<-KE|EcTLs2S$}X@B`YwfvtN z|AzllkTviPu=3Y(qa8yJwA0xr2L<@_c^O{ z@PFzFO&SOPr{?b?+U*+a$LnP8&&>bRc03*aFW&e+HS6=@|J1C{i~mz||9k&B%DX}J zi-P~t_OjJe{!e{@`D^^2n)Q+Ke`@9h;{VjFr;PtoRR^mRf#fJC7ShrwY^@` zCc*!y8?|f^=KrZXHftIDpE|R4z2N`U%sa&YshN+6|5M`|@qg+Is#gvEPtTY9pIZJ; zU8mgH!T+f%+B{O`|EZ%A#e)A+7b$yo@PFzv&$acRXY}>`@qw)WtL>G}xiI)YU0>Dm zm4p9N+y4Rtc`R&&P@7KC-qiFlc137u6}5)Z)ZK&hev$o&HT6zJALZS@ojw& zZ>|^rr{m%2@PF~f|EckCH9F7oX8*1if8@>fv1fefjjx;j-TQ@YzHff+dx<`?%)5R) zTwjwv-uCADE*kx|@6Yik&41Ikcd_-GXTI=;ciXY8BK)7OxBbmo!T+gy-DK-&ub=7L zndkPO4_@`={#2UsN}}71c{$PeKYjhNKmO0#JR1Hl-tUZm!MlS!KkNHEpXi?(KIe^p zJG=C=-t6Dvm+9U-zxY2Lzmxep{GXcne)vD#U*`Ma|I~Qi^EOOPbk?lLy;<-2%BfQl zjsMf_Gi*ElPn~V^2l0Pu))U76>3Z;f_`i6!+Bn(wXFL8+UvHP%JV*SWx}D8)-1M(| zy_paA+unN;U2oFe-t8xJh$d#;ndrsQ9p1ffX&-$)^EN+!FY|wYU2%&y>jQVJG{Kwm zJ#lE9H}e8_y*Adnxy>)Fc;yY=7Z0ryRs3y?-{1S^J{XOdGs^qfwJV}7s|V%SXWGI0 zeXwtrecs$ZXX>yog6CVk_ds;|^1j~N%wzmns&~$!J@bQa+HC8CHu`%H@2%!3Zrs<+ z8&6^LJrZs6KfGDL*FGOiw0(Z)z1w^h{!iD#ygB@zTK+HI_W7l6XZ>LNeAAor+2^0J zKE`|$Z{`g)e7CWmf4i-hI%aA^@15rTZ2dKVy!M%2v-R1$@qjkJrLgV#ZN7^)KFrpC z^FC^A>%(~;vHflRIBz`Ki2Tal_%r;U8L;3rx7zvee`@?3^Z(SG5C0eMvs<0x$J=FI zZqo&26OI4V>j6)P|5M}r@PF~f|EcBw)cJP(_&@aq^LF?@HR~zk|I}OTdhvg1?l1mN z&EtXpQ*(XzKQ*2a|EK2uH!1RqH}m^!?K|&%c0JXe{wC2jKWVXEPn;kB7jOKZdZ(?& zd;g_77VGPQ_3-e2YJ3p>PtE6>_F1bp>jC2bbiDQU`7{1c*T3FwZ@$DEPhi`;bM1Ke zKkd)w-S|KCYTJHn;fH?wmF5-je>z|O(eHx)Q*SgMfd5m^`{w)L|8%@X_VtYaQ|H*% z6aG)V*gl`f|LOI%z&@YH|EU++cKn}uy{+$x|5NAM`w9L}y~@1RJwH!K^tcJvd+-1L zM_aG?YVR*ruVuce_ginj5&WNyH)`~V;Q!RoEyIKV^S*a<@PF!#FFzanpZeyt%Yy$? zzhLvPSpQf3rp->1{&HoHf>3!S758%VRYuq_8 z_&=RL>fMFw_wCVb_v7IfYI}o4t2w^+>v;w2@4evYFZSOf5vDHO|1Zp+*!EWHCFWc4 zf9jR?da>gt+V;=TcD`Qlf4YA({!hKmJPZC$z21(G|5M{>ng6HGwRxJhKCB;qmA$_0 zT;9vgyV&)3Z!o`z|I_u*_&@cUz5o?%&Yd49b|^_>y?pSIsS`qSY5 z)Gyten*XPMld z@AqsB{!jZa+r2yZKlPe}2ZR4puVZ~)^M7hQ6aG)V{m3`={q#-mE#^BKRejHUwRsiu z(cZit+xw^YI`bv?KOK*@e|v8@aKyaS;!M3?uHSpmem+^|J!{WV-rv37*i;bwpZ32m zcWv;0>N5uo2>wqUU6~d9pSt{`*9QNmzJJC`Hm_`droO*?zG-7r>A+#{`8IzF|EKK> zY zso&XqIQT#HJbVAb|Ea$)&x!w2e{R0=shnb2x}G_9e+KL-;k{zR#;E+SrM%yo{YmhD zy8UBQ9|-s=W9pZcN4Cq=)HJKv8t;?srEf+-hxPuqPsy65c*-t!6$ zMwc$F}{KlOV1{)_)p^ZtSVQ!}p*|EFd<{!hKd-rw+l>aFId z@qcQ(AoKs!crW~)n)!J6KQ;5@+Lz4q`%_@YFIqF(oAq$5a$2s`1#v*N2d>d-nX;f zZ|!Sd@Wuo782h3(9&p?pFL|%c-yHm(?hhUi|EFG=m-2t=wHr2t^?&1y|5LA6oAQ6^ z=U<)?{GS=N;QwyDb42ie>UxbU1plXQ+V$Mv|J0Wbt{(iKx?|t^(Lbtvn)Thz6{+=U zt+%)R%$xahpIk9F(bMjn=gs`N(Jy}P&Ah-)pU?MhcUi;W|NQvo&G3KfHa2hWVDUxX zZSD8Fi!NU5&Ah%BI^=lwxF$QAc=Zx*=EL>5cd2(zTd%gkE6cq5+xeLPr~Au%I{UXb z{tf@9>$${!AC3Q0;{ox1x;>5mQ}g@jRwLH={+(^TUHqSJ&-%ysKXrRspBMk9=JCS+ zsqt0J|5Im~=Nt6M#;kIER|N0Z>bUf7Bl@Jm1C^UwX^`X@B`YHC_|{rhAV>!T+h{ z|Kg4RQ{(;ce^33kEaCsu?QLEk{!iV}eCk_m{^gDTTQT(C-tvDseh>42_&;^ezIB8D zQ+MlKFU&ay6TDlsNzU8o-z+)LE4?pimR#?%ZHweQK|BrqZ)$}a zJ`WK8r^XZhSYd>B_qz3h|7&?>&ENs?WX%6la_9qqSg`&(a)@n)VH{?GTf z^-b}AI)AH+>jeL&&Zt#4_`i5F|4*G&r+)B%YP=r)PmS-w|Ecju_`i7L|J2RQo4s{( zLiV@iss~@!#2$~?J12VM@0kCm{W(AL|J1C%%KX20NSeKefADN9{u|xle{y` zH?sb(_NVcGYCIGEPuEA||J3bk)ry{bv#>9%Su^-Q-Tva*)r0?2H)vEh_&+sX3;(BP zej5Hy-KKey;Q!PevswlJr|#dXRq%i6-sTzbe`;QT_&+u4!{Yzc1MK))FMi0oulc@n z-YRT-={KDo^7~8Qu%fWj{aCs;WB>T))9Lg0hM8B5Zy%aAFR#D7zT(@{yLaQ{_P$LU zB=%1~U%CfO_kQW!C8K5Hc>k+=UXq>IKi$)%&+B8pWBmT5uh-k5WzrL-d&~6W{jW~H z9=ve;{2iJn-@mSIk(tXgCw?BW{x8wEjf3I9$ zKKMdjmTg z;*I~)^>TasU%c^uy*gbG{2$w2DOT9{L;T-=n_n0_;EBimU%c^uYWyMoPkrKPrv(3} zX8qje|LOe2ix&_6PmKq}|LJQ$oD_DT={6= z_YZnkIOp7`)y&EM_?%U&c(k)hVdD`8)qBvdhu0_T|LS@o^OUUrt3Kt7BEkQuOPzj3 znE$6PZR-R7?Y;;6@hDoVNbrApJWe?ywf?X6=Y04-HS3|`|J3y_I5({St8P@WeDHs2 z))yUJ`)c;kdi2qaL@9=->Mi*5M{!d-;{4!zwpSo7Hiedhrx}AB!XE%=X+xKbSJorCt z$G_wM)Lrd*@PF!74eAE}r^d76|I~c{$N#B0AO26x{m1{Q@qo<#Q&+Rcb>V`It8vmzm-mq!#f9i~;Erb74_ptYS z=KrbN)k^t4HQo{b7jOKZx=xMM{6BT=>Z$pEdOhR)SpQdz2W0-A8sEwMKXt8QCkOwh z=Idi;uYP{MVrQNn)$QNcyGW_CqRE5%co#jZY_#w4-rjt@H@T{pH|qmWxvpnnSF9NP zpRT{6HU3XsuF{3U|HT{sr>__G$N$9}|EI2AG3o!(z28L@&P{y(y71hj@5B3Dmv=ZP z^O4Vj=PPwyxoFA``! zjelEr@9rEkUBTaV8j%tGcx8b%ey^{s?`vy5gx?p@_P24~?MG%sFLl`N-PSzcq_4O6 z?Yr9F1I}E#HPI{H+v45LeqVt9)A>6OYZCmQw|SVl-8TC6ZdWyp`qbUvon`a;@PFDr z+x~tN|EK2o_&;?|`+LtrbJls|`|y9-j_7UkjJ|_FiLcz1LrJ{PF93Q(OLi)f=CN|I_X9Z}>ko+wp&Dw&VZQ zgKZv~{e7(;Z;<&Y`}3aL#+%EV(HC__`r{?j*|Ealu zBfHK>^y9T(N;LjYU;pfn|5JB0--!Q3Z>hRc@H(_n&!}9ePYn^r-red-t<>k5kW_lIS_VKI+Z-zxY2tzRe57|EW8V%ZiSb zc-Wism;2j;g>BCl{!jbkY4Lx0{&>Fde`uf9mS?`)~Z8o}UL6Ota6Ahvb+6 z3cl~{b*rMM{xQ(|i@m$dGxg7zUi{tQ`%GxF|H1!h`!@4C_&@ay^FjDO zHR~zj|J0joJz)Hwn)yojzj)*S)LVZ3o%tf(Tg}JW=a1feKF9n&-5=UMzf5eu_xF~G zUbLsV_hy?9_xEK@6OI4V`L`bTf9h?v9>gW5?uE#!~^*(IpzwnaUetXtC8(95f zZ#d+)W|4;px$ zH{K2Zr~UDA_&;@+pEv$2KR)yJY<;~%+xmOnT)(Z)=e^738QSOf-uOQIeBXPUo!{pF zc(dJnfH&K1evmikxA{VeHh-{K&-cb3j^Pu$nI~xL7kYC&_h0n0H}e$#_2c*6ctGP()_|&!b z`91zG-sXRNf94075AtSy5dKg5Z?yG>@qcQ3G5$}@yd3LxSp3I0z#;r&m7|5LwV>%H0hPCwsg1-pa))Ald+9|-5d5Ed`mWu<|6%;_e@phK{GWQ+!Ib|~=kGrl z{9nBBe>&dg4Y|SpsTX|_e3);4{ONmw|I_wveOlx7e0!ADHTXYmZ*tcZ{N6(K#GFm+ z@BQl6f7*YqL>Rkpf0uq8)(38-USso>@PF!j^LO|^b!z?SA{pvj^BOjv&>Qb(zRi2J z%}+Al=#9s-<9qXZUsw7C@73ROy!XBFgl5|kjsMg6HUBT(_&@a)`}*o$;Vqlqm_MdP3A=>tICGWeQ{gnIbJ>;6X(Ra@@^se6EUc25_-WhdY z3;s{X>ykM;_&@bEy*-9rALSiBVt(s6Z`PBv z_a|@WOWFIEH|v+<|8zXsj^*3&f99jTSDDYU_fPND=1J`R)q9QkKYRc6-eBtu&=JY|I}|390~qUJ$2=V;Q!Q<<}M2UPhG5C*WmxuQAYLP|J0YiF*W!<_3Lxy1plY+ zCo8vY3;s{NcGs@p|Kg4RQ!m}QBlth{M=MtZ|EHe5VomUWI^Qf??->85Ub*i`@PFzr zw(JW2Pd#H>YW|=4ZS%>@|5GpDb2#|Fc;~-)MwZUcJVpGUdcA%B!~dywnTN*zsq@z7 zM~8}@<-P3vH-rDv@kjRV8vLI+s$D6nKj>WFzkJVj!T;%a(exR?|EZhV{7(Fz`V;ez z_&@amyFS+c)$#Mq18z80)weV6YRoodTPhFn{poXBT;`2m#Q*8~X#AhI{rraii#Pr+-pv1tH~vq} z&oB7DM1Oz1pMR%4e@~n+)|>Tr@qfDhJ?8W9e`@CY;s4b8?fJt0srTA{zx_P+c5l|N zZ}QM2Z@l58m+$h%=N%e!k2mW9pM1@|-n;F1)yLlF&HO+7pU$_*-cRv=@y7qDS%1Au z#)DZG-u3pP2~R(qP2bl3A@3bWz6}0P`)@ydH26RDR`Y$#|5M|;@qg-kYy4ll@qcR8 z2WI}Cn)QM4f9kE)XBB(WoArS4f7+gB?}zxmc;o-n;roI4KXsn@XZ)XfgZ+H?Rrlw- zb9d|s{!iOC?%W;xpE_^b&fx#zjsH`x+q^CKKehZ{y!Xy{#rMy(^@9I;=T+}j_Wp_g z)Ba1>tPb=4)bGstDEL49KKHfh4+Q_G?%1kUbj7BRv(7tXPVjt<+Lnm2ew^*yabT6m zwt2Vf-5~fs?N8(X)S2dY@PFzo^E>!IH9ipkr)K^f{!e}B&<4T(sXHF`e`@?3{!h*N zF8DunA8Y)ddZ4WbjQ>*)xw2*Of9gTD-Z1`8jbFq6>G8pH;s4ZlJ^Y{c=lu9THQw*u zx@!`Bd6%``-G-(7pZ2Hmf9gJVe*B-Bd2;waHS^%`fAPlusoM=SPh|e@(x*NN{;&O@ zI${2wI=k=1!T;IMOu_$U_O229pSo$Uno*xgTe3dwJv;cW%z^bIoAu`1)aKJooxRPw z#pR8o4|BJBcNv=Ue>xuP@8bW|tcQ&Mi#PsH&Ex;yv-W!TvClKg*V`BCmJ$9>_Xi({ z|5Gz>5dWuU-e2eI4tq0i5dWvgtJf8cga1?W_`kmJOW&WiwPn3|J?uU9wKv!MXUT89 z@uFpGf9KuDexKL4~9-Hx#caI^>g8$R~>1WS>>3{#t zACJEFeBl4|`1P^%f$@LpUIQ8g|EKP4>j~rk)IA5(3;xgBz8+csH{SR^HU5wFf8)*k zKfPWw|4)ri#s8`MnlHuwse7AGW&WRzhY!U6#hdwm>Yg_5;*~3-Y~7y5|Ec@*O8Gx^ zrw+;aWqn#CeNOM@NpHlwySOh&Z+sN~Z{Ln{Qu6@KW8weQ@_*`XHt*%Ovq$=N{NG8Z zkMhR%P5Vz_x35z@!vE>^ZEao}{!e{rt*TMIJ=c4)9sj58jcoo5^Z(RMFRmT@pPJ9J z@qh7V{-3&|&F8`YsqtU4sC-v|GvW}XfHPmT9mlzWRe z^JnmXIv(qz;{W1}|5LZJ^-b}AIv$^=E18hm!-8c^Oo_i_dYF?KCqYhlK6J! zea5?M+Wf$7jg#~8y4$?a`2M|`ByZot{Ahf8`nXIv;KAbc&r~D?;#nNB)U)I zr2k9zgz5di=JTb``#Yid$%*r&dp~?${QCY^v)*oe|MZss8~jVrg#T0H{qTSB#{b0| z{}*rkpPG4qm$WKu`9E!E{a*avo97k{{*Pw*@v;s4@||I3|PJmvpvJN_@;xl;J|Z|9AJb zC4!&CH!}ZEea0DQg!zBk|9o5D7XPPiT&+^@e`-8>$#(bp_BPe4M}yD0$FH|)^@_p& z>Hc11^GI3$SIv5)tpBTSR;y0%f9eM2!SH|ThPCU5^?!AKydVBgt@(dy=I7!6)ObJq zpPHXP@PF!t<;n&Br>;@{%;5jjO)stx{GXch;s4ZpKlpL$P2PO}#s6tLz7PMWmj6?; zKmJdRx5ode`TmdpQ)k$EzW6^iKd<2b)Xew8|Eckh_&+u8=lDN0x5xjftJSF;{9nBB ze`t~z)E9{j2Q<_E?bFPP}c$@PBEzo2YlJL@BVbkgA*TXQscz8dG1i8dcO=zVGZ z64CD~4tS3l*fhF)|GpeEO2P9nAMd^;dlUWk%st-tzYy!m}d`-YnnZR-3LPN;Q!QIKmIS?_&;^8YnufBr|xHd(f`{Dnzf1fd# z!T+fT*nB?xpPG4o_&+s%%+`keF^VA<1UTxf7*Yj-5&p^$L})pX!t)hKF`*- zNc6hr7kc-c&^G$v_66R(CSJ<=8Q#}U=oI{)j(3&$IQ*X)Z+F{C^Spfclur_Utmr3x|L}SEKiyv%|EIppyxipfp`#sBH}tgnmzQ?p*K{oA{* z&6mUf>Fbl{tKNmL`gZ(Z@4sG7^u&WRyz!AQE_*4_Ij_Iy&HTboioNK^$186C;dyV? zKmKRlbBVt2qi4N2ew)Xi@x~8cd;N58wm;hKX>aBq;{SAiSnv0*DNht$kIe_f|LO5y z{vZBN-NW|B|EY(X@5BG8hun}E;s4ak2i&ps5pQn)&(9wAW_@A&pRR|-|EckS_&+sX zaoEQXcwcgJW_16w`@P$Y&kFue=f?-)|J3-vyPv*_-3o^$X}@PF!+Uws|?pPKa$ZGEmBThl0f{>MB% zTffU2|7Y_(5^bOVdE@Ww^T9;p|8)Gd=IQW%>UFk1{!h*M?DNS)d{x_U|2S;LZF&`~209_wBJiqQishdVgi>nd1L+KGrY8 z|Ec$z7qriRz4Oeg+2_OF`8K}~|7XS_wVty1I{aU}@qgYnkMFGiT;R?8y^V*?_r~)* zy82viydVD03|H`ite<n6{GX1$(aw+mQ*Sa4hyPPE4-o$sZ~UKH{x9D6KQ+h4 z|EW1X{x9D6zj)*S)c8vLpL(x7zW6^i9uohjX1!nhpBlf2|I_n>7sUUmd41sj)O=pw z|J{Pcdc7|;PnUb^_C#lQ+U&hz|Cjdlke_J$pN^MnpReNo)Xd|<|LOXe4`jZ?d%5`% z{GYbZ+IuAUKlNwk3+#8>zCF+8!!Z9(+w<-7db0uE>&!#p|Fk{V=H=l3)GN*B;s4aD z%;(|%^!mxQ?fAcVpR#(I_g4G-+2(tBZ?Vs(@qgMM?}-14cmC&hdh`CWxXlFb^)^pt zR{j|8&v$OO^_s8t&KNp4ns#J}cQmSPbk7Zayh}YeEE@Y~XYadSd@lIEpWc2xc*Rfh zbA$g=zqn&>@PF#p%)8+K)Cd(ysa$DVg{-LAzH*eNQ zX8xbHFUsGD5A%L&!F;@#_vm}>!t;4&jJ^t=w@|mQJ){rE_r81bRQC7YT5#C@`y>k2 zRAKUC+4GL3=KtyT3%^bIKlKXp82G<<+wn5g@_*`lo8O23^S0aL|I~S@;}^F1KYK1R z^nB#o{429--s|k^#b()gud(a3wPC$CnztQz_ufR?`r_U@kNyz+pU%Ji@OL~Ond%Mu zZ2eiA|EK3`ovrVT|I_w)dEW;Ar@r&)*}?y*uef?%@PFzWweJf4PhGRx%fbJtvs$Ir z|5abn=cVBP)Z?!CDEL41op(JP{GWRCn2EvvsTYmziqFl|Ps0`uVcp|I`i5+qN3J z!M8_4QuF_`efXHc`0`ABfB0bDoA`6@xu4Ao>;G#1^|^V$|7rhudHKQrsXtk>Hq8H1 zf0&aK{Ga;GdGmt*Q$LooBKSWYf0lV0{Ga+$^LecQtDdbJyoZyPiAS z`{qX;jb8q^toMDLTLk~7hwb>CZ_e^QWZO$U*4mqS zdH6p){(H^i;s4b5Jp5n0@qcRhKlKj#d4TzUW~37SPc8qa=KT0SHQo^ar`~SY&-%Y= zex7IjUvGPS@PF~f|EckQm-iT!X#Ah97jKCFi#PsH&HBmsKQ-(9F3uV0$J_Ds_t8n) zM<=?I`9Gb1tNr|j|5M}5@qcPOAO25`|C{;rgsg9NJ`+6MUiZr^W-~|Kg4RQ*S!%|J3q-YSx>_ z|EY8L9Eh0z7jOHwciwUTr|oODr{@2u^X&bN`G4wl_Ws8FKlPezJHq@w^{Oo?|EFGI zzHes5m;LcuzHxJOQmt3KmmQz~r~Mb(_mAA{nZA9=+O<*L&aZjTTe2khKmGpejZZ%e z{!g9JwO#Ok`u%OAOU?}bPu;dxrQrY6-Fnsz{x9D6KXn_MCx`!wH~vq}dYRhW}IdyD}sAKlSC-eQf@pda(Vy z1O88q2P?jCxpz+;s4Z~%#&qYzri1`E`#d^|EI^ZlX*ba|5aaV^VwMc_l?%CF8Z$8li8Q_ zO8Gza#l5Nr|F>=SE5ZNO?N=-KKXsN~6a|;rEQKQ}7%U(0r(Qbb-Os${ zi2IND<3Ue;^{Dqyn@52E)8j?s|J0lx|EI+J9}xc+@81vp2LbCteN<{ty_bNiSA>*EB<-i zfJVvN%m3A#dV0eDsrxr>66XJ@d)xdw{GXc7fAN3u#{a2V9~A!=Z~ULSo2|!&|5JCW zneu;X=Ck1c)OBlC3I0!w7r_6;8~>;7S))quf9n2qYX<+P?rfg#@&DeOecQYu!Ta&~ zIQ~z4f%yRZpSq&W+rj^-nYV}kQ}g-vn#H$zceeEix6HoHyJNNL(SbK^_ij?FM(}^S zJ)iI6|I{2G|EKHa@y7qD`F#JBI|>``*yZ=a#{aSYulA?$e`=18|5J1P8fV_;=f`8= z|8zYx{x9D6zj)*S)OaiWpBjJJ<-5YhUv9o?vTx^l`tK`j?%&@25BhelAOEN8#XqqA zubO$6%>UE*m>2h3#>0t@e?6povi2=A5??ROGmP)wJ|pSN(&zPcZk625{KNR|nSU7X z^xJpOPR_F%l9`;>H=sq@@zT}@PWOKUGLrX)`HJ!Lr+c{cd5JyhCB1Qar>~FPE6xA0 z9&`MB>770=FtdJ*#Qy2)GpFA^{d&{qJEnWW^!b1P%m1a%2Tbqud4TEj0{?%z#ObGm z`G5DX`^Tc!&igByX8xa=WL-yfA{;Mzt{M8_UWgb9E~hj*v!|vdB!x~j@P@ZQekuahu@y+ z+fTRsr`IZMw!bp_aopZc^iDgUQF-J1D->NCow{Ga#P zXGSG2d&IA|#5rYx|I_s{zi;)G5Bv7=Wy*&2f3>}MxwFIkKlN#6mWaOXHrXGaVkJ(G z+HQHko7W@$PmdR`*KzMW;LZMP{&>L8$9%xoZ!7GwWo`bL`9EEMoigVJ|EIq2)H5R1 z|5dYo^%WVhw)L)A|5w{9*?PbDKXnuHN6i0Iv%Wa~FW&e+-QV&xDg^(hKCjvZ!T+i8 zS@=ISevA2k>e@Ch82_iPXY+cQ|EKfu{d%|gKQ$hX`G4w0_VWn-PhIz-3c>%W+uQl^ zf9fWsiv|CuZhBVn;Q!Q}&6~}gIL@yJ|2JmRP2PMzyXd~L-h4mY^U#gnTrd7l$K(Bx z^?%j)zrUUzwsq zplbD~`ag&G@fuc3t^cdrYyO`a4~YL$*Qj)U@PF#+70*k}|EvC=MayzeXx*y(c~SLF z1APCc<;n#Ar~S_>Q!@BJ^;so~1plY&V|`%!pZes|rGo$S{mln6|4%Ld=WX7O^?&1y z|MNC4`1VKLm;Cqm^;W1*A-a2ZH}C4Uo^bs8bL~pi6J4WHa(ntbz-kpLCicIeY`N%> zDo1i`jm_ZwPCM(2=vd1`Ic9Ex=R3P%xu|UUgWipsmyTNfXTLYUzrg=#|L)gh1plY* zV(TT~|J2Oq!~gaCX=?C)-L7dF{GYn_$khBlb&qSC2LGqdw0V4cAKsQT>4vGn`(<5i zKcAWZQ+Kl8f8hV(jsH_KpAi42X1!wkpN@a2%`3cd`i4Y5Ju%?pV0U}HMhtAsk@s;#s8_9zlZ#??fd*cId-t@RXe%Hequ$&e|EJ?~d;Fi8?H4@zkarjJhL_y(pm$iWdf?Rq`KOVZ*&yU9|KkA-Dwa*WI`v%*N|I_(t{GXcr@qh8g|EckT_&@cIpMQ(+e>xxY1@V7s<_qHg z)H{FqJ@~(P|EZ6d7hG)f|I~Ou{9nBBe`@CE z;s4a!Km4DX`F+g)i#PsH&HO_ApBk@+|5LMGF#a#z_&+uC8S#JWo#rR;e`@Ca;s4Y; zUid#X&oBN@k3W7A|EK2j<3l_5E!Oj&YyJWMr(R(5_waw}`8Mwd|EHd}FXjK#a|#ZH z`F}e8yj?aw#QdLn{_Z38`d;SEygvM&t~Y1jSHb_O-`#gK_&@c>=9BP$YS#0`|EV{d zFTnq)bIm{D|Kg4RQ!`Hu|EFgCRI@pY&F}?3ici4*srh=x|Ec*rAO9C``?vRI`+WNO z7w_}qGY_!B+DYEbH!414yf^;wUq6oaerau9^zA)Yd0%K=!{(cMN3FAMo>p(~{xe@S zf799fnNQ}~ddqG6dKTE{t-VXO^!{i^LGXXJW^wR=csl%_dYOHGjQ>-wu=O7Cf9i#H zz4$+Mj(I@yUyCt#__rnIH}QY!xmya%SN-Ju#+H4-|7rXC1xN94zWozBK5MUPJHCcl zZ0c3EJ}Fj9y~4Z_|5mep9sW{+p{GWQ|k?({5Q?D}5hyPROF~7_F zpBlf5|5I-_zw!9!|9UeI5dY`bW9$9qJXy*+*XG6H|Fr#!+;4*aQ{O**PVj%~;n$@6 zpZemucL)Ecu26YK@PFzS8S{94{rFe(eKGhyZ67~k7V|SRb^TA=IhpyI-gk}~$NWw2 zFGhC`{!jbAJGh0d&wgj7zTW2!tQGv9`qyVhnE!e(Q|~AEzYk7(%=^a!Tg{hG^UmLE z^M`HzpZ4EkKaZFd^Il`#g86^ijt|EFsaM)OD*T^%m3bEYpIZJ;&Hng5^;%os68{%( z{GVF>PaV96&Hq!sWAFF)KlR9$-r)T|Q}6c~(_djetoLcdMuz!++W*?|ql5p`{&QC> z2>ws~>GGT~|4+SW{hHwa)Nia`7yO@k=GxW4|EZr^nDT$>Y4aBb|EGR5XIb!nx}LWR zQtSV!XWM$b_&@clYx08sQ@_3;<^R;P?fs7Vf9h4{Uy3|dBunR8VaLP&sh8OM5&kdU z5B4mPrSGRJ%)j9O)T?bCApTFCw`p_mf9mI6ni2e;`u1^SqpQ}Ohm?^6APskfScyS`!XEHh=nyK%fm9r}9ju;cx6NPlnUgX8~n`)zhT_&@b_yI%aCdaun7 z#Q&*x+xMq8uNhw0_Vd(tcU+a|22Wk%z00=W^6qts#{cPfTkQP^{}*rkpPJW8mwq?; z_2d6akGjd5d3^$j%X|5fL1Nv;1I?`I#J;rp*P--rLx_=Jpee23kKZzdrbe8vs0sVsi)AqWp zD+K?iZqlJz@PF!#U28?dXU)laxy01q^*VK{9o?P#sdvjBwW1kcedgWDyxqVaz^UTd3AhW}HyGhbKt<^|q(x-QcedgJXzez3?JUxxqF_4d57Rq%gmd>H;u zt@(dy`9F1!%Nqv&r^W-~|Kg4RQ!_6P{}*rkpPJjV{;!&Obof7Yf18)b{696`jQM|R z=FQ>%)Xby9|LO7SIykldue!^i`oaIHS$`S-XP@Z?|JS}x?J)mO&GW|)sNo&%v0k3bo+sW z8VCOuZ~ULSx2^9R6+hA+p3v2%7-MwFG{a@`**4?6jsJ@`{!h(3K>T04 z@qcRhKYu>W?=k-`-uOT7Jt4(rVNBd^yB|eYC-^D-QOP}w>JT&J2{rl11?Dr}E%%++Dr|xI- z=~(|)-KS2y;Q!S4Is9L|@qcPQZ^r+r`8>MX&7-sLD|&2Ew`PB4w`o!*YIyA!@9c&b zN121J_h!CM$F4VcGcRcK{IPz#)>W!R!y1k)+-@Flbk&=@JJ@={%>UE*yELpF{GS>h zg#YvFvBv+!JGys#_P;;)Wzp^pf6r$B55`SM^uVhpdgIyff4Y4an{SB!Q+G1Ii2qZ! ztW`7kKQ*7Ha{H=ZkO zw&VY_Klk@w{=I(x=y~n$^X7V{EGcX}+3@D~`*!B{;s12J-nO1H{!h*M@qcR0kN;D1 zKK!4W{jc0q*xWzn|7kn^4*#dd-{Jq_9shdh+#>1YIyF!Fx^&N%?)BO?NzT*j+A1sY z_0~VDO`^LsN&3K^O_KBN(!F56?Bwx!wMx#vOTT^JG!K}5ymbGUe*6E+)1}P=fa&uV)BWA0Y3rBseh@!?`u6{;?fojTe_E%{cTB&Y^!a`1oj&g`z5kd0JGqDf zwP@+x`d@mpKCia%|M!iYF-e1RupY-jlx7(+9VaxyN_VRyfZjb+qH~vp8|EDf$_ZR=C z=KkaV)TPXm;s11h%b91}e}7?@vWM%(!;dfNGrJ&oNc`W!*CxA)t=FsV(FrF+joLrH zWdC2ggBPUjd-;-ajrIl~sQG{DV#ocTIx1Z}_&@J6Q~pm~q;$#P|I}xg_hbH_x@eiw z!T;&}tbfV+zv_$6Egx-s@*%(8i){VRQDqAIz@~bIS(*r!Hmdh2sBo{n_V~3;s`C%RDIlPtE$l_&@dO=9%z+>PE$i z2LGq#c=$gxeh>eru4di}|EKFIdC_^n|EbTenVSEn#{1#_;*I}PSGS*6@PF!yZNBb* zI^OQxsdj_tv+lQfceuD-@PE3V26ZnE{!d-4O3MGKJJ@_b{GYnrc_oAYQ@1gn_4VrU zzP+o>GsOStdhl-ezj)*S)XX2m|Ec+T;i<=O@Ma!i$EUCN#xLUkw0{e`|M)*O>+|CO zbba_f=Kra=zxY43{GYmhotnY_skuJr_bo_eF(D z=S3Ate3?^a>7=l}Z<%tXg8#em;2pvLonEd;@PD@EWbl7=GwKBYr*6}+a`1oZYeu(= z-aKbtj?JhFo^ROb4$+!_?(rUQRd)2<-re4KKm4Eem;X~Ue~du!n2>wr9e^|rd z{{~%hTkwAkhc^!XPuGg|Eck1_&+uC-0**Dj)(tK#3oo41GmQ+K&J<^R;3Zn~7eKlbgc zpNs#~cIGAG|J2O4!~dx}n@_|4so9SIQ?vdn{!g7@^WyM->P+)w_&+uKu|=No=JB5X?bF`)zxlaOdE@`~ ze(Y)d`xjp_**NgAl{?>iIoq2!wKb@cZga3;+{?FSU5B#6Hn>}9kZ*P1i{!iQa zddL5%@qqZhc;o-n_*wj)y2a4?!T+f%+wZ^a^Q|2F%qe`ncGuj;`TWcKjnygt*SP)Y z;QtmK*khilUyiL&6};dQ^DZY3@8i9}*6+ptY5Pw5ybb>sZ~UK{&+G7i@y7qD`FxJ~ zf9eABbof8@Hk;>UpD%jjIqdVt!nS!H_&;4ge#}0<^zF?1SlYIw_ipoe_&*(gyZJBt zU%c^uYWcr-{TV-uSg?$7A#a^7G5`djdSW~x#i@Rwu3|Ealu_&+t?5C5k=Y@QDPr#@gF z6aS~)X3wX6zVGMbdfVP~syANn&H*PU`ismHz4LAVV^yL=Uv~Dt7wi7y+4;5}{ClE1 zess*6&vSEb`85&a?IA@PF#}SFE$=Z?r#uofpqD?{cMg)Uy-wO}$5q z9~JzcZoe#lMeu*>_qOk`d0m(I@!#IEEBHTM|J=I~tD4cV1<;Sw8A28o${!h1m^}AzSpEvU=@qgOB!CtTUKQ;5R z@PBGvfA~N3x^I3C{!jNG&u7Q??d#3|+3Pt&*Sprdj;$5zz1-#z^)9)Cnjr}v% zd!2nfPCK$E(fB`|Ki51V{!h*RcKw;^_4~gG{!iDpX7|zH|J2L#Q}h4Sk3aue@PF!Y z*Uk^~|J0W>c_{clb=R7&1plYLGW#bvt7(F5Q zKlRcZdIkTd{$yC2;Q#b^es1gIG5=5f!*e$V|EI6NCCB}r`ltO{g8x%*JMRC~dyjq< z{GWQ|k*|XPQ?D^kg8x%5wfR)|KlL)3w}t;xudrtRU%c^u>ec4|8ov8krrwX&e*1&X zPn++ZZ}X+vmt5?<#^(Q--}auhJ-okr-}L;e!T;%alg5k*{!cw(;6R(Nyv6sw;hx)r z|I_vbd8>o}Q{$6uKCSQnzWEUI>)x-}dXeVayPr*%H0tBpZc@) zn}Yw-GtzC?+pG=x6j#` z@_*{jckK!OPyN~UT@n6I-%pwMhyRN={!jhM#%;m>sh^rX*ZfV{Ed4zE**$mKdYk8X z_p!f^?lJZ}@2F)BTTipR_s9=ki1yC7(EF7Yxlxr*D|*kj@Bgi{s`&ZykNZEJfAeww zr(R_~9{(3_{GWQmH$Mdb7jOKZw|#%b|EV|H&)fJvH69=Tr^f5!|I};k{nCCu_FiW{ zFX8{RecMkd|EJ#iW6J-j@p<^ac;o-ncs%@{dY4_#purve@#5!y{GXl=e*VY*squ~Y zzj)*S)XW3K|NW!v$m9O+|B&|H;Z>De_x3_SdQp0nPACBql8}&w)DT({LN6+abVWt6 ziv?6f5U^sw-W3#;5_$_IKq#R@01*Z3?WjkOzd4?{#@uV~_r2b8eb@J&x6dliD!Y(% z?=gOG{vVnCUy$Mdas9orfB1i7{Qd|2ANhp*`vLwR8F_i||H$Y^hW{62_04+#H{d|1AZ!v7=F|Kt9Ve<&`Q&1b*(fbjn~zE6BX_+$ehmMQ44-e}U2~1$`@#R?{NMw^|0BaUg#SlAA$`N}|Hwy+ zwf~pA`_x(I|B;b52>*|~=lDtI{{#C*4>3((xR7)H;51TqVxfCe0{+l&wFc$ zasG~--t|jgG2Xm&oAdwp_tp(7RyhBUJbv_O=l_vgr8ji`AGx*ofb#dhG;+VbEuH_j z==nRG|2Lq2E9d`_6Z^Gt{$G&c|B+MrMR|wB|08$FZtL>@$Z12`IscE`eN>$D|HwUs z;s22{#0P}`N5=2TXXmdCWAy)W{_wrv|B-XVA4L8i8ToDh?zG9)A9PKeS1Wh3G4kBt z|8aSY!~Y}G{|hqwKQjHlAjAJ7=Zen<|BsA3IQW0$tdWV{RoT03KIn&q|HtFclD{9l zuxC%&*;O-~-`8LIT~}S$Ym7eDni+*@?T+2<{66@A@niNGBcBoeAIGoG()>SiuWa@I z$bAR5asD3}*AM<58F_*5|HwT?#5w^*Ia=Nn5uKWpa${X)CBO`AQ{$G&c|B;c;2mdd~4aEN=XG!1pqfvj_`358ZkJqz@^nb(u zBP0J4{vR1WA@cvoedPXx|3~hh-OihP;-9p8|Gdrleqi{2ft(mcI zetO@m4&I{V62^Tp!t?yDP7C(|`zJ()J-_Q0AMWq`4<9GOpXo38EzeJ#m`*93fT20e32aKYew!rvTyhQD@XSGM*4&Bvx4)BWc2Tbjf`g13 zzXz`N{UT$`x54xfV?I%TEVS`TmzQz=pRF$p|BsA*Uig3HG9^nm|BqZs^7oMc7i8rB zk?H@DF(3GUWXu=&e`NTL@c)7g|Bp=nZ}yB;&UdVKc`4`rk*i$hd5LA8SWkxkw`lI% zFoyrvt&cptxMPnQqaPRff82iEx^t?uQ|dBC>c?5aB6Yn4JA*SLXq-;*5>Ns|Bsy7w!Jqw z_YPy^;UWKz$J0jqNc8`bW17@<{vSD^WdrB`kvmC#A^bmbQftls`G4ft zsOHZ93vpBD|B>U{v~d0(xm~N)&i@NC{6BJQ`F#icKhD36e1Am#9~tvQ{vVf*Zr#H9 ze;mj5;r|60{vVnCADR9ix7V^&6W9MsZV{#Vf8^H9uX6q$8NMp~KXO{bt6cscxpUom z&i^Afs#nALf80M_U+DiOm%gH`^Z$Yj|Bvg}yrP2h|H!o^PZItg8GXUX{|hqm|H!qZ zj~f2pKPT5Z|Bv~9+Sd7h0-q6+gf8+sU(wzTC&bdCt%l_-g zy47zEa{gYHJny-+_^@$*`F-NEn+_TG75{Jbn?=SQg^~Zq^*hPGr;-0hPLY5A!v7<8 z8Jp<*KQj7z;s24*KMenm^GhF>==?u&_erVF|0DOF(%JccxhSLgqc;m66}cWimE^gkHG|C4@*Foyrf^^t!E|1Ze$_a|elFTYPU z9x8s4^j8=UkvzfEmDYqY{68MgVCidZad1`Gc<&V}jgeO<{TjvtC0`EyALldjww})a zBM*~&JNSR(9LZ0E|3@BpTNmg5kw;5kF7p34pAq7hU0b-+mdEkP?~9F*2M7O;%je4V zg8vs}_QuY|0AP+8U7y`{mbzG$ngE({{*}k!v}=_7i9Q5dI(Mi#$O1e?czSdVwvE`9@cK(iq1B|Bw5_`GfyQ z&XnVa|3`+O2mg-@9}xZ@8P^Z~9~svV{vWxk+~4s3$X81~C;UG$<^%tajPv=)=7)^? z;(iwYFE|eW&sg#o;r|60{vVn7e?b;E&&J^w!vEtqd`ieX-|zD?(l06gA9?+$GtU1b@A=l{ zZ>;0`c>X5O=ZueB`X0~kjN$*u^Sv;Zb&c`-@XGEzjp6GRM0YnvUI+X??jO(d;Qx`4 zA1L`G#>fMN|HttovON4hGJH1pe`NS@@c)7g|BsC4k?8*oGW@@D@Ah`SB>H{f|B=z} z3;!?3@c)7=`7fdEiJvF=Fky`RKQ4dxhu@t4M@By_{J$W>|05&s4*nmR`F~{e7sLM} zV|#BkuVIY+ovBdG_?V2>|EX#iOaGoR&Zp$_7^9C@@_UR6<@~_^nck?}km{vR37!z(}Y-CABh>S;7GCL-)s-D^vfdukMn)^z)|P_ zk>3zMOZ*ZW|5%>4ihp7ZA4&X_Fn(wHGUILHA2q!C17q}=!vB*DJm-5NPX_sa>mhX2R)k%t5Sk9<(pUzPfx%@2LSqpIIy zyi58vGd{f4__Z~AdE=?m&i^B? zk$zv~{{7l=k41sK3pr~C7*o`f6eAI`^kCm;qth>Ch~hY z_7R@c+2Ig416)|Bt*u{7U$LWcYya|Hzw9 zf9?D~@;31cC0{g!_Y?d=@uk98{HIio?>+Su?vGT?Z;6OVDp^+_&3D&i~{7CJcJP`G4eleE*NU=*|aS{vY|FiJJdM zUUy@z^Z&@p$M$yqAJ50C>$^Gsk9>Z?H0S^E_%|$j!{z^xzxVV1$VDfM@&01x>-ZO6 zI{%O3$S3~wmKRd_df)lg1^IkjV!Ty+!1BjlH-^vmRHb)}cZvTe?~lei#TS(KPh-w=OMK0l4ONPd<0 z^~UJimCs+}rQ(ag|Ks*P*s;s`f5wFeo&QJvNcJb6|F%4QK;-|~xS#(=Ugi6L*|tr<)I||3}^^+lT*0e!K99^Z&?mmghPDkKbSCJ@=aP|HuuaVx9j-_T=wd@c+nT z7d_?tKQi(X;s238lkdwDcQi5HF7NkCi<=qmkvz3ue{B(Bxj&ODwldx)e(8fv+8D!! z-<}v9#+3)OH%6Xs?zkA^{qlQ-#dmi!-Y0(knFaA--141HA(rp!Q`aRK!|z*uFxlAo za~D&M@qN8Zi7v+Yem}cbS7VIJ_jhCXfAam_82Ns3u8fb$_j~w%Jbz&Le`Ngr0{$QQ zkbJ*?t3g)U<2!pf-|w9KUIqRi`LyJdBma+#`5^x<$ngKTJV_%GW@&)1lk&&0!Ztb1M@cVwUbalYsiJ|q3VP<@JsHKQjG4GV}k)1-}1BMxHJFKk~lgr#$5UkqgBC`{gobR_|-$Cd9k?H@D(f4;&Ti z<^Q$A82;C}+PjQ%#0M-9Uto;9Klp!~&j4Be-sQXPeDohF`Eug_@qG7_eqQ*0WcXh2 z|E4`N(D{Gx!QlUqGsUNZ{}*KB|B<^7Z0GX-$ndw2|3|)B{4V%^}FzFW`myuWVA;l5BL|2O{!d3^By=x3mx6aHW7gcZ*J zLp~q;KQj7Rt2{9={k4qGo$m*R{}*KVe`Mqb!v7<~|3UsAd9dV}!T%#?Nxoce`c1~j zH$?s)$HDObjAj2bYTpvZ4_3I=_pBjftP{|g=;{J$W-bLE5SS=pbiY5T};>F~Ku zNnbD-^Q&I+A!Fnd%I`Cb;ln-fb2zV<{BYPf{6Fpw{ucZ{GWG}mkBoj@_Quz4);0PZu(zhKT_ea?N`!#rWY>2Ubmz7W2IQZYGAx6LN=bPu-I2isP zw~zCO{68|zAN)Tu<`4gm3_lV69~nLy{68{|ANhYh<}G&qAMyi{|3^kYG5kNW)cZRB zFUau!e!BMs=l_+Iyg&GVWaRz9|099yhKmJ9sra#8o8! z?%soQY#hfA|BvhA`oRASGWd_v^^k#Rkc|Ht`ME>*($e`NTW@c+ni`n^}{huD+z zk^IUm8!uH}`+vFoWmi=4F5NoI_E)i9E$9Dn|CMXk^gix5YkhX_mz?id7X72*|B|Huh#HUE!{<3s*mkdglvWaR&m;qSHBKgP~SRFwAr@_e_I z-;==qBjb28zqrO2`$PU8$KgN1|0Bacg#Sl|Ux@raa*Gx%yi@-S53%@uPnQm7^#5|c z$OpW$%djwp|Htu6x&P4rOYT~~q4WR9@a2&IXZx3YOZb0e_<6|xBf}qt|Ht*4R4nKG zKXS9m6`cP^u3WjY^Z&@m2ZaAeu35|P|4n>Z{l7-dH2=?M^dkp9f1(>V4dcd5!}9?f zHK`Xij{HCPf45%f=={IB_0|9Tpm#^-|FvqM{vWw_YIAR7Zm~R1k9B@uYsuq(AmNm8 zlKdVH`F|Ww8Jpz%KXT{m1@+dy6k7zkf9Dbz>@i zA88E#N`60SJV5$JrC-4~OZ+qVf7~DZIpqJ5hf1F>^8d)l+k^i{rvFDC;ro94^|0Cmi!2ct69Ut%fKk}d(I^yqxHl8!KgY*A5o^^eD=l_wj z$92HpA8q-e<6@lu$NO=_ggBS~M^2d-=lnl%m#K-)|08EkNpb!k8F_s0|H$3t_~HKr z8U7!+x7|H(5)=l_j({SKG^N1nT4 zx%2$tA2+L&jh_)ePPSzXzYhK%w~xMG_%oc~AOC4IW^|H#LL;s23O z{O~Ui{vR3hhyO>${NewR(eDfYFUau!$OmN{{$G&KZ7gBOw@^_dc!PtZ23=R`{@7W`B*8- z!~Y|1K6}yme`NHP!v7;9zYqRjkm3K4cggc&@n4M54<~+%@d@z-;QvjU73KUu_>%Dd z$nYWI|B<)J>mB|d8F@xSj?A;|A#ZT^8*{=~x(1EW{|o<*^8>^GBcsm~{vY}I3 zN4{;*!_NOBC*<~U{vY|Cc@H@Mk9^`gcZ1FHhQ;!sA1K@ZoC5jq&<}|HpCoiSYl(`O+T@|Bnp+ zuk^Mmsoee!=>xBxT-$h~@BeZBbD#gr`G4ebQ}UeuM{e8kLFfOGJ9l{5`G4eIsqf4A z%(U%~ANYbd^TvV3GpBqiKH~`EC-0i=Eg5>f@%r#TkGw+!~cN) zM_wa&oACe0cRjP%`G4f0Q*LnnA9=voQ7-?FJn4x!&i^B?JbuLaf8=%Y`2+ut4Bs31 zf5!6pCw_Y>KW|nZI0paS_;vB~|Qo;xi)ukGy8* zUg!UjpWjpD{6F%2%U3)9kDvedytvr;f8+|%pMm^8vKLd%`G4fmPfvCJANi>dmOB5B zyjgr6_^8GrD;s0?Q`MvP}$nfd@ex+Ml!~0rT9^aPFdKe!QUrxUN+w%B* zPIhr`8wc0^rH?Uu!Q!(0jgiL(|Bu^0^TSWh|0AFB{Xa6+hyO>0kGOH#&@g^<)^KAi zKVb1lWB7wLmyR~Z@go0^#|u9Z{$G&c|B>~UO zJAbQCK3`tE=|*Gt>d61&@(1Mi8u0(f2j%w~@c+p0LE-%K6?`F;r* zjhz2SPVU#-TM@N9O}=wGzb~mzGyFZ#I5D%S^Zz)WnAybnf8?~RC~y4tpQkO)>EL{{ zHsUMID!0mO@c)7g|BnoR5dI$-d2sOm$mokj|1UX5@&eylay;$QC+(g8g*?P9 zD^D0BFY$|gCyjAEyi2FT_^MK;jp6V8df|+1e~>)Ss8;F=<56-y!2jd<8X-O){68}M zJ@|iQ^!>vB<9sm=|1Ze!|AGwvk38(!1lRw|?ZF>y{QWmJj{7IQ+;_%Lczj^^e`Mqf!v7=pmwZ6@e`MTW@c+oTzu^Dz`lreA@c+nNWP9-c$V23QLjGTk zJje0bddh7;PXECYyTH_O9=Oq;5WhlqfY`q zsMO*K=`mkD>wLeysmad&Bg0pN|3`-J1pkkWygB%PWaQ1k|0BZ>g#SlIA1?eqGV%xE z{{Uxw?h9fxs&)yx$|#Lzqi7(&i6}=5uXY9e*s4SFB$$C z{68}0Uuy6SV;nE~f4P0|$fP^N#>=+3%Q#D(-!HF!w=tH7{})^z{vR2B9{j%`!~Y|v zNZ%p+KQi(F;s23`$nnAdBctCL`F~{ke>^_0%m4Gw2N?d}=5Eh8{}28n{J$W>|0830 z_%k;gMQGG8#l|HJDcIKRmJ!^roa$o+Lq2%m4H&lh=qA{npe;Qk{Sd2qq; zNG>7ybHVY;%7puYUfFOiQ7$6S@4w{#Mf!df#dizt5B?kczlSc~=KMb}{68}NKXTbp zm%04EAjAKY%v0z8VR`s}WNZ)qAGw?eX7K;W@Y~@3k>U4E>m6eFeXaM-vvK%+@c+1f z^drOn3o`saGV<-<|B>ncmCc;t{6EY$`x;q(#~se+ga3y9U$Q5D9{PWS4F8XOnVLIA1XQKe8wOApAcv`k<@+ILqc&v3wQh|8c%`YSs5< zeJsnrbGP&T>eZ{~{68}C#NhvttCmy$k6gJ-S?B+eYm_PHRh{*q?XOk62HvGIA#TvJ znb&vAOq*XL@&CT=6=LMEUHHqP1Azu*w9~pif{6BKX4sD(PN5=Z_|HvKM$2$Ly92*no z{d@C7yPx9P#d;qXOfc@yTKzv>zgFVs!~Y{k%l8BLf8_+xV?r|HUE#?ph|h?|B-7}sp|Yca-A#H z|0CC|UPt?XTi)yZzeWw4s{iM68+pA2KX0NMHwk0-eZlen%?E`4_uIEsoc~w3YB`tx z*Yw6J&i}iz)@5GOEvMIIeOKA}em(mnIRB5Fp4-~_f83#5@0w+)I2x_ubYyc z|Htit;s24*KMVhlj66H|e`NT6@c)7g|BnoR5dI$-`GxTR$nf{z|B-RO!2cs7Uk>?y zWaQDo|0BcSga1cHKP~(}GJHSye?f--NA4%SEBrrlU-3)f{~61C;Qx`~CnEok+*8gs z^8bPi|BsCG2mg=E{68}NKQjD6_)`$NWWaR&m;V;7f3o`saGR`mj zKQhiQ{68{$zbo&)+wPZ4@%5y8CBWUim&?ouWB7l(zp+02KQh*b|3@Bhdk^RTk(0;7 zIRB5_Xhf7(Z^MXn(|#=N{J!g#Oc8%+nDM>K-*f&S$CsVg{6F$u@mt{kk&7;=|F>X4 zY3CCjlINB1|H$|0D00ely8OF^2yq&rd@vzMDK>H9q{)A0GTao)7fb!v7;5m-$P7oAGJ! z)!_ee9R0ZREZP`(h4BA4j^l;@C(p>8KM4N~{vXG|@c+p0{l5RLei+05K`hR5lf8>{a z|Bw8d_=fQRc)s&aO5dgUf8-5kUH+8urZdh@G2SM=5&SXDer}O`~e)^ob&i^C7ApQ{iKQf+w!~Y|n zkmG^>$KyNr&G*j#BOj3WKXIAX!hwUoR(SDS=l>xS5B?t*{vY|^*B6}sN8b14dFTI; zx1CY{kNj~#f%sM5tl{<_5te>g;}=e!h7V_q{4?>>j8_~y1b@x=y?qDZYp&t^-emKfE%V)HE*ZF_k-k`qEIRB4)^Mp^F|3`l6o=2VkN1iqHPUruTH%=er{6F&N6LXyZ zM_xI;m&^Yn7tgy9_lF%X{Xd=$`hVmDr`7)>ACcD&{6D^4cbq%t{6F&Eix-{$N8WW& z{Xg=KuQmUVyxsTzf(-wU4F41UUy$Mdk?H>h8U7!6lk_{n|0B;_{F3wk$hngzI{%NH zagF+aij?Q<+L>|B>nck>QWS|05TQ zp9=raSbQwx|B>-|3jdD`{|o*f8U7diKQeqbHh^8{vY|U><|7Q8TrHT|H#NghW{7j6PvF!hF|yk zkuk>bEhl|@z40Nr9x<1VH$E)q5B?vwcS80D|BnoR4*p;9$EBSA2Ok~&ADQ`oTpsg- z|3}9D;QtwmuL%E-3||!fA9x?Gi^TT_x<$g2aMsf)>`sl zh{f-_`<;iv82%rR=h(Tgoc~8YD!-qA|3}^}zn6gj$Nle--&4T?nkG$RY|H$wG;s2503&Q^+GygBh=>H`boIK;r+WnO6f9LUH@9V=) z8^ibOd-jKn$EB2{J!3UV!cOZA2aSdG~W4t9PcZ6ckutn1EfzE{vR2>B>X?J z^CiXqBO{Lw{vY>`ygvAUWaI_LHausHKHvd~Um9cisX6Dv82%sEhhGT)FUau!$b;m5 zg#Q=h%Ze_AG5o*ac)Iw1WXuo#A9;w}A9tnxV2pm?=Z5@fjJ&|f{eHIl1^JTj|9HQE z;s24bJp4a0wg>-@Ja}k~^Z$Yj|Bnp+5dI(MmnC_G@c)c`|Bp=nkDNN7rSt#DU31$y z|Bu%Xd6V$}$i2ibg#Sk#loRWXD^tQaSNec|Srp=4S?#@}&s>(y?e`qe&fBoKWIE^H zBO^TjFSSc}K44^DC;D@P&-)_ty5QHq|Dz8wIJTYh|HP?t{vR0me`NT3@c+p0yWszk z@q8El9~piZ{6BJXjO5#h|3`+;2mg$^J4gaWGpZLZH&Ab_{5JT1+&&oopN+Ta;KBb3GWd_Y`(_}_N9OoL+dj69x59uyPqI}Yh6eb#~eyzbH$9ptX!j|4f=r;E(ni=2NXNA@E}a-{zk$&vYo z=-Up?FYQ)c|09>Ip#C5CSE@pJzyDYFe|e>fe*dpBd=~BhRjyG+@&=F3lfKf<&i6z9 z9sEBs{6FpgO>%yqC;5Kb|EqkN_=?*9tLu9e%K81j$|b8*^80_4D_&8~`*k|{fR!s$ zE$cn``yAsMRm*#A?+NE^|2$^n)vHwSrYwC_`gnE!$jjT-F~r^#WxU2KAF*+-;$_}F zDFK!Pg8#?$Jz@BNWaJ5I|F6yu*9-n1=Zkzv_AeB{6DUroSf|U|LXF1zlZ*|azF+u%WcYs# z-W_g?`w97f+<%7_n*T>ezcTzk9uNILGJI6+|Mky@F!KL6-a_*I;Qw)Z=*LC=AGv|} zf!hD8$6Mp72G0NE`gNN%asHpN^o7Td&9?0$A5i;$b^pi*)c#-P=2a?sd*2%%eZQ&B z_p4Z){l6i;e_1~puT!T^*yjy=;Na&E<{M-jPbB~J;aTZ_Jd`(T{=)R?)vJ3opFCq+ zwNWYO|8cy>pd{!2kuydodRuNfDgCNNd6^X#ruQ1v$@?njgfaeJP$A*Caqkfwz34i} zjG6z(^#@-Y=lB2W_VD+Pabg^3(dv&kJMte>@&6ul>Jz{`yQ#cK#p7;Zth=FULFk{l6iG{})^y{vSDGauWW& zXZz2T`N;2ojR%cScm5xj&%HtN?_B?{zx|2n&i~_h=7coo|B?GjexLUL>iv)N0soKV z$mfIq7i8`K)#Wh`|BvGtzW+yVe^Y1Y|B+*FNp=1o8F_))|Et>rYyYp$a(`+6Z-}-3 zR~h#s{6D@Pkv|9jj|{&I{$G#}Z-2q&3;*uV_ZNq8!}-sLSni)Lw>)Qzd_V2~)%_#i zPy2sEto^^r$gkA?-w=O)W}$5leb?2tE-*$PHvB)%7x%07|LXem|2Pi+QTu;&9IXAn z%JBKL|JPq%d_C>|RSxz4hFJT5L(AX%#%!A(e7~n2nPm*WZ^fjC!}wUghm4W8r~SXW zJ+SuwD)*57YVH43?s;1;Z}+G7+WLK`_j3Lp?-wxqKXO0u`{4hPk>>~h&sh3>;s24d zX7qIaAGyyA_5a98<2pM3j~qR^jr0Gcb2RUYp^v5C==*=LNMM~2^r{J$W>|05$W5dL3~;s250AHx457fIe8{68}MGx&ex zBftLT{6C%#q9X#A@5!)pJpUQcXa`+q|$bF=xqC3z&s|Kof=lIO8i zAKzdMUtrdVHOA;C{-e!G<9z8yz45Q*#_*-i7A!T+7asD``(X_KkN4MJ**^R~GV*TV z|B-jf^J(eVG{*kLzcGd%2>*}E@0a@-{vUalTrc>4Qv&vO1BxpQi?^Z&TL-1~0#`+s$N%Z}}L{vXFbl=}nzA9=aFf2}#5 zXuMDS2I>1YKJ>%S@ZqGtcxT?tsdLh|e)l8%Ea?Z{nFpUOU&edBU(3c%i2opdm+{ey z-@tdX>ikGcFm@{5vZh3qx*69s$WuNg0V>lOHLc^og-pcb}o>~$=U<&7U- z_q6=`#dGW6{4Fck=lnm;H(#Fb!~Y|r-&(ev%NXs?f=#LgZ>}K;d99RrO#H! z3yUu}|Bt-m2(DKx8~?cAlH_qVGQNGmvao;uT{rG?^i!wu_?ox6OYVox#sg|TGke+&K}8GexV|LXQ}yxRY(48H~bANQ9pd57}(oyPUI z9Y2lFcVny%|BuVBJ)`~~IZyHdk^e_7^z;A7d!!Fq`+xQG6#c}=|KtAhx6yv=_9uYSM0>y?-N{$J&ity=p1zsgnP%lrMm%J;rD!|(r9e)+TI&i~`~ zcbz@$_y6kn7V#yu|5v%->u>!2UuAs0YX7e?K3}!}R~bH__Wvs5{?`6qpXL69|Hu8q z=Y#)8#`pDkRpO-|RKM@w_c?=_bqetJUj3vbWB7Mp^h-9z?|b0?1=olFM?NOM?}7hE zM!q)uKk`}W&xQX-F82LDGX1|G!~Y91{J$W7GiZSHmFDM-t@>#C;ctKNmQTnwK5*e1 z@9w(?8sqy+*Lj1Ckw0Gk)gi{nlijy`m~o-_yC~J_`KZii?1R&c z;b&_9uU=oU_Wvs5^HKYM{c*X!wEtJx`KYe{R~h#o^8Yx0M95Bxs(e?iv% zUw!?d?|t3Mg|@vt^8V9g^CDyVf875L=~svUN8Wenn0H_HGd5o^{6C)0U58IN|Bt*= z`q$zA86Q6C-CAa`ov$5-j(D}JzF@rVK#}MCKmU4wo&V?a=G}$r|M|RrhwuOSymiMe z=l{iA+M1{S-%jWMk+*H!U}canTK_u|8Gh0t}tHvM}aZ@KOR3A{vR3rKHC4Q=O3*7 zzsktp)Ba!OKDp7JtQ%Tid_d&?aeKWazwyViMbgK*KW}TJC)2x1pL69Vhr&2I`LJ<{ z^cVHXJz`A%kL#z2&jtUFoG$ru$p0hv6#oqVAGz1CSm*zdd&~U*|1ZeM|0Ba^OKWh( zc(C|`BNNUVBcJiE0bdvoxh}zbZo)ZZ_=PJT_|h2t!v`0iH|{U_2tP0XDvYn#{k1W! ze~0rI!WjM^&u6aqrBiBu6B-x4bWY5-#>1r#`Q6O#j7MCX>gA99-Wd6Z@c+2IY(Jy@P@t=*+Fa6V-zZm2ERNe4v7`Hq2oAK~rabDkF{$)H&@&YGS{=*o4p!Waj z{R7tiUuEPCYX7hDfT0~+{vYRy>#P00I*#kB{l9vDbsy5v@BdZqHaOPP{$FME4a5KA z_3kIWDf~ZjMs^41|8ajk`bRtekFQ_&e{U=)mCpCOF5RNT{{0r||3&&mk-iRmK<)ok ze`L7$INJZKJV<;!?f*@1J|KKB?f+GVpQZi3%J9*&|2M?i|Er9AKJEVvvG)He<9V|7 z|0=@=)BfKOYyYn@d@^y{r0-U_b=#JH|F3fUn6}RU`@2iL^Z(!NxUz;Qw(P^MU`z{lQ;@|Htu^Htn4M7i8`K4b5Nsf0YyE-v`?NtBm{_?f+G7*Q%*^ z{TKJy_T$?`c~y$;H^%%%kDX}@-y!Zqh>?d>eh~V8^>~t6M|mHK&&T=Wd~5%&jw8G`20FDPcAZVE+-;S5B<}@^&|bVu8HCKfkWcL{ky>tzFnj* z7wP{+`fQPYT))_GUoi6c;9myk8_DR4435W%4;tkE&HoLKNBV)09Qpnc$&vHL{Se%K zy!gaHPD%(r-v4&~BJ&0#_m6zI;PxZ){~{UwRdD&pe85PKTt1TF;{~?|UoXh;{WSmY z*Svp4{gqDt@1ct!hW{62_bgBX&M;e&YWnd42x%LOvk;KQ3QF ze9t~5LgU~;vn8L;Umn-vi5;_SdH6pU`h~d473IBd`yaOPN>$1_|BvSn%ftWsJLAv1 zZ?e5E<;$1%^Z)*x*ZlGlUFiQk^o}z0R?YuYhR+KBkK^z=(f>=P|HtjOs#Dj`|I_`| zYf#hA|I_PNr(ShG|4+GU-CBPBpK`+}=Km?f$I|>i<=CjEe*T|wpH{8?{6FR1k|(J7 zf67TwEu8sN?7V>G8(Y zY2fGoDZ`i2{6FQZuDZ(kf81W9dNus~KiyybT37h_f6CPw)b;cKlxsC^=;!~1#^L{Q zd$pTf<@$fgQB51T{$Fy#I@P?XZ%nfJ*A>64`Fj(M>({UE=l|*TZ&K$fKmSj;dHp6{ z@4Opqd6yTrah!3ye4fNk7;E!M?%3L!c+(i;&atih{69S(Nik7g(Y@D(jl=)reDQq| z{vR3NKQ#YOj~~9D=KqCQ^Z%6L`@#R?`pEwqxNMj)`fndwA$flO`wjY}`&1Za#{>WG zvMYufd|3E@i=;ZJ~H}$$(L8Hz1|H%0J2K+xV`Vip%k^7B~_4EI9{VeG>xV89jXk7Yy z;s3oFUU%IMdH|HtD+exT<6 z={Wp8&Hqz|52*Qn%2;0W|CB@df6BcjpHK7ul(Q#wcK#pt2ZsMg&XK%C_3`@f4AP##^|fw{hvi)4F8YY8zQe4_!FzaKM(AKT{CqhZ{C<0HoK{owy`e%LJJ#F-QLri_1*o(=`+;-^lKjow1!)gAXaLCf}Bw6 zN;@C$AAj(w8sq%Dcd=3!k3Co+j2o;g7siL*E@O=CNj8Qt{Kh_amo!HHW2tc^jCaWO zyXU3$X$O`iY3|0AzC z{e|=Y$ScK%ILF&cGU_U?q zPuG|7S3mzxdE}`xa{e>y_&$~X&Z>`hG2SS7pz!~AeDE#c|B>O>Nf)K@dU@V1ewO3~ z&UQW^-tXZ5k&&ka|BsCRK=Hqf3ol(lKHM6P<9Nj%Ge#e&_+`esBri%_t2N@tIo}ZD zn*XP~Q+z1R|5M)R`+wa2Cdmtw|F-RIJ$c&se;i-$`+ww(a=*g=BY&`cH|B3V_sut* z%g6D{<=@x%Z?e~}0hTwOyJ4yPd&YCi!2kPPeL~6i)ANVCS^00{jlTcK@ojSd$o5jm zxIXaz$jE2Z{69T@u=tHOUL?MVENcvZ1^yq`KPvY-{6F#@xj*6mk@w2|FRq?3{XdR_ z<9c37;r+7j^ac1*#s?(7Q|6z_<@cVx=;#0G@ozhP#`%97U%KlX=l_v!U$`8{YwM36 z_ZjjjjpI8$g#1e5|3}_&TKzxr^UFSR{vY|inRhz>kDQX$ z$@za|@75X4|09nQe+2#?`BUlhmVSEUJn7q=TIQ_rYVk=l|4-i^m+so@{6DTgf8PN= z|4+x?y~O-KWgL&>>)Q5^2Ppo%@lN^t6hGg1tN6n3|G53l@_7jVkBmM~@&AoCpZ(I$ z|I_okM%IV_$Lj&VPx6IrdH96z|F}K$3(NPDG=Bc(%lnype=%Nvq}b2@)9(+@f3nKY z|5Kjw{A+&xpR(5`&d>i-uHUJdpZ}-)(#kje{6FP)*M08i|0(Z1cf$F9oX=MA88!b; z$MJqGU7t2T`hQ%W{vR2BzUKew`uP0lysw?)h3WU_LV3UP&UY~0C--mupRvY=>x^4~Qa-+5xBfqWXjQlX}xnR37{H?L??+9b~e>{Ki&*1+B8UA08 zHUCe~50=;bKV|rU@c+0xSo8mMyx)jeKmSiTb7*_#|8e=ga{l4}k>Llz|Ks^b{vZ55 zGV=f6|B;ikTRZ=coFaY0n*XQQ5B}iYKORl%-hOW0jCJ$VyNkbdtlV+qu7hH{#3m<< z;eS2b`J^%Y!QXOD8N(mUom^~;{J`Z8oi;{(;1w^PF~;+in?5~j3}0?f!57BxG2#Dl z{>W>D|3}98hW|%~9|-@?Sf01Q|053^li>CH=b|z4BCnru$@T}{H2)jp;lhpI`8JGa zZurg^%bz;(y)k^lQqTNo+aHR4;iW$r4<6ac>$3f4WArJHKJ!Z$-}~pU#zWNuEuk%OoFAxqtt*-i4+mB@a;N+chJ~>mOB0@&NVy zEcxojVbAj-eZP$Mt-{8UR~PhABK;%yN$~&vn)8eNJ>buD_(+=n_j6vqPJg6lNWPus z|0(xw8{_ByDW|rT=fy7nPdQogW;Fj#8Tm4r|EJu(eS1Iu&tG2rJotYPR!~M>pXUE5 z!!OeOzYxR!UA~~p|NAlT*q(o-J0HpA|0%;K)BHbW_=NEP{(4^-exK(5 zDZ{T@*6R)%2W$RcXnD>5Q-&|7`F|n4w(>o;K76=}-o3`{+eUe-ehhJR>lV)c<9s?r zw|4#?8OI0zkBsAk{}*KVe`MqV!vEv>0&D)C&JTX4=KqEGy2OWUefWNfABPzEa`68q zPx&FQ?IXXXXSI#>^Z%3ww2ATa|CDh)H2+VxkK@<;KV=-h=Km?9A5ruFl+pLB`G5ZU z@HqqdYTaVPeZ5`@;rV!x{@y_G8H4L14>HJU5q-hA5&gIWJO1DKdXfFUk$HRnZ9LMy zi}dLtU%!bF^XVKPo(C8?-^kHq!z1xg|CEu}rv9HY{66*nLahE@ zh}HiKvHE`@R{u{q( z0sZ_xvM2ti`hPlpS$Xjpo&To{f79>(b$%iGg8lwq#~9C_^MLqIcR8+fc^U7uN+I?n zU()aYRo_$c%>4de$BpIw@cVxqBk!zz%e(D7i_hBn`sv1XDwXv{o}X^#vtIQY-c#S+YTUSP zJ#XhPw-_Tot;An98^Z@g{vWSLvjz>>|Lf-4pk^)h|2l>*i2Oe;-(37ezyDX4Zyv?| zUtPXsYv2FVRWKixn4RQ3OqalbCP{W{xUbgk;X|EJ^a>(q4lf1F=z z{YJk3r{jrDTCo4u9WTy@`hPkO_WOVR^P%~F++LH`ZGHbwm&f-__5YNSr>y>;9#5+_ z&3yk)xmk;=eE&~5reR&*{|m9-|LgAeHVv%**Kwe*dpKzwiUq|I^o3 z?Iw+U|4+GI^QPV{-3Qp~2|jJB%>Kp|E0^*8KV80L#mjyFPq|d3GGU)L@CSpRKeek> z31j$%!ExN*>i<=7{vYxK)&HyP{J*MItNQ+*a%z)O-hJ;DiyuTV6r<{F$br`Gv zr}N94D1WaQvdY%a7$4{Re>&bl@)p(qQ;waO?5(=&b6dXK#CY$;^Pd`bpOoPHf4V&S zdy)Ug`GM8{({cEP>i;RHO-RAt4@1j~pZHDcN5=3w_cs2}c(~*Xs{g0gAME%4>h+fU z!SDYyR{u|zM_!-b|Ley4N`9c<|LeHF_<(-@ud(0%>o`mNx3ddhxBCrT`u5k1N6P&a zHSAU65puozq`YE`?W_N%^BEvMp!$CyR{u{qOZ-6f|NQxjpQip_h}Hj7M!&E6fBv}m zZ|eUkCrkdH`hUu4;*+WWr<^T$f$IN-Sp7fcVK;a8{Xb>&TdV))FE75U`hOu7SIv$e z{+;@NIu5^YQ`}q|haaf^pN_-dQ~ysH{;c|cq3x^xr;P2Z{}*EQ|CHf7s{a>a_5YOn z+}hLk|3a+(pK{V|J$(O9xwH6y$p7Q}5Ap#0{$F>$fc^eo$C>8;>H2-|=;`}^$~m|9 zV*jsO9_;u3I);C!{+}-2T>97lK0n#^-)3A__WwHnZ~l(AeE+Yso2@{HDv!#DE#e;va|Qva{C^Z$_l<@f&@tN*9t$p7;Df897({lC)A|2uGj{$GgI z|5HX@hTs3|);})&uj>El_KUuw{}*Dv|JN;#{5bXhbR6vW|Ju0ve>#qQI`#iT+f)B9 z#FD=vews4+cjfu4@p1G2^!)9X{5`+_*PXvT;sg5qzmCt!@_zrX<1^ypssE?zAC~R= z{l9MfpyW^a{lAWn$?^OBzmAWKpQrwxt`9%5-0<2qzhmOtZR%FjxKPHWA1{p6|I_0` z9-sPuAy)rS`GD+S{l5^a|ECO}PyN3TtN#~b_5b|!#rISHPkATi=lnlq_<-vFDQ}Z; z_5YOf<@nV9Q{F52Z0i5%{j^j35cU6*_sR1_&r5GvUTEz6r8>LU^7RBCPyIi=KJZPD|Htti(r2gspN_*1K>i=c z!7bleVcXv&&vzH!y*!L74_IofKEeCO1@gT9*I(Z<-X{LQ#2v4N@rf5-HeN5UZ}Dqv z{~P6by!bc9c>P~Fb72_I&YEWoANa3EbHZ5MjQH;dm9*K@M*`i*NO?`n+k$kD^t|LfNGri^6&uj4)|-uC@JJ-<^99`XG@<=Nu@ z{m~}T=DS|rZ^ZXCUM)U=`hPnAwUWm(^R26F|LY{rNBXsmw}?M9TZ#u^Vrc zK2q_+*6@6MCi#5gj~QcR~3uTI_n){_>F%5 zuUj50{*{e?E_pR_K5c)?#kY}uWaH0|7UOu0pIG)e=5O5j`Df5)n#cKj^80qUJLIc# zlCiw;s-4T_-!q>3f5s^cukm)tvyx>~xIBCm_5XBz z_z#kAXXD7PQvXlKk%uMoOX2*A<$e~Q)%cWbPx9f6;eScrtMLJuj~uV@e))X#`+wc} zg>Rw$pWYvZXWaF*mSfxZ;bmdX5p8{yQOb>?YaxbDTw zKaJ7%ss5iH-vP zqi<@7zoVb`UVN-~TZy{H;|BL+|F2tq?}lYw$uQly7A5OdFuE7I)>ln_y0P^`i;R@^H}{qWh}4$ zpEADxEu5Yp{!uB-&y&yp;g2L5Zm z`+s$LVfFv~{R^xA7h?7QluyaH`hUtNWc%v>DHqE4gne1!LzQyA-#+pE)c;d1mha2z z|0$oAJaP5^l#3)ER{cL^9B-M&hKqkz()nupU+`hUuM{bj43G)6w)%ApJFc;N%SbnQZ8 z_U=c)<7nbonjvdy7YwzG&m{|E8>X$#|RO!46pevhmiPd)WW$UJo0$ zY5pHyA8WU4@%=x&UUL>K@Xnli&DOtj(zV{!^RF8xv~1w}fBN^&#MElu?=6<6@$V%W zq5fa@_tAvDZM;gaE*GDtlKOrbEq(t_IU&RPf898E{P&;R@-e-edF#il5Z|Yw^Z7dV zY2lr^d!_N!{hE3IerlC*hV%ui|EJ5ROP-kef6C|wR{u}A=cqW}|5HX^u=;<>S=V&* z{XgYF*C+b^pU>k`eg986XG~|W;*8BUpTXw;>G6Wq|5F}*U6SwrDZ>X;|4$jdnfiaq z_p|3a+(pECS2zyH^rU-aMl{lAX;kL<|)U&rwM{Qh5M@w1Ts$Lj}QPO{VN z_%bCQaR2uQjC+~?r{|+*mgfKQ`t=yl+V}r-9QlsO|Km8=@Bekz`|7OLzW-Oz`F~*b z|CH0kA5{NOxr_LN>i;RX$%*p)KjjWXr2o|Uf66^%{_6iJXGlNt@I9x~ZeCg;Z(Q>H z^vn?n-pVh}821rBPW?Y!9(jpvzdR>?oig$oAOHJHW1Q~`HNFbtjCNle<9W^7JuifD z>1!?;=Scpa`hU9pZ1F+W|5JAUp7Z}gtp1;JuK0cG|Ajd9#~*C_BSv@j7MJ_Uc=)I! z?~lem8{_^P+W8k_+<%|v{AxV%nq;rW)&JA$55H3V zKjkdRYm8m+mo1O}VDg%apTGO!SdHvh93gbR)T7ja-@iNQBl7CcdKLc^ZEV1j^We!{lB)n-~a14O4j%L ze;vaI^!tAuCrDqa`hU88_)LEPuNz0+m*4;E7|8*Sl|88~+U(N6Tb&Nba_5XAn?Dzk=arl6K|F13Y_y6kl+P3%9|I_u;qC5Eh zUub{o|0!cW$p4eRTem)ZIpqJ5k)NafpN@z8KV|q=>i;Q^jEVRCKRsW=+QqW}*KI%K z|LO9`>rwyD=XT;ZJO57^^H=|Gn)Ck#wuxr{ud(0%>lpWs-~X%oljr+>|F7f!N7{Qp zXH{nH`v*}$klv*CUP2EcA)%K*AcT%x5s_vA#a=+MBVuo3nXx-MI(F$TKp>%a6nh{0 zs53hA-}m0nz29@*S?hEC*59>eeO%vu&U2nq-jbXv_eLI1=>MzSqf0yX|5Z-;f42Ys z@xi(!eZHZ6a}xLal&tIokMEiE}Ne%k+Vb}~P(U*F_> zgZn1yLvxbz=VvE*cvjl@%ryV8PjddreUj^&*gNU_rT0rt=X5_W-S^=mFyF6rN;`+t8_PamJ||NRlC`+o4n;`ammF!+D+|BR6T z2S)#2GV=Z4|B+FL|3^lC9Q;2r{5|-8afbgFXZU|{hW{65 zKji;`alOFs|H#KzEFZ!DBO@;o{vY{x=~s;WKQi_Y{|}7gsn@8s`hR5P$07eO&hY=h zI3Di=#rt48bVT;*Kzglf^{O|EpV zRjIoAf0z&BTU4&1{vWxeZ2xed%Y1x`8nvUb11@!LS+hryxz8UBlZ6{ANs+<|0Cn|1^>`}?NfDbDcao*a6zbK7Rkqm#!>b#C3VT~vMY z6z5JIGSvU${QczfAO0UXQ@)R^UOCCRt@Lw7{vYZ%-WIJItN%xC-l(qnf8^H98fgDt za>u3(H2;s>Hu!(!R!!?iqk0ti{OBKiY}Q!klUg;5-pMU=ZqTN&`hUK?_=xcT$nbxW z{|CnF`L&96tJbZbsMl=JSp7fDhy1@b;;X{{ z1Ec?MOL;#yW#dt0^z-eQ)mZ&M)WHQO=c)fk9wdKn2>*|aeg*LV$jIk||3@woAM1?8 z2b9sz7e3ygnfsmL>$MrZ&l&k{$p6Fk7+)}Jfck&rk>}+_rN8d-I{4)yJDrhd*J6w@ z)?Xz3X@_>-p>;hT@%iBYaeeUna^{r!_T%T~L`}zTOECOD-@o`@@c+p0zlwj`?2Np= z=ZJnX^8d(VBo7Vwe`NTH@c+Q*Z-Kl#_i@+V`G4fB8J7P??t5O2`hR5l ze{n|s9~nL${J%KE|0DOGnW_FCIZu2<_TUBafV&rT(9@_<->Lz_=ff4+#H{ z%>KV|hW|&V|3{|(N1iY@PyN3*!~b(Wzn}VlWaL4@|07Qg{vUZt@c+moF0}kVa{fh@ z|3^k0{vUbdygc>)oP+;I&KI8z{vVnCAGtt$KKOs+5f_b6|BswMFJJvX@+lWeo}J|X zkx#y0XaxU{3_lS0f8=o&4^{t%#vd51KbHg8xSzE_sW{|09o(e!cMj z$o+!i>~@&Mi{^ z4~+i5_murz{XcSX*$(yp$or(<8vH+Ui9Ek~Yjcq@`u)P^f&Yg(7(NmFzc|DHBh&wj zGy4CMcYXf7_WzAD`v1mR@|eCP)Z|Bt*w z>hS-_JH;o1|3`+u2LF$YJVE$>-2|3^l?o;<&GM!#NpzMEk9e;AMJ@!t3URR53s zuJliX|3}95@c+oj%Y*+HXZU|{hX3a*d3*5xz}l}_@&n=jkvGZu;s3=M{vR26jqv}- z#p3(H|0AOxCj37#{7LwKyiT5Pj(PB~*VoGP zOZb1N<9u%T;0yKt$eSd;5B?u{i#!h&zr%T(JTDgi!x?#Z;)f)-f4SApSnuC=zvEmY z&-dZ~aeh4ShyO?3D&yh*k>T$yZ1KD^{5tr5tb^hIk>TUP|0A!Hyes&BVBD{GJ`Mkm zTq^zm{J%KE|05%x2>u@#`9$#l!0^A|W5WLb(<|Bu}CitE(>1LJsVzq&^KKk~>ge^LLBjDE%N|H#Giyj@%B2UDalTf*`;q#8 z7!Ut%t@O`?{}*TYf8-}fd5B^9|8Z5jL$Fle_$LhKELFCR>u8+{7dn}ocGH82>*}c!SMgc z=r1nUC&BRlSVvwG^8d(N--Um9d_OR*AN&83i}xOdKdN=C5B{I{rOxNy@poJg=QGcE zRsBECpWSzf`hVo%Sx>0{M=r>HTKzwAk@$bVRxk4TW=;Q_`hTcnefM6zNc}(ZO|vgn z|Bt-lvXj;SBfok<5njJO-&^AU$?MyB&rQ>C{+(ZY>S6W&usx3Vi$goq|09=(FM<3& z@{SKaQvVN(>$OGlo{;}X-WL2n@=oa&4F50A@c+oga{b`{k&%ZA|Bnpc6aHVE<^5L~ z@Bi@s9^;W$2mg;;yneO%f8=Yfyj1-^^4Pg^)&C>Uyzxf$ z|Hwu1qZa%>^7S8^|3`lNy-(EtBd?Hto$&w2>&5Sb{}*TYf8<@_OTzyH<9u&_|3mfv z$Xn(7!~csj{68{$K=^-ghW|%iC%z2)Kk}*r=Kqmbir)wSFV67)z&M}l#21ABM@C*C z{6F%m+xJL6&RWX&{GW31<^~>iA{6F$~dB1w$=?*>~-yh~J@8n$i z`M2u-aete|SA+i-=kjB^E2BSdnfPlZXZCd7DgGY(Ka58md8hFI$os{YZvJ3jXZUcR zzmVe$|L+48_vdD-M?0h6aihM4%IHrD{&+-@GxGcXI%T{w{+{UK^Cmj){^I*6_p-^(JH?-c z|A+H|`HJQ5IpF`1OJqLye`L%L|BsA3!1kNYaz=mJ@Age|hQIjsr_-I`7pwm#6X1M+ z)&C0&-%tI&7(cdKeh3bX&$mxMmOl!Nao3;cIq#6yH~c@;alPUDt*U>i*OBih&%YC_ z{$H36zTc#KuF^Wr2mL?Hr!3!h=8OLqXZU~QgR+14f8+y__lNvHGV%bC{}*TE|B=fi z4^Z>}}E7u@ZtN#Z^KUw&I@c+oY^BbxE zM;P6ABlnxwS^YoqAo1Pc|B;6XBma*~|BpQCw65y^k&CAFR{xKTd_Uy>#Tot| z8U9v>rRx(s;@J((H1;j|@Kz`F~{Q|B**c?H1j;Vu#NMhX02;u1BHtdxif;9xZu$$p0gcDC(g3e{n|s zADQ`oI??e6{82Nu-_fn)*Ckg+LTp)g6z284@Mt|W;YJcRMFFxCzjvvRkXVhcRC(g(VTsHMn zXPkfde_RiI&BB|Fv48MOkA30e!ByV;(iwiozc&?pl8yT$?lT$|FYU7{lIk2Y}GbG{vY-a z-=mM@(cJNSio3RH9@YPTme(^ow~L&-?^MjuzE}S#=_sk>G*}c(Z3h|9~tX||3^lDUgZCgk;Fqeo+A7|Fs>ht2mT+qo!lSr|HvIX zw^9F(jDE++|0AdSf5=0OzaG;2_m0m@`f_7?CiDB!^XSsKut(CD8=r|^#iU+;|Kt0m z`G7;RliR2Je(CE?A77M}^#8{6PWpX+lqZ;;_g5sZxA^+g{l4`4zV!2vo{yM5U;6&i zeZv3YJ{igN^iE#Sbl-1qW^#PG-}nE@<(;2>8$p6cRPX>nn zC;4&8@cTmkpL59nQ-<#s^8cJe{+}}ZJotZ{4;=FUv<_b@OvH|I<1c z{@-u6%+HSde`KtG>KV6ty|UyVTK``=o=S2$;QxuEl?~q~I;LE7%Xhc>_~^J}qrnSO zjP=3)<9gtm?H-Zhs#U8p|4-+uR*n6CZT^#L)MWmj*1^{Q*Xk7|KhXOB8XqJ1bJqXY z7ept5pT$0}h|Bqa; zdM)+;$nb%B9h0iV2MYOrx;;4L|0%bsTZ8$3%J943|4ANOw)&RR-xmHK*NgtP@c+p0 z>EQp7kzW_`|MYxxYSN7Pf65&jH&y?Sl=jtxA{QTB$-irBuy8kBfeJ*+dq(gzTtlF z*t9wG|8zWjMfiVwec^h;|0CCG(^CDvIEVZ{-M&`4Cd~g+uF;lKV@R~;pGTZ~&KMZIdGN4vk8=k^53M}p41e$HCk`eU{vYR?68t~%q~QON z>Hm@8_l5jFT@U@gcpd&9dD5(Y(cNoyB>0jiw>!i4n{snmg5m#h`w8M_!T%$}&kFf} zx_{*Th5SEd_+s$?I35iDFV0)57b8zE8^51I9^H#SZE!|E-K7WDI}Z_mZ{DhP&O^`3 zW&WRTKlt1n`TgnYmGbvt+4%j;Ao1}gu3qIlK)BCSE1d_*_y)JFNU{7X8U7#FGeG{H zH01y3{Qafha>)Nv&YPAM`v2PfF!Y=(=KtyO51ZbX`G3mTf5`t+#{NV8pVepeVg8@9 z_5Zc`;Wvi-Kdldye7=zX=N$6?lrcW!|0(1AhWtNe_U+`Zl-|t)? z{@RV--0M6>`df$mKi$4?-Z19>DW5TK1oQutPYwPb-(QgTXZ?Te{RVk}A^%UupDY~m z|CEuB8S?*>alS(SpECT|kpHI)-!J6X0`G3mr2Sfg!a^d_T>i=AZaA|7GL(?L9lq z|C491%J1wn|Bqbqf%$*V^85+@pEz6DcwSj1&(}i!pECL}hWtP0lYShzQu0)?@jMm& z-`Mv?Bsk>%X+4(zr;O)uA^*=|CINM&ld9kjAi?le{bg7@0WbQ!w)xcMnBzq7dLW7f8H?{G;oGL81nygz56A9 zFy#L!ul@d4=Knc|{6FO_;tPiSKjp1I{44bTwfmt&_8;>9tS;k2{-5%0*?-9YbCz@A z>w8bmcgX+K`XRaAA^%Sqc`hOUPZ|DY$p2HO|HtzShX2RwPya8@Lo+{HA^A7icpeIW z@r@cEIm0&$`G0!i=|ZVhV6Dn|J$b;Z+AxjJ@|iIAD)-P z|0AQ{9Q;2r#>4+3!=Hoy7w3@wr^gR}Ddhjz`H=ZS{+}{@KKOs!p8g-XOpY()|LJ&e z$p3Q=`G0yp;{Ff$f67>2$p2GDf7Fowr(7b(6Y~F@;s1#fmJQzreq+f0Q^xUx{6FPl z@x4O+pE7*JkpHK={=@f}|EIj{<-aojPx;ZgXEOg!c~Q|2=Ktw>I^BE=^Z%4*Z{EWE zKjkZqe9Zhm<;CI$!2jd>An3>vM1WoBDsOpE>y@=Ktw@y*e#Y|Bv;79sk7qKdley z^eC>c&o?Ij9`*k?{=8`~G5=4`-%XcY&-_2-D`qcX{-5&7OQ$mbPx*}t$Ep9v`Buyt zq5dEFz>Vj~@h|rMzxMP)%>UE%eX@Tm^Z%4L96B8O|JwN~d0+er?f+}vUyu(4|Bu%T zd9ESC!2ctcir)hN zkG$=}PniFw@27Y@hWtN!f8M>5`G3myKJl3Pf874^%g$x~pVp^N8HUfFe*8SjzhxOd zpPX+jF2m=S^M!l0zrFKSAAAG<-T6)Nf5eY>enWg!`TTU=Ci$Y`*Zc95$orFg{yJ}w zd^`Dkc82dJpWnG$f3fuYmCtwQjpFM_%^7)s^8LUWKC*m&a9(xzLwvt*UVTJ-Ld*Zt z^RY(!!n+@+mdo?;+@@{O$uHJ$K3#kj_UER`&w6?&-_2-SFXHF z{XdTX@6Iyj|7m^WzC+CaQ!bP91^bjvg?zDW_*C%GDjw6v`JlXC!vEuV zd|!e8N5=OP_zu!Z1`vJ z1L6P08UCNM96$WOIK%%V<9xvXBggXpbp8$UeQ5D7C+7}aRzCZ(&ll(6=bi1xpXN;e zkK2Rc|B(;L&rk6G$jFz4|3^M59P`7u ze_dKp{J+4+Fa6Is3w;0RSHJP%%ba(A@^!TIhAUDm>w*8r^}-(v`G0zTkoPy=^8cJe z{-5&hRQ{hb{6YACoDcoet^coGPq6j>HQp}or`G@1?pOE!c>G7@??JTxuhq-McMkb~ zdcI1<2Mqat%3BY6{+}}P`$GPojhF93A^*?o-wwaS*Nc2V_afvGL;qj<{c4~5cFh0N-;ZXF@ccjJ z?BUHr|6lw4Y1YuD%>UDR=OIm*|CbH_rrU^?%>Pp!FrqQ@|C9?Rv}gXGa^H!anE$8T zZ%PL9|Ew=%J28e61?Cq+nwP9!vEuZ@ZUoIpB_(v_*xLwD>^>_Io|m|JSYuIOPB7^??s~&6GpP=gWpKhy1@I7aVp* z|KXgQjyMmNJh+D*eb;$_^oNE2$L+x(|4-*bo?*!UQyw9{8T>zvA0+*d;s22bPwA@u zA9>i6?&|-M;S0k5Bjfyicj0HwqfhRo{vYeeXN3Pp9wT{`@c+o;i!=N`GOi!| zzc}Ag=i3B-*6BNE_=v*>fA3r%`GHTJ{6m6|oA;yhaJiqR-SSg{*FOGFXZU{2-}*Vh z*KPmBdCIAo>i_ZehW^3u|H$wYAF2DBj|czW`FCgdkS7oMkMnqW{k(O`f1L|u|5f@% zc|88n;u9|4kmBK|_KjwbE$8+8({rMRM^ZebC@X4q^cds?>iyO|FX{Ic^-TIOllvy~ zz=ovdpAE~#pW3ASr3w88sQ*X50}TI<+&?=<{l7Se{J(7Ye&e&Vng6F;D85z5|5JuP z6!QO+(Z4g~|0(zB)s6Xo%2~a;GyhMS{+~F1+3?4Z{|En%jQ+sz|H$x{;Q!5zCEr_oO`Bm zuddw^b=Ij zIK7^p4>+cGa{cL??kA2-^B@0TeZO>{?~k~G_*L=attfeQ2}Xn4*!$@T;MvESbX@e~u4T^f=L#n$`T4_ldL2IB zac8C&{awxfv-#1_*ZTja*!;gA)&E2O9rFLAKfLlWa(L$d1r}e@{6E_s=hOT@TW?hU znBf1}_~R;_5d1%5^v5;-&$h2tgZ^J&@#&EN$KywTO6&h?^EazT|IfJbiPeJtXN>-} z=KmQZFVFlxMD$$iWDTa@@Z}noYBag8AkQ6r(U&;JG zo3BOvrqRr$($Dt`JHCbu8%7t`NipU#|Ifx(saYxbf5s{Q&$yc0f6uwNnLCpC^^uS&N3j|1(D3ocVvo9otAA-@5bse(KfU^8a}Ld$gth zXY1+Kx^3|P!urHlGygBJ{QU;<|G0g(wk?AHXZ1d9>HisLwxR!*+WyR%XZm{Z_aOBe zo{?hN-?o;gJHszD|Id!6L!)}Z|1)k|pZ=e5!@AXj|7ToN`rDfS7wYIwE%|?ZJvOdV zHTZv4uOoh-`G3ZEeVPAf>u=MpdGP;?ng93uaJ&B-v}zvwKjWt2znTAM<6AbT|7YC1 zX{)Hh7i0Z=!r$!oU7<7Xulc`>amM`juP*TQWB$>bM>*s5QLk!&k8jwvNmNj0lyisH zO%tCdxL@L*FU@LJNiclMc>ToM^%7jUR^6zqbe~(l(PWgXf zy!dd)|6?6Km-&BI&!3s4`G2ez%*oOGKQi+5%>T3TVDtaN{NiJo|CeI(|BT@Wn*W#L zfmfA?FL%58aHHpBMXk@;l3?@yY&`M?&HqcW`G2Rd!yao zy$;{+fhw;!50mj%e*ZV;5yIyG+4dtPuhINJV_a|Z|BR8ZX#QUqFTR-he|Enk&+nek zpG)0u!V9)No8YN0Ka*m)Kl(6exXwBMl0i}Kiff&RT|6inFz_1Z;o|#MsC1R{Xvr5e z|IhXZHvi8U`GCm(KcHau@wS zmFJHs7N1X^Pde`r-%p-jIwMcc{6CuyZ2q4y`iGhSXN#I0#`AXJ*L1pLC zZ-0&YpL~Kd)_d8|3eNkaAF@2lc0M5ekH2hG-Wk57`G2ofn)c!%@{Hvi8Uex3P$ z#+&8&zxjX0>*e|K3r|1i>)#;bn_T^rGyJJL$3Kza@*V%=3}0}}1rPf92AlsE-Y?|! zZ~kA3&Hpn-o|^f8#-;LlllKOxBIRf9PsUOe!qhG?W_4*3&U&L2&UT*%2^Ct0IfK{Xg6P+QUbK z|7W~Go==hZ;|KI=KmR&$oA6TcDXoLdVV(_d>8&zigzCh{-4#Ke|-h~ zFt3lg|CZqYS-o6A9{e@0M?LCcJ>vIS{j~e9#Qe^8KmRPoJFh= zjOG9Fe0=TxpN&WUpS-{L@gQH#{69Ni$OAP0&v@^rp9lZX82zNp|FieQl>cXpyiW7~ zSpNd=pZ)lH+$sKx`F~d5A-<>ie_?ycqcZ=`xI}zF^Z$&IM~M7C&Q~h;_pMus`|Oe+eyI6>c06G7|HART|5@<=jJJx9WBy+lFYkBe{}~s{ z{>=X~E|GjK^Z$%Di|;JoA98tqHp}~=e7|tsBJY>-{lmFz@8RJ8*?QkxwITR_#?zj9 zDENQIHOG$#{-1F)I5YTv#-ks;Blv&D_doYs@c)d94;%>opYi5>hlBrTyi`(S@ z{-5z)Ve|it;p>_IXZzbF-)A)cFRTx2{$E(1j5q%;#peGlQlAL@+|B<>vH5?-2j%Av z^Z!C!{5|vkj8p!famxQQ#@{2D|F=l}KYX7t|IZlteD&*`AwHKed_D93Z2SFk{mlO} z#^1M?|7Q#zaN*B0#HTVoBInEeKRaHWKkNUSV)OruOXd6Mlf5tW?aSo*>YSnToDazQ zdQH688F_@}|JnY~uh{%QV|*Vq|IZlPoBwBw?aluSF?{J0>ZT_EKe|-O%H{;IS^J^~3K6m=!yv>r|eE-~K&RY&1jm-bE z@jJyIM*bhKKiK>~JN|744+sCxcnbEN;T z`G2>i`G3YK|IZlyk@OekJUdJC z|9Je9&ddq^pVgYIL*}#L& z@bk?7vpU%PKjW1Dmtyn(jEA`YXFPO5*Wmvd_n*)y_ z^ruDsU!2YVv+?i)&Hpn-|6%0+aXi@kKdZwZH2=?d%#@zN|1%yd{ff>13+(=1ip~Es z#`QD*&lrB8`G2YL=KmQZPtg27;|by`n*Wz#^Z$(DCz}6fJYKdp|IZltfA4+zs~_)V z@d@+(`!DB|{}<+S|Ihdo@n_BdOR@QXsrk+SGsb$&|1-w=%>OgS`po|`9$AzbZJBY5 z_<_cmY5jlG{h*2BEI%&|L=-3Bmsp8Y5rK`u`fEUnuhb zetZ5q^~F;DpD}zV^Z$(D3z`4-t@>%mCo})g82Nh0|C=@2ctode!T&QJmC-Z!e>Pus zMz`SqrP%yG;}KoDg#N$A@Z-$?Ge(}C`F|-!{vY>`y7_;$f3W#~#_;*f|4Xs?f2sYK zb-UK*!+MT?F2(2%ZT_E)M}KJZ|BUk`PuKiEn}1}-*1`WXhF@p?pE3IJn*V1EU+lUc z;0GGx_^to1G5kC8|7?Hg2W%BTB`(bBhB=a@L$$H}B$EW#+nVr-2pO#06^A+Dd-S->RGwIW%`+@0xAFgkF zzI0zNy^j9Q@$txej5DrRoYVK0p7)oYS9nUFq;Gt3W-?z9?+@|$)AJb9eZcfQ!J@9o z?bG@HxBmxyFXr#5?ib_qJiz0mpKW}6#Xs=>Y8_WW{l5>+?~{Z4zZ&H&|Bnpc@57;Y zuUfnyD+hUb;JlK%QXKq0uM5NfBh&wjGyFetJ@NhE|B>s84+#H{`#-j_`G4f{;^)Et z>o+4a2l;=|iRIP*b3P%`{=Xa#-w*yD8NM9+Kkg6tddUCd_SK|6F7p4#$5%N~{XcGh zLiK8z|3^mt-Mgi?`26T^`T4jMcc@-l^Z&TNmM2tE|Bqa?LdB@lmA9;FabMpYi9v!-> z|HtF2*{Ff~f8=sDg8D|Hv)+^i=o`$;+R|Kbe)kMrep&rts_ z&hY=pm=F1XaYp_h8J~af|Kbe)j|`vw<*hTEM~QEU{6DTIt6fL+|Kbe)&sp+z;s25G z{*U}WGQMvh|Bu|eZEMZ{Bg6ND|Ht*v|08F#Zl?ZUoZw$l7Ra&_@V;s23OYSB#nzc|DHBh&xm`rwzs|0AOg|BvGvNnRlQ zKQi*OV)4sPzkjRqFv*vL|Htv8&*`cDA9>W--J=S_HhaB5et+_L$4v=_|L5b+>ZSf4 zdGxeQ_5aAo*Mt8TXZU{?+`CKtzfrP1{J%IO|1Zw)|H%1g^w9i2a<2S72mT*9=gds? z|H$oSe)xan&eO9Z_}uxW4fJ z$hf}n|H$a?eEPnZoX5%ag#X9+khcf_k33cUQ22l3QFF7RSB`tZdE}fv>i@BxKc}zy zf8>$k`@#QR_+|BEyHKQjHlIFEYcZm%Q1Fyo=S5?u3| zWzORy|M91@?sP7ae$M-bE_Ftp-`gGTaK`Id++JtoHD3GuZ3#YW@2$>5=L}N+kMCz- z_50t#m?IRXD55A~>^!Ls;I3rIG{vVGY{KPd2{d&Wv zykXjP&d5`Q|Htveqz?a&jQ+sz|Hy^G|KobW@c+p9k~awdkBt7r$p0fF4-ozz=Nop( z2=)KS$R~vV$MJ0@wN(F)JVo+%8m>NhWxFpnssFcf`-|%Tkyl9m%pFT7dA;nDk0ftq z{7P|@)c2$RN8Tm$$;P=7*BX5%DTk!v!<@wybjYq63tyHZ39{PutRvMOK z886QV6Ab^4+i(5y2lfBBJ$x|uf8_07|ET^Sd583;h5r|4_@-X`6Qpk>&VxW{1)f!lHUjakK@7c|Hym9zkBJuR?fR*eenNS zN50^eykN8a_ruj>DiQHTFWMjieik01Gl%Rl*j1?$K+ z?6TrlXZU`P-Sv|*=0pCUkC*ee`;@O%@P61M{vrH7a*13&_MzA^(qzd>iw_QFyWTSAo$~sA?u*-<(XX}f%A1|xFT(%h`w#a2(VFX=H_P+pms?%ojQk_`f8t!Z zA1MBj^O4Wwd9wI_tnYsBsQQ28J*(b8Ua9Z@g?pFC`5*3l%C)oQeD`;5liwTt!JVTE zE>{1K*Q4u8ud4q?p0{=zd|V&Dc+XMw|5(3A@&Mugk?;TTEBG(Y=wAo_kM)v6@1sAb z^G3;!LH-}l*9Pf_DaW>)$G2Mg%fbI6zb$z&@c+mUZQri`ANktXUW0$-^*`Nxr}}@a zj~zA`ewf#zFM`JLfc!2e@?pWKh||H!yM z;s24%FWl^mJS6yktb^hI@p^5Reyi~R$i?C-$ol(n{1)*?;s3F|Ztwf*|B+wVr2VD6 zKI_J3)&FDt>`~9F|3@Cs;b!&!$oX9#h2QGiPsua?kNclB?jiO6$XA`C`I)}Hg_oKC z=k@uQtN%ydam8uTgBvdL`Pa=U#Ov32&D`O5eLKH*+jPAComW43ujc=8z905)mh-X1 z>zfWAQU8y}vn}NRk++Kv0{@Q;e@XI7`|X;lhaU+4k9GJ?@c+o@ zM-KmwT=tLe@c!G6?~l90|C9G;XZT<6|2Q7~%71@so!8ONT()&SB=1-7|2W^yz5CSv zBX3#1HoD@9UH$lZ^vHepM3o-j=REQDCD8*L4>`~I%ai#0a-OhuD?Zk^43cA|H#iRyI1``^0{NissBfgCJc_o z^{SQ2^B0XD6g3!L$9d_*Nzn&W>p6e-#+&N@ar;%`Q=LKBZ-Oaa_5b$E_Y3%cac=PP*xYF+ zZ%|+FkR0#XtHwDa-w^&E$HVtS{vR2~)9;HZJ{}DJkMr%3zej@qN8Ts>nBo7C+5eaG z(f=bKkp02`Bkz;%SMdMHd*%HrzrrkM_=L6V&2ffrc(~2^&iH(T|HtjY@c+p0_2B=J z;j8Doa*40EMDqD=SbeGU){no8N=q+y-YfIfJ94G-9;u)4<<%*cd_MSpoPW36|M36F z=!XvfFV67)oMk=m|H#Nsh5r|4&HoG6e=Ga{2HqjxpYE%FvyTT~-uxD4e7`!q{jCWe z)a|wuOI|1ZKkg6to$&w2yTvz$|HtdQ>*xpS|B=g(S1S2`afbi*)I;ml|3h9N{68}O z9s~X#$L~0BIC`n_J48%l{)I4-ol(W5t zU$1BOiBYAke{;?s+d}<6{=PD2bZ7Pd$bCn3RR51WSo-_I|Kogvq`xoxKXTT{R+|4u z?mJ5S2JAn~~xNdI5fJ5KDP`G0Xn|6g*h_+;?^$mkCY|L^0WJJtWo zIlZUm|B?Hh(M$9H$nfD#Ik3jZgWvvctuuVUlPaxG@PZZ_oD0Oa+tYWWGx7j?jw^PC z9|-@C>q8y+f8;6Be--(EaendD65k&FVU=xLo$3E^Jp3x;|HT>p9~tY1{}*TZw=<3x z{vYe$Cl>7X{pCx(BK$v|FXSo0|0Ba^ga1c{?{-$L{kiRL+@Zc-54j%j|Hv7Vw+H`^ zoIkFk`hRh5@${kGS;gD4i{4z4H)vdkXyJ;(3I1T$5ohE9BL9!ugOUG7&JiCG`G0YS z|3`*j2>*`^pRn=Nk9>ag7ryd>j}v@o@h8sxrGIkYM?Q7Vo76pe;P0O~!=L$r*>EWkLxcwxkq%@ z^zXcm{<}Y1`Mopp{EF`S!THovGS&a%_NRz{2>*{fR_+J*e`NTB@c+nTr9UwIzc|DH zBh&wjGxGn)GbNu8{vY|gQ>FjVy#M(6CQQwY&b#@)&P9`YMjwxf@_2uYmGfQuP?85t zFX#0v@&D$1m*Q6aT10=o@))m=$w>M~W94~v{CQux&y&uDl2-=*?}_2PbCBnU{H|)Z zpXZGHJ@|jD_looL3di=$L7pFcLdlkM#_{Ys<-!ER|KoVn;s245KL`Jh3?B{o ze{n|sAJ@}P>d5~icaZJj|B;cOhx|YCK=C1-*?w7SKItb{Yt7}(10){_{vY>;ydU^~ z*G=XBpLy}$0z%%s0ItWVN6o7N}UKlq%i|GS@W`uxMQlG_*L<|NiP zA}`4U()_uxJ(9lO=&s2;L!9sU@#1{PIXw?Cy?=7LKb)Som+s?D%1j=A`uRD%N782; z+bfyxSJb;(VtwiJqaSvB{poeQU&ZU`{d@n2(|x`_%Ku9rf4ul@@%_VZ`@gvIvEKhz z{XcN%|Er9Cx}pECaw`AtVq?$$TcCbmD*rFA^!v5^zZ8f5zq);$3f})$xvuyzq5rQk z`lDL@pY0FxhyK6n|E2Q(<|`xr@9vIE(63jwr~gNWj~M#@>UuGM=>MzRBkwQt|5ZkR z-_ZY8=R^Ko=>Mx+r)o9z|2Ti$YSq>MBg60c?<2QJo|YYdo#T#Y|6kode8kZIR~hRK z{eO*v|HtjCRIRN3ANizORYLxs&0nwPi6Q^bxMlT|LjIp|+uDsn{-1Gs$=?h8e|3K? zYSa$-e|G+ANq=C=|1-vVL;qhLABkTI|BuI8P4fNV|B>s|tFHbZ*W0-1N$UT_8U7!+ zQImS=|B=yex8YCMdL4Op@c&qczXkt~44)4EAGxvkQI`K_$BTTk(EnH0-%|YJdT(Ct z>uuM&XVhu!WzO*12X4L8Ia~U-!vEv((f=cNY1Nede|7$D%^I=)uX5L>4cY%!xo!Iv z?EkBr(M>+TKbbH2YL}`H+D+bH@BVt8b5D7Hviv`*BagM*jTiXw!uJdPe|0{*pN9Uw z%J2n4|6k>v-OT^v`2vUjzgkD$Z0P^14FBEo|LlDB?qL2Ow+ElQ=UiV8xbeHw6Kwf^ zwto2Ymj9RH(EnGDAO3pi|ErAg&!2FX&)2y_8}+HtH*=) zztI2J8U7!y|1s5SsQ*Wo5NK(z#uW|C5{4uciK<^hd}+|6cS{ z|Dn-Gk`HB!_vbp%htBm*JT~P2Sv|XJJNEz8?fd1oV*lS9^#2`yW;Xl(DkC2*^#4`v zIjt}I|0<6W|1I?Ybq@W1l?%@49`gUHDvy;syf&lvNj_EJ8F?Z9FU8`ncpdq0rN8cS zMm}8V|Eu#&oN4|a=R-f>w>~eE{J1JP=)XH`W}fR{xLZ z2j>g^Uz{!f&(1IU8C(9JF?>GD|1*Z~w`b6+zCH5%EdS5y@V$1-e%X(Ir1+VCFZ!D^ z#>4;P{*nJTVEK#Alg0O&dhB0){3PlBoBhS}&d7KCZ07Sme)Rb{QOTI+oZ;{Nwdb?W zqolsH{xiy&XdIV zTYd6l3AX${dp%%&%l}KU<^P4(i{$_1fAf%U5C5<8?gyO|#+-ks>bIAg5j=^dMceyMvt`zrcs z!Wd`dVYC`lkl<6hj!dvT-&-mDr*hD54CCebpEL5y-aKz`g5~+4Z@)wOskR%|-|OI` zy>gvPzx*E0C!OK<$@5ER_;m7o(|M=(g7W;+8QV*LG~ZvDA&XZXTRjj!T;m=LS7*JKk`oD(EnG@?=JDpB>%m z#(4ODaTb38{e1O)#r1;!N5*`i|F72J4~G7~%J4HS|IfBB`NsS|&cF3r^Z&@(r4Iiu z&Y}OW-Y@X|LjPaA{`CL&dPBcz%m1_2AMyg>|FI7L5dI(MhYz@H{_B1`CF1{;AM=Vc z^33M9f6;l3Z(F(!W#Rk4hx32>u^=n>-&5{eN@NFSty63HX0- zz`zGS`IP;Cm3JL|U;RJU_q}^W{Xg#i^%cw2|06&4@M826_v1O|%#rYeouk3>d}T)$ z=gya(7xMq?dQE)rIraZI-@=W1L;j!DUoG7k^8bvN?>z|r#pl~8{+ry-%XxlF_a9OJ zkMnKZeIUB^!~>EKXxnetwO{fJH!bJ+DU*I~mj7qxW5dSH>i_Zh|F-;As<`qotcU#)L` zkNJOLe#v9A{6Aa&hCSy0@pzuvX#O90`r_w8{-2GXJi`1x*0VZjex>B)S-pRE^Z&?& z17E`RmHa*1|Fp@Eu>Y^FZ~hGP|5(5Ck}E_0pN+rm!UgL8vA*SM^Zz*is(Ito|0A!y zNPJT9|Hy}zoT2_7dG+IWu>Y^_|L6T1)&FCC+upq)|IdzR|NA&U_xgNW<@GN4r2Y8% z*#6PS>i?08Kl+6IfA#&hM0`N;pZodiP4bP!k9LNiC;oJb#Sav}+Iff6;s0^_GO5G= zBO~9>^8f7hx>@Fj|Ht}P@e9QTbKWKSg_i$k@3-6Edq3p=86TAQ3;2Kh{CefZSJeL_ z7ui>}!t=OXepYxhx_5Zm3rKP*o|0A#2 zc}V>~^4eX8)&C=JkoCj=Bd_0cK>a^*+3x-L`v9+RmiJ4`|Fh%&`}$4l|8e~N&;B*! z|5<&~4YNZ2pK-k*9ohd^KYycU<<i=I5<9T7*1ZN!Y zPlqNY82%r}BM&e1|JC{T$j<|z|F804Ie(V_7xpj56Z-$^`rz+9-))-Dhx74c-gIZI z*Yf}D_`&f1nuqg&pSR%uk#~RkrTTwl`0{7oc!AG{ywd0HxyTv)et-D$eCOTr^Bnv? z9$%S!zQX?_Bi|JMA9=qp{J%KE|083*Jy%}qjQ+i$|F2z7>`(l^=Dfbbmj7qRi+=5) z|F4cmo^j~^tBn5cr6=6z+n0*({Ys6Soaz5@{_T?Y2mgF4=%skxpe=bXm`zf{d|_}KN$T||2}8Ob`{=XZ)X zM8EBQ+|TE8ufNLvzk2=dx#wE;|5eV(X{-L9^n=aWApLkdzM_eqM`qJ#ksfmf79x{>YO*SZOH$#@nFmUGwwO64g3G#0oWDAMmP|Bw4a zJ@o(8^92t5f0c2*EdS5WC;UM8f6}it2mO49oZ3C){}~UQYW^SV@cY&;J(&A&M&%s% zeuKw%jNt!~;RnM1BM&QV7s3A{4;2d^CTq0g5$ z!TdkY-(P$}_*`^{}BEk8U2Xi|B(kx?56%7dGrMH|HwsCGS&YhkCS{r z_Z2q$~kW0lDw{&4Wo4} zj&VkQ%w2y?F`h5SpBEzECC)jWll~C$?c(*^?ma{P-#qmJ;ZJ?r>AXDYAFF;Io_{~w zMEU~a(2TYyDVmwlkh5KlVe4@qB#L$8)^iOMXAl`k^_JA9sQJeHmR^MR(mg z*STAVChGsOp3|$n`hR5P|H1zw!}kmQf6W&Z{~+}LRmS=(|IhXZe=qd^)jE8@(EnGD z7yd!$|ErArq0s+Vd5Ap!4*h?XhjnVL{vX!^Uk&~rxljAH?EkC#>)N>m`~NEU>fV<9 zf0f}|hW@|K@c%d;^4=`}&yEMjZ~1>IhX2R$sKfswqrY(I|Eu%Ep9}qem64|x`u{4! z2ete^n;-dZmj7owwr9_f|Cic-=>Hqem-qiwM!&@D#f$xZ=q5f}=>MyA9KYrN+5Ly> z7r$R|f5jR1SDcX_8Rv8#FP+nUz=>)7v?paJ{Xpbl#^+D>|MIhw^}+#piSZ{7PV)GE zNxv@Lmm4j4Qt|!adj4OW?mwpY7f$#6{>TR`lzh+l{wAmSij$HUAx{lS7XzggPLCieF~T&`TAp6>HW99*LQNBMv0{vUj;`0=JQ{l7b3c|d(O z`hR5h|0UD^i*t{wm#vC(Zut~f6#sAdO?P@74F8Yg>xe&i+Onn2wJVla|BrR}c^%4@ ztU9vye)aK=mpc4Ea=D7fX#O8LI?nq4l5xIje{!3TuTb&0sBBh>qpByW|HtuQ_Z!Jvn{E8{Y_%2Is_VJY^zY6}}kR=bQ|5HJHmXlkg7=9-FKh`T(I8OaP zGV=70|3|J}w}$$EvikZR{xJ2NnY1u?H77I>eMQF{>AH@kq`EIj}$j- zTsK<%=Cxj@|Hu7xZrWV^KQjC)_GWa_i z5BU&um|Bp=nFV4vSBafZlOZ`7` z(Yd`f|BnnGY|za8K7O?1dBOi<9sOF-|2NK({kHPT@4KoWH+<%Rs7CfK=V9mdk9wW8 zW98qAx~ktcMSQ=y!?!z6Ixjowdr|4iFJH;f-_H!3nT!4e&Uxau{U>j$b3bAE`$p$% z@!{m}ADz)JSN=ZIx!;*tk@Qb+M!uf(S8(npJ|z4#y_8U7!6#Ef2={}*TYe`NT5@c+m|B){*8mTx)3?}Pux z>w)We?l-S{y-=?Ah&``4kCS?bcV2Zyo*(=_ZV!h4M~43e|Bw3z!~Y}04}||09}oYJ z44)7FAIF2?|B;dB2mg=b!SMgc$a91L7iai?afbgF=bH+i^!f9}&zsrfFA0YK$MNv@ z;Qz%L{$HHo|Hb*w{U1&7MY+)pt^ed)FfT8fQRxw9_<8XExIGyD9~r)1wYMHfF#JEh z-q8OS{vXGq|1bPMGWrR_|KoW2e`NGGM*bfed57@-$jI-5{}*TYf8=3ONB$pqi1?fE z|H$xvUzm5BuV;wlb1s>Dt8?G;a@7Ch_?%g}>i>}kNxmceKOWCux&H9~$n^i>4F8YZ zU-}!v|BLgM6BhdQ9x8c`fBoj#1jGO1c-$Y$PPy6{{f8&DxzZW_ApAeB7YzT8jOzpc zFV67)$fM?)|Hu7}oHtbcKQjDP_hS+K z9{oSz|B<%}!~Y}0Hd^*AK|G0kC;s3>1@^73=Wqqw`fpY7I-d{yi5G6W)YpUeAL)0ug0ENbwRfEB zeBi@RkJ8!!Bf8?o| z9q{_~?W3_p>i_Y0jyvmY_5aAD=3Ne7#mAp^!)@ySalX^;Sfc(PdD=a9qd(_z@|ia+ zQvZ+hO}hFr_5b+(efjL^>i;1F4?g7d$wlh_k-HZSR{xLOG_M={x8>yMoGI%6k!#<0 z1^h6t5BbaE>i@Amqj)|1JFh=eyd6H=JFG94yfFBG`X;*&Y!eue+X z@mt0BK>i;Y{l4MZf8=u(|5g1z^7MiiH2;r0JVW|jOaEW;*pUB6K6mJAxW2ysbEla9$Msx3`)}}P zy?)D83)TN){pt%ZQU8y;`bzWvIRD$1OjiGoy!PUJ_5a96mY$>jA9=%5ccVYJulLu3 zo7Defeb>PQ>i>}sePI3{d9&o_!T;myW7~%xssBeVk@pAm|0Qo19}oT?UtjR^;Qx`g z1pki=zXtwaoZ3;O?(OWw!# zv0eT6{`}-SE7kuaKXdbq>i?0iIYauJOa33ZVD?<~|Hy^sUx?2?uQ!wHiTpp-8_%7m z{vSEI>Js(;xSr_N>(&1wUvTTK>i>}!EL*1jA9>zg%hdlPUwZ$2`25f1{I}eE1HK

(u`vZ{2%H{Xg=m14p8hsyEE#=MVak!~Y|1djC`P|H#Nwt6$bE_ql(xQr~5x_*L(} z+roL1ykAMpd8_z<7yYM=Gy1vqt=irhpU3e3I6pp*;s2452M7O;48IKi9~u4}{68}M zGWdUF`2Vk8nd$ojUvpcQ^Je)xANFvz^A`EMul7Pe=iRcN{qN*C?~?sLRx-dD`#Ap58Um`AXAD4bJfY;s5dY!SMgc$QwldA9=g@x$ytUTjl!({J%KE|08da z*Dw4(@-}(>!v7=hl=} zKXU0I^Z&@m_dEW&d%V6y{vHJWANRjW-k%C@zt8I>lK*${UH3b~2ZaCUdhz@} zJ2xAir~V&*f18n2QT;!1-iVXb|0DOwZ=wDlIlG{>`hVn{0_*=vMxG!1zc{Zt>kVg& zhyTZVuL8^eBljunp#C3ufH3?&@{sXe)c+%+U+f19R^-;n&M==({2%21kq1g1+TmYU z=8k%(i}_)~*)>)>4;3Hk!FFpB{7c?iXZV4WCarUZ-}d_4_0FSC>mAiuyuleh-26v2 zIwS9I*Q><|?!I+Xg75rrvorDnzx~%1XKX*F=GFwm|KssZko-XSe{qKYM@D`i{68}C z1L6OX>Hm?(p3zhD|HwE#_Kh8H`Y&-S;$i2t5*ZePM!T%$V5TEcLd%nwkaZzXW--b=<6)pMld*{)zzs}`; zOz^h4KRJ(-{KDCt{+Zwt2mb6lKzzaHC;j3)NPNO2_5bDj$MuE($Mt~W|B)w29wPj| zIK%%V7ftD={vWw;QbttqoB#U$a6ZN_jPiJV`C~JpR#nP5XO0rzu35Rfk3Z~`^Zm}- z^Xhi28h!O#ikr2qALaBq#_Jusw@N%OOz%IM-mkP*n$MHYSv`BH|94g8`_#wk)1#;Q ze`NSX@c+p0jo|;0QHTFWM*mRwf8@+8>7OP3-?~Bfs$YiZ-F|0Co1Jp4a0_7DG$3_lG19~pUR@c-fr|BvfK9v=KZGV=A{|B>O(WgorNw}+2~ z{6EeIKM(#N8Gaq||H$nBOGbZM5=35AnOUrWkp6Hx63pb@Y?2@=l6R>(@8ByZa)qpCNg6 z4W3Ie{J5__yx#YZd^_a-@%-WX!2cun7k>=?9~s93|BsyBAGdF2(l^VN{*v+M<>~%k zIuDUNs`&Wye!RW=BrU$3EAN&k3Q-(>#Z zxXdJ{`;dQ>_m}STrTcyn;`?I#ek167F;3t9*yA7!uD*u_mI()wm?zv0) z-M*oI9r&S!NuK!lGOt%TzCu)^ZHnOo!vFi={5RDfM1B+eKXSE7$E*JrXZU~Qx|NPo z|Bp=nkBodj_Kj9?sf3gGm;GdkK0$OEd3|N|07qfTsidrwfU-4 zsiOWL>$N1m5B^`A;s250_rd=oSE^P){Xa7L^TPjIyx=YM|4tO24*nmxyfFMfa+MlY zLjPYIU!`WH=&VIIOTW#x)d#EBsCM-G@hPrWzh3D7YvXG*ZW#Li8h346KlJ}K?l1ln z{6C)G_T8obyZC?P3e_ux{=eaRil2!5Kh}?z+spd@+I+Ylt^co$uP^y_*8kVISts-V zxP8O6P1OG*x08OW@c+o|#pi?nM{d)!Sya+5#qFB6h@QXU8n1V1-6mRd$JGh8{=c?9 z_}kY1*SK>#_Wuoa`MiVw$Ngo<=Oz34+3V?EaYH|$>+{vYf3ehL3C&es1ooFB;-g#X7nzJFT( zU#r94xBkDz-Ne^~|Ht!ze#7wp$jE=R{=YUJ`FPg<*SLKv^Z$7LIyP;f{vY?>O!^7K z|05$G&-(w`{ZOe=rO^M^82#Om|Ht{j3!Wq2!DTT-K1$${=wnSZJRYue4gO-xoY1h($8^%`hJ?vDgGZB$A814A2}mmdd8v; zog3Dz9_63=fpepijtTvLC#WwtwjfjeKhB4rZ~ElFEB!0St8aJ4S=mvej3dt3)B8mK zsdd;nSNyu8zZ`TPcW$3(?U4fsesb-8=kYV-=liGkIZv9E6V1GBuk)1I{i9JA?s1+x zD=(7X4bqQxocev^XAX+SUAfb_aC)Blf2^aQu=E#L`Rd*x_5Hx`|Hy^sn*T>Gm}dST z8Tone|Kbe)kKF%^O!fcB1J3ND{vWyjnZ4Eji}Q$QH~97=WcvZ)x12j2w15M6JQB=%v4C6TebL~3!)BBwFTfg5o zYt34Ht-Wj4u3dHNl+<+^Fr&qt6j|-WT);{-65y zy|7pC|HM5nE(rO5V(R}^D!j?h4}RbN1~)qQozf%0|I_&n{;2tXF`w|_pPgAR{6CEk z%rY8E|4;3kmH(G%heQ5fhRFjA`F|PS zX!&L#|1ZPjtA+f(3{y`mp|I8r@ywm!p z^?y^|ZT?tV|2O6B#{2GT>ix+Fw0GIgTg|__du0RPAH3qNdd~QM_TOgFaBT5_ukO7|HSy2_uHP4XZqbAJ1@8PuP^+-86Ob;Punv;{68^%p4DG;CXX+z|C^rgb#}hf`oAetKN|l} z*9-Z0mjC3;`r!Ym9mf9?ug>^?+W)GI|0l)=B>zuLJ?^JooaM(;V(;^--uk>V=X?4e z|K_~I_J{wc?RlTv?fxg6`FyAKf79cko-zKP=EvuG{LA+`<4>jafBUC-Tef|V@wa+A ze(>yeGn^Nh?=bw1>At_kmR~f#)}MTS_>1^|I)CJ~;s1&8yYT-se;EI-oIeZxU(EKm zx9_w3F!KL&JWJ*;2>ze=$>*L5{-1c*nBl?y6DPw5k;m!VCnt}jzP9rr!+Qq*PyLTN zWnl3C#1&6IHTZwxqtBff{6BI1b4KHv&K1`hHz@djIBxjcNxypLd%b1#fipa)aq$1B zfr}5Av^ydAf8rX$3-Igaij(ut5B{I{4|m>)ALi|UetALg|J45Q@@@EQ-u{nu+wtM7 zzHhp}*%|*&T)bm1{k@$$EdHnV(hv62ZuNcB?a70}{}baQP}^0N7hpe(w|V8}qHk zbh!RYcUd0TlwY#g=5O_C)AO}r`^O>wPdtC!?%@B4pIQ7_@S@8bW7SD9~u|EJH>D)aU5|HR}2lK&^BKmMPXdckS^ z-}HXC=JPKz^?%D5|4;o(Kiwbl|HP|4|14AgH|@V{-^aoKQ#*|RC*E%JPwW4t&uecl zUKad6-OuhZpDnHbo3@Yp^YrA5fqM#ce=NHGR=(ey^QO%R{-3t*JmECHAHBW9+2ibf z`;~KYUO&EH3)DZEG?4FK=dS0R!uPXt{&}a_{X8jD|HkK^%lEr;i^&s%|EKoh=bs$> zKXH$-C-VCN@1L|gisuXGLwnQ>{-65eU*rFYE1q+1@c+bTKk#DmQ)#tAt;enJTE5`U zW1MG~ZcJ|ZqPp|EO?!g>r|svNzl{H>y*;s2>!{-1c8`PcY=;;r_4F!O;SRxh=0@cr<)@&Cm5d};mPv>jjX#cxJh{nb9f zhvUCrzW>i?XV!=OKWz`+QvDQfr+)9PH;gOXc37YMS_fIapp8H3&QqNkAOBC=Gd}*G zc$@i-d0|6SF?}f6nGBuDRes=grn1|4;3l&)1*0*yk(%Psh8%=8OL) z-fG{M_diOCPd{}ba6;{WOVlMjghC*EZBg46oH>E{jqF0KEY@+#wAOK$V=R$HFmc`I*s zUSs~??d$Jwru~&|cRFv{xi_)gCO_VdJ5v8o$G_Sb|1aj6zun{OMZMo?74CB`-LWV5 zf9k((>+X>M7c>5!7$303%!iyyw`>dkpW0V#-WL2nG5+79k38c2$^TpMT;tIcRcIJ4W8?wcZpY=KT+^x>|gy&wp&6)MZ|I_*n9@j4Tf8wEITV?A1rt1r* z^?x(#ZT=_zpVnu<$QGIUzv=l`{-4_6wEl0}F8@#a>ovmiKtlcBbo}nan`P?%mUCMF zH)Z_PwEk~7r}ckR?rOf`w@vpK{rDOMl$k&NpXQH0IBdb!K0f{+{-5>_~{68_DC;UG#{vrNf z%mXL?>`cAm&u;j|8UOFLhyU$7+&+KJU;Z_VOBVmf89#C2w%?qG*!qmE@ZZAsrVa}} zAM5w)VM&p=(C$BjA1db_g~tc~Pwnm691;9Kar0(1g8wJ((7vwy*KxUjl3V{Xm-E|Z z`!&J;innjyIrxA7=`knu|BT816ZdG-KDm6`M637uM)3Ej=l6ce1?=t^SOx_#*pBR4-|4%%&bC=-%#f<+a9&Y{d|1{sh9XccpPMzV*`Nsd#^#I>9 z_-1b(*sevgY)Lr}?vRrwXZ~k=z32L8TyJqZeqqdo9kczj-2S=#9mf-I|9km?x&Gha zf^6SzOkOsR?v|Yw_2x5ATqjH#juM_v_t0JMWL{CEot` zICnjB*Z+6tpOY^*Cg*(S`hUNd@Atp_KXkt6es{n@*?wPco*(skJ zLkg!#iioyRA7aVm|GX2pT{dkf_)r0@1_5+&M z3jUw?5A|w>{6FzAb!!CwPu!w*&EWru+chvh%KSfZlO|1q|0gDo4gXJ!&xijfZqvL) zsQ;_uq5eAlU(D4172~hr|7rVn_WgwaC+7PN|4&TbEdHOkQ{&@<|0k|{RHfkmY5d;R ztA+eO@kvb^2LDgo)V@FP|HSy1doH}p8UK*{Kb>Fvd;Gtc@&B|v^Tq!YtNyQ;d}RDT z&6hku{J)sV{}c0jheyo+6Swc!Cis6Euang~$N!5N|4-b#b=%DCnmoU|1W0zKQX=^{$I@af8uUU8wdYS+_g!g z;QwhoIyXxFznJm=)W1!mH2+VGA4vUQoj>XeQ~y^?o+b5v#rSymf8rW7Y6SmJ+|lm8 z_Ga$nXYx1k|8zfVc|zUb|B3%k z{$Kq4f)7akpJhS?AFxHkM#29R(~kcqu3PKa;Qxsm*RPbc8uY%mpERO#@c-04?2P>2 z|Cw_V{J)bX^a}o;xX64P{6BFI^KtP1#3xVe9{fM?81wz`|HSx#_kNN=ke=(E)=X_eT;Qvkg<%;0{jXK@_d)NFw@u1V}zXvS;FJ|)p zV#fcA8UIh5XZ0A!|BIRYKXJd)ItKqQX8b=f|K5WC7c>5!=HLFzPQm{ZcRDAn|0^D1 z`GDmAiHBM~Ao+jdVV1v0{-2mUKK#F!@&CjlGyb1=gwW{C6|0iaA{J)s-|HM74UM>Eg7+(zkPb~jWEdNhD?xLdL|HWL@{68`I zbl;Ue>D*?9#Q25e|B1(%zlQ%OKGl4)!q$)Yc;n4Ctar@A z&O@v}{-658_k0oaX8b>KAM*t-Ex0X<@&DA$c;x?y*9&OK=Ui{|HNab^iJNta+>p)i&Fnj^C`6RiT@`qvh}sUo%>trr=hrPi=cn&RJ1_YB zi{SsM{}y|nga0Qc4H34`*ZRqs?c4tNoip{7&0lb4J@NmvJ?9_)PrTUtJp4cLQp@i% zf5I7`5dTldPrY0GKQZ-u&ChVg@BI9vHO}~dr?p+_yx!gi{68JfGW&eu|B1;f#QziTviI*__kP-$&o};`_Q(71 z=O;hnyv=;SWBWhoOkU^h_3w2qHQ#sjO?Ue7;S*f6<(BexdtbfhwVRyrwebJ6zZLer z9sf`B!_Nx&f0@rKY;E37e%l!X&v3>^#Q)QH_!8v*iC5eEb8|bKcklhc*1OPo`|drK zuh`jn?Uv2K|I_(eRI(!Yf8qxg%?o!#8tYz58SQJLh>;FAx7u<1aKnfc!u4TYE#^o%6f< zKC}MZ`DOis|0n)1lm91v`}qgS2le^x-?kKg*m>!WE#!+jmwlM}f7*WK z`+GzFpVo7&)dS!8_+P#M;*9^Nb{PLppC|l2{6Fzp^QZ9t#N@Bx|A|ZN{Nw+Lm)QN4 z{6Fz>yPxC#iK!P%{a-QpgVg^OlRrrQpP2f<_WeE9z zgMCS*TelbJ`HK3%5C3Dg^WV*nY_?*r^8>5Pl6OA-$oaL`UbA|mpE=)Y{_oDlUpY^| z@hZMweSg>AbT!|<&KF;Q4d2hs7hHQK-`|Cr--xTG^8M~S`r51c{&&9Nx@&npaK3%! zjKrQFoNK)F9M2cdP3FGI^M~`j3zjD5|D%fYlXgFQ_3f(8?^u0e{6EcSnccte|HRY- z#s3p;vip-gKRK6}e-!fnGT%RN$p6dmBFm%2|I_x1?fZrLzv5EM_rw3w`5_+^|4+Q$ z82?Ya#qL-5e`0(<{6BHHKbik0=6M_cPfWd7{6FzJyMN*T#f<+aF12?2Ke7BjXZwC9 z|4&R_H~ya(KM?;UKefZ;|A{x-_V|C|O?Lmr|1*a! zt*>hB_h&w)(%B{_GF`&)J?Y@c*X0b#Czg z$mhfV6Z3ng33+FD|1$gUrB_Zo%bC2spGTeJOdg_*?acb%|7rePKKnNKf8uTSe1!ie z#^1yL6K^)g|MU48lm92)Xx~rxe`2mT{68_jm%#ti@xb_h;!Wn~{OiShIB|6<1f6O-SE|0mvHdBFI8;#GV11^-Xyf5qF2>ze`{d8u}@K(Y9 z)Bf_!Z^Hi*7h2vQ{-0R>pXP)Aga0SSpThq;__E7`|JQp=`{4h@jQ=Ojv;O#hG2{P< zsV7SQpLm%0gZO`9{3rask@sH~{J+6guN41JjNf$BZ_AuVjBB46e7JSZOPulj z+Vm`S=J)M)pS;p}ko`XWi^;2;Pdy_q_=R4ATzGgGmIphD$ z{OkHG#{bjy^8aGS|BD&_Pb~jW#}DKGiHDBw82mr6{J)sV{}T_e{^b9O``P;A|B0#p zivOqm4>BK+`oH3yc743H?|ozein_9hU{68`NUc1qsIg>xQZsO<8L+$f0<qZw13tQ|4-bZSMA{ciTmW$Nse2d6diN!CHc=zxwELK^RdZcBMvC%c8!vM zZ!hOw9h=&J9hdum_+l~h{yJuStC)Fz9dkqT*B<-nyrNyFuMd7-ZF@g|$o})4sV9v8 zr*`VI;{S+iy8k!9ZeCwrPJP|n{JvZs*F8V$^KeQ|US6)BH=ujAPnVm& z*S|2^_sjJGbH~Fkia(FtI%oTgx%qp!{&1 z?Ak z|4&T*AO4@XcEeS*{68`EeX0K&GxdLCCjU>|s7c-6|A|{Q ztsne9aoZM+g8wIO-J(gT|Eu}KB3ndlXoGP4oZMKHB_o^8dvBY<{-2oZ z`I7Z#_yl0)&JG_F!_Jtj!l~f|4-|| z^+5igxLfn4A^%VP$qyv|Pu!+a{owy;y~xL-{;%5c|H%InH>^`DIq8m3&W$ZEv+{!@ zotv7^x8R8p&PSX6jsK_Z6U!gP{}Wd^u13iJ6XW~g|7rfU8q^E^pBTRn|4;W%d_D62 zVvfI0a(zI2Km0$di5dLA<_#JK|4&SPVEjMv@y8z@{6BHMh82VVCmu4qeKKako?^?` z3clZvGYW(MCmuDSPjcpYJB$BS<<8*WooIPly@u>??rrsE@&DAH`oHA=iASB^CHQ~h zp%XeLD?i-q+ruxFZgTEt^>*)ib)$2ibGiioPx~kD?xA_>iW}U0NAUZ|X?-|4&SR^8dtRFDy)sc=~ncldWDe{-4_M z?<%i))z=IDZ1yY83i*H9AB_Jemj4$s{-0R+ ze`4kTiShlY{~I&;e`0(u^8dsqP41E4|A`q7|1W0zKQYJq=0i_7b9|3n`?&KE^Y!rm z^m&6%>;Gt0JN}=>qaFV*<_f<&l*Rk@JebA!e;S|l!~csJ|1W0zKQTTX{$I@ae`1aY z|4-aMlm92iU&H?s_qO`L_Bqx*9LGk~@y={H)|HSyA_f%b?$#m-v5Lk4B^GCRV?y*xs>(_hV;XeGd5+&hxh|3jSX* z@}}SeF0uD1_V?>j^OUuJv!ppgHUVe%(J{$GZ9 zKZgIO@nHNvvHU+VJ|F&{7{3btPfY$8{-2mUI{d$wL;hc8|66VQkpHLo+4dp-FT>PV zwfbm&{Pv~dyEVlQ@&fC9F{Xd91s4Vn0mJM z{@a=3v-jg!Z12w_{(<-F&g3iN|7kqx!Q%gk@%`}s#OxpcPt5-D|HShDV#fayueJ5T z|BD&_PrTmN6aP=V;p-oR|0kwibIAYG`M3Fm{J#vZG+!{}|3!@dr|mbH|F^cu4(AQ# z&*A^+{8IlG|4&Ri{$I@ae`4}3%PKE-CLa_3PwkvP{6F#buc>GKj_-eqy>G|=)BM(& zPl*2)^U7AU=IQfLV*R^UdER;DSLQ#G|Cc#l`~mzwF?lp+)_cMk-(c-;4?C~3d_nv_ z&2N$UD)@gf|N844&iH`%e`+tW`-T1Oyu{k^|I`js|5r?Y+c`H(amI%*x5DRB_SqM~ z|I_@*<1)Y5+cyQDW|(ik!F(M2KaEemDgK|B_tE%&;`Mv?@_BbI+r1lq*SUDZy5Rp= zreW}d-zZrg{6F!NZ@(G*Kk<1^-Vx;em&P|0f=C-@U>A6OZ}JL-=QN zao86Ba7)pszdjZGKQis`0Z)4B8T_@m;w#@=LSCBl4U5(W|4;3ITfIH_f8y7+Sv_U* z|HR8JzYqUUy!!o5g8wI;YwLyoXU<>n`HHPRpS8WK_Sdc5d_m_o&5z)JYUlh~d!Cr{ zYkxa){n_#6>3CuMKQaCU{$I@af8u#I9`0An{4K_R!T%HEzx?pSbI!~U|4;4shxmWu z73MqO|A`l6{6F#1O#YvE@s54L{}V6I__U9D6AHu=Z+%wG~chcr~aRK`S#TR z6R+I8gY)IvFWb2%_sve5Y6(a$(9&G>(6UuN|t@&CjtGyb0#9}oXe zOgsLcc!ga*_3&arRs28ky1gF;|4&?Iejxszc*Xj)<{N!l&@1!2`1-te%`f`W`R>`TB$NAn z=lyS+^+NL7gdd%+|Ht#e|I>V~dg|%m|A|LG`b6;m#N(fSHu!(yYyS3P@c+cuKKD}a z|D4}l7W_Z)%w_9>|0jNG_2%IJiJ#lBGx&evcemQ_Tg?9xFWQs(f8r9$`wIDgneRjV zE&M;VbA5#Tzf3#zp+o*(#3BDL!}y%|f7+h=1OA`ZyTp7f{6F#9kG>54pLoOmZ-W0P zmj5S~|0m}BxAVHa=Hr?F zr}nk)?+gB)n0E62>V2F3_bBb;|B3nU)1T+u;@iXcf7%|le?Rc!W&4ME-|oCJhf8y1d`oH3p8#X6Bn?2(5TV#2E&$WKkd4c8q9p3RV=cQ}bCzo`4Jc~CKKH{68_< zZ=SlK@bNac2Y-+Jz|MCqbS5wD!DkmaQ*ZS9cNRO-AOA1j9{*2_ABg`a#t+2*6Av7p z`hQ~T<>LQ|3oY*t|4&?WR_gzWM_bGPyU~H^tg^8|1W0zKQX=} z{-1cL)qlnR6U+b8{DYrn{-3k?Z}@-W{&qd$|B1Q&@c%R(jQ=Oj8__)Ye=+0##f<+q zf6Z-K{-3z@NiCDSk)ITPI_$RK%e5KPD%tVJ{m%G^_OIu-Wh-JodG{M;}7Eh>3CRw z{68^%EdHMuU$fI!KNTMS^{v6bgR58g#d-Lc)c;d|82?Yq`NaQ=8UIh*e?;5h|B1Wy zteZ41NQ$(-zWH^7|0nL%t#5!w#Qe*{}Ye4JRtl(G5L<< z|7m-C2mC*0^BM5}#37%}{68`N7XF_YpAY{}jQ@rIC&u5z{}VHR{6EbH#{U!3f854w z#{W}0^`FWA6X#yfMP0J5?_B;pzl?gu@#iJizdI>EJMV5}x9t4D-26K75##ZwpB!`U z__>_x%jNpJ(`CUsTVvn$JfjCfphnl+n&o@5AptU=bu|oId^{jI%WHk z{kvqJkI|j7c~r-2U$8=szn9AgZNze=z)GqAC#D`T{+}2>5&uu)6DesGJoS2{NJ|FpmA)zkbxG5KHQ z|B1=(!vBl;TFd_vS3Umd;Qxse%Ok}96W6qQp?8+daBf)j$l(8Jen-?eCis8iV@^0O z)c@7?$JMT${Ji}}-yR-)MmaaET_btrgB!e^`o5LVFK7Ip37=o@?Ts2WN)}8hXY&4z z`(e7bH*3}`x$>%VZr!YT@c%R)^8YqJGR@Z${``Ngb#B|DW$^!WJoW7N0_6XR8`}K~ z|4&Rl9sZw~d^-F;abbfr|4-cJm?MJ!C+>D^wdCRNFZcdK+cXLOpXN)R9{yj<_4*;%l{Ko4;cSXj1P$a7c=>P8Xx}<|4&SPWa|H_fBzQd zXPN&e?%ULSLd*YC|MpEA1piOmu1V_uY5f{Etrz@1wbyT0JNSQMJ|FmhG2{PrBm z{6BGG_h0-!XRF_h|0h1$@pmVthsX zKj%Ld2LDgocVf@v@TrTv9Y61tDvN#nVEjL=H+~=fpO|{Q_I>cQgwiK)+v|0gET4gXI(*z)MCeumEoe-Y)c+IX6XO4g2U~q${68^%+|S>UcpLmeHuO$CZ-2dW!!T*aH|4%&p;?)0( z8UIf_V9JTX|BKoF_I7+R{6DqB_W_LLc zw)0`GoHPE~mhW$O?s0Km^3L|#obmr2UvO&{U-#TC&V?75&uspmjt9p76L-$|f8wr| zcUZ~%Kk=}Oi$eaN7+)0sPb~jW+{^M9@&CjeKmMP1u&o#VpP2f-_a8b z#Qzgh-xdEaX8b>Mo`U~J`%^Er@^ER$WPTa`pT^s0J{$gD%=Uh` ze16t$_2ZnWCrkdH`s2fq|0gCd5C2b$kB9#!F0uLH|A|X&e)xZ4{6+jfG4+!1|HNC& zm&5-PZ#G{N|1W0zKQX=?{-0R>U(EP_&USpK>^;DbceVM9b^rF?c{<EfBZi& zJ|X^J%$8r|+jD*_-^iIfMDrhY>3YG3 z#Qzg>zVQE?Gx>jFe7^TO75jKQ@#D<@)Bbt?i~lFar#*GZYd(LjZ~Q;4->QuNCoVJp z?}aa)^>*sf;s0qo@`LdI#MJ-A{}Z!6``dY*`7p1(eUEdoy${F#)A1~|@$vt}9D`&CQa&%s0$BX}``N8;q z;zj1?;Qxsi*!>azPrTCVKX$vnwsXmzz2s{;FW9xm*5h#Jc~;NO>R&t0*|w8m~nBuYE&DVQZ^Ic%q5C0S6 z-&uQ}82`>(E@!@9@c-1#_Y3}?c$ekDT0QlAt4SUF%k6w0S#5UltNXt;pK_w}>*kB& zVyS(Z-T(Ppyx8_{`Ebsw%&#!t%bD*#%WrdDZhnN-XLeq?_fz~$=f%4|!tZo0-fH

D;^3JvQGi&i&gwLw#%K zlk#8T{1#~aE*$xA@c+cupEoP`f8u+m-IzQ(;Vkce>lN1o|4;2pt~@FDf8u{m>~F_= zmG5uiB|Vddhg|Qx@4*SIzw?q8AErLI^LJMNclAwoIxpU~iTdKsD|T<^d^xY$v5WfT z&g9?W|7m@fW&A&J$p;^W{68`EcJcqjC7Jra;-z-~!2gRG|4+>Ii~lF)`o;efZ_>VBoVov9F>!N&?&sA1#QziH->j{;yFkxJ z?CTQz$Cw^_$ zhr$07&$jyw`G4XC)=vJPn0n#l|B1Ojk^d)NZoU%vf8wQfzasxnyu|!l^8dsomOqOB zC+71@{-1cc<&)w6iAys6pO|{R_Ig8wI8Ykt`A zGa46ay}7?lxW8!@lmDmw_;l3&6;po}|4&T)S^PioTAL64pO`$rS|0m{tj{m3q z!T5jT4d(0N|B2Vy^@0C4@ACVD|3|%C{6Fy)`+je6_UOXBhuj~0Kl1VL|HSxj_?)~}vz?m|1W0p z|6(TpPrT9kkN>CjDlwlA|4+PZSDODPUSZEW_ z{-1b-)$=9)PrP#5p5Xt9ORe4h_Vy*)b|)uRdBB#U<6bSD3=TCIni@d2lv@E7L| zo3|%B8$9g1W_{}aX@5)BZwdaNc>e13!T%F4U$r*)e=+0#iRZ6M{lA#;|D2bn{$I@a zfBL+XEM6G=Kk;J^-k%J9?B&8U8a)yGxS5xnmAo|j73X2yng#z)|K8WJf34(#_h0k& zo+mXCr4IR-c_8^Fo=x@&7(~45C1P_{6FX6jf4Lu9&Y|G{+}2>7XL41{6A;=JmCKw(fYCA z|MB_4{}YcffA)v!|8_okY{z6%^Ix5Zo!mZov+zI8gY0}hIPy2=fkRs*SN`$8&fN=Z z2mepw56f>D{6F!~yavJl6L;@!`J)L z_Z^It{yPWXRf{6YLbG5#R=f8x&eejNW#+}*|_|4&SPRQx|NJ`w((bH@J@ z%l{Mez8n8fjPFMNpL6>*!T*aH|Iay-{}(gQ8-Q{6F!4)~$p8C&ssX{Xf&Z{WPn`jQ^+c#CbVf;UF2lEy1|6->8ubA_J|0l-h!v7Ofe;NNz%>3~G#Pa_%AN(-(D&wdL=(9zJAFE`v2oxe~o(8asOQA{KW0Kd3U+Ydi=li&&}V& zmx#B|J)Yd-rT%8zpX(*&-1&2T#qGJiUoLb0;{Lgud;Gcif4P2fF5}0>WZ2{6Do* zuNVJMT&2<>A^-2**|mcI2jl;V$@|0q6IV6A5C2b0z9IF0HJs2uYD zoU5e%U(EP_8lQT;_N|HX{|C#K#n z{-3y0q|0gE@5C2c&EB{a2(fnxY z|BCbSi-P|r9@y3D16ux{xM!PA!T%HU{DS`{?q+$z_W?o<{-3yIGxJ-m{_nTbjtl-|%SMfZ|EG5RIr9I+P3trY{-3y2!{#CXPu!$Y^Wgu9 z52<)q@c+b#-5~M*#77=|Oz{82^8dtjnlw*_mJIg(d_HSb8RGMWhx}o%bFTlF%jEyX z-$(82^Eczk4~zTU_ge4)TQ+YH{6BHMIyIB~9(%v|+HYSCeqZO-m6OY-zvq0K{hpBg zKeczY|DL|?`d!7Zk9;-weqAhoAOBBGejWawxQErJy=67vae>vp#s3qtKm0#2`Fi+&V%o|76L+)vz^B~4#<~01okRYg z+6S5MNB*C9i1~T=e`5K6;=yO<1^-V>{vQ5c%=mvXKj(>^ga0QUIH_y! z|HRZc{o=GmzCFCQ&q8N>zSmkT$m08}&37h$@A9ALW%0@H&2=V!%zmHhj6Y`eE1an( z`|k(db{=NF-0o}Ma>lQkfA&AK82?Z6$8W;_i}~CdZ#bVaxhU!P+iYj@|M36RU-^GA z+uz=fUx@#wc6e;%S;c?IdnNdO_*eLUV*D%oKQX=<{-3rdzpeA}&pVH{`o1+P{KJ_% zMEpNp@8red|A_}(+B5inV*Ehz|HSMM|4*#^znJm=#Dg#D7yLi*&?)^x{a>;CKk*Rr z5ApxR11&EO|4%%?d@}q$F}~uI|9RMt4<2#bU!3vx@c+~w#{U!3AOBCx@jd_I{mz3g zEe!sj+6P@y5d1$e=L`QYX8b=f*DwB`c)+B*;Qxu`|A~7}$q)XYnCl1sPmE89|0m}B z;s1%55B{IHz^-@l|HR7w6LWo6n{|V)7kP!>-+#R``F)$No}R_{fARMCe`5K6V%8J? zPt1Db|B3Mf$^VNP|4&RkVEjKZ{qg_A1(Q1m|IeJB;QzH4-_YI%k1G~mJma#Y@T#%S z%XXFq|4;3_-^KqEueJ9_$G$eAc*B*?27hp)y|1$OYtFo1#{W})@;dPUVz&2p&MPfn z1OHF$tIWqZcYI$TkN1W4e$W~J&)y$8Q$N+-FFJ2DAJE=EI#YiZ|4;K>W$))Kzr>k( zyZC?F|9X4BX89-1%gqO|_oL1$%;&QAr_SUHeloXBv1O*EzM!?^|B1=Z!~YYL4~YLK z#`nYj6LWm{f8sK$_l5uG^D{pW|IgXB5A}bwfAh)k|Fk_m8~&dd-|b&_*Yxf2)ml%l zp2hfo>c7Rtd*aM$-cH`)rr}j1{?6+ARB^@!?A`8g=N-2F)%7YnQy*>iQHMB}*!qR~ zznS?jxBQfP-&XK;82?YlyVB;5|0iBYIsi%$qr}?uz{-1c2<>Qh6CocQq ztKk2MSAF@FU2ji$JBJuyWg|J0ABg{_?U&mALjB*&@oh4HG1ULf@J6dIi2tYlW%fQl)c?)2!}xz{$A7^8 ziy8kfho2iA&8VF#pbZnfXQL=e?`;67xaL-*e`Ck!_e}mstH#{6F!c9s7g- zCw_CyuHgTP<^PH0|B1&AO8q}^LEHO-|0gbL|3AV16Zg-1iS_aQpEly5&QJV#X0mhfna&SieFN+1yky$=q}m0SIM1FmAozdU-y(Zn#Qzh2{LtCK{}V5L z;i2IFiNCk{zxaRR6`MB(|4&@DGxh((r8{>9|4+Qu@;dSV#7p;Dy=BY)6Z889``dZx z$7%kb+L!M)f5z(nI@|pN|4+Qso`3GU{LKP=9`VVnKD#r|Lzds_EdNjaxxVoKoNavk zznJm=bbnfDeiHtlc(q;s_8lb?qFCuaZnfBrmV^^NiW#HAVkPmKSD|0l+O!~YX6 zu{-?_yG4}nO#rFN}{7>`u?EAe?+rMM^q4xdnyv%t20TrF`_w4z> zdA|8Lq5f~?{=V@2kAwfG^_Xkzq5f~CeS!JOq5f}%IUf8!^&f}qaAm`YzYPAL+Sl3h z5dL2|e;w-oYCL{Vga0QcZyWzlOddD>pIH8%SpJ{J#}_33PmFIy{-2odJN!Q}KA=5+ zJLA{m|EZnl5&SpBO(4|F7d2{}cQ_d_VlZnDPI_tL=Q^|5?q_;Qy7GZ;1aV=J!$f zf9lWq#{bj)w%GZ`{}WTM7ynO;e~AAlCVvqBPt5jpXH0Tt`@el~q3=)rpZ1R*i2o6E8IXufw88{rX+HdTp|G z*<)EeZRO+6i%V7}4c0#4yrgthvSQ<3%Xvjfa?!RYvv}@#PZiF*_?i4^MKg+)ELoB~ zJ?UxZC!c&W_a>TPu!t()8w$yR}01M`qT{mpSb7frosOclb447Cno=I z{`GGZ-uUlX!KW)6-qb#ybFvu!FYf=$yOnqVeKQVcL z_|Z+x2nCmwWWLGb^?LoJ^V|4%&RwC=(G6XVw%X8vEy z_cPK9#&z&gKu||LJ}8F`rlbKXLCNO+)^l_{0&Z|0fpv78dEraJ=fj`9eEGk!_@o^_I+Ndr|EK=)|HSy3_ejEOu7#|M*Pu$h|n0y`b|HRA(|4%%+W$R?&=hrz8xB7Xjcl_Bo zuX(HB|EWKW|0gDI2men@{ty12nD_7ae`3xz{+}414F4}?{68`4N&cVK2R{J+PfY#h zSyg9vfASAI-crtk+Nb`X`k!du@A3O?@_%A(+qhmfH*B26otkCm<>j}?_T_Rp*Qd+n zT)!^Yhx>ryJ%@kK|5N?nyXrIz z{vUaD_Id`F~>S>r($$T&3z^!T%EQ#f<+a zu2!vD@c;H5*gW`uCM+g5; zd}OT}!T;0v_ zZIn>|S6sJwlTiOxOy1whg6ZB4zc}O1&MjKBNEY6Goip`&$^X;#ZOxCy{}Z>d?*sfl zaXa(D$^R2~vfmHj|B3lN!T%Fe50?Btao^f?g8vsY^?$`Z?D)z56Aw3^eb#T6Ig`J) z_>gkO$J<)%Qg3HI_3OpSWw+H2*JV{6FoltNp$L|4)ohhyN#*|0iZXch8>W zYL;YWI8~c3*{-2nG* z{}XflwQqH@bK}-6lKx%BIM=u9yThepd_3w~Q~y`vH*ZuY_dYT|4z-a$K(0ol{fbmk9l@c@ckNCy>R?LasQ6hg8wJJaBSz~ zvB!27TgF`Q{W@A+|B|j*TL=G7-0jr1!T%F?9p5JSf8ze*+XeqmJm~b){}VGm{J)r~|0^DN zX1Cz~iShgJ|6(TpPdwzD{NVpNTb?2QpLp1L`3e4?c%b=x_4|4)qng#Q;a{+}3s3I8u<{J)s-|6<1f6XQ$a z|HX{|C&sVB|BD&_PmGU+|0ia?_|4&RFA^xBC$9(bs#N-R&|Hb_C{^y+W3-SN-d7-{5`F~=3F#JC; zei#0qSpJ__^?${~%^#!wuXv>STbAACJjnd6Pbxj(^MO}>`B)aewCPc2e84;BKH^NC zAO4??561r!kGiZ^(&3VaobmsT8T+6!J{kU>=GV{iTJZnG12g`gctFPgbGG%t{}XdP z;s1%{|B2=QiF;2@^Z&$sEq{{yKQZ}{_jD2S=8G3!=gjri{@!by2ip3Q|EK-o`{Dn^jQR@&Cl+590r6`?8GxC&rJQFy$C;Ctnf&PwmvN#s3rIH{$<^w|xDt z;Qxs~u=U0N6Ys&#G5=4zf8?^LfJm z6XP$~yL9K*EFTB|PwlVo|04K*+8=p+x=(q{;+e|*3HxxcV2J)pPet~6tq<#s|L1JatN4F0{-2n9Z2Uhl&nquK-Q0PtJ&*kO zN=s+%r#*^WJM%nn>#DZS!N=R)K8wl!)A)Ps`x^gGyu;S_^ATMOb$xI??D^W6ygz&X zc4of#f7+ho!~YZG@8SQ6@w4su-MBIV#fayGd})b%=mxWAN6<1{}Yo3ivK6xV2uAKUT6LB|D0`n{68`IiTHow z?e_V?{}YqPhyN$W-#Z|g?(>83|1{s-w%+)E;+^(^l64z`{}(gpiqd@c+a;2RBNtd-=^m zG41$&+J2zX7c}>$94(+pLo!iPQm|k&eZ>n8UIf_!t%}V|6<1f6SIHn z|B6SPp636F2b_`C|BadaKk><@bqW5T7#|S-PfYz@{6Fy!^ZW4s#3OBd^8du_AOBCR z{6Des|DM}b9Q?l%PfzpzV#faylMjgh7c>5!nEJo?e`5ST{68`6_4?3l7a(b)1&iH8ff9gNTd{grO#N_MY|HVxHpZ1SmhyNEd{@(|!ii7`GXnrC7 zU(EP_;_i064 zaX*){<$2=&ssB)8{68`Ij`)A#p|+m*f8xQz+lKrZLV)>oRBjtM-4t+__hiCP~plS2(j?gJ)dnOg+|d zmru=N{6Ecy{`h|}abc^r!T%F?wR{=;Kj%hG zgZ~#Z{-3x*lV-vH6L)E0{+RiHV$Ki#U(EP_Vth#aKQX>0{+}4X4gXK)3qP&NBR6?F z>xciR{_V|g!T%HEcToRV+ZR~AReXK6sB>%Z zxjtj=d~=UyOpd=ds$I5UoZCNleMaZhOCDuDN<5$3?Q{LZ|JS^~+5!nC>p4u(=fJvo;LjIrnC+1(0|0m{r;Qxt_Jo3ok z|A}i=OZ`9b@qbA3|1^G$TGfL8C$47oWvTxwZd&z-;Qxv1*nFGm=r-3n^L

{TgTd zar{4x*S1aj;Qxs`b?g%SKXG4U{6BGf^P}+p#QDe94*s9Gp!NwN|4&?Gz9ashSpJ`w z`v?A?nEMC*pBO*x%i}L`#*eGeWQuc9hfYbYb{9M2!%_cN=NHER(|A1p;QxvF{wDuV z%<~ZWf8r)Kzegrd%wqgMjo-@hmGS>##{U!Nx9J%CKXG2`4k7Ky#6L+@zbGtXr z_Wh9$i2tYgupan-VxITN|BD&_Pt5N%@c+a;+ot}XnDrq4Pt5bg&V$OiL)(_Y|I_?B zwQn8#KlSH%0sl{o?~eZ`Zqu@9@c+c*|Ka~>Jn8}C|B3m10QrC7jt%Mr|4-bmuGP=B z`oH4ZwQC3ePkh7?M+E;*`>TD>VZr|sH$LK+;Qxu)9{*2Fz90F28V_GL{{Fz{jk#%q z?B|&#R^K~rZ_}u57I$o(od?*#d_eraHe)sh|BvIx{}cDlKQ4J^&Yt2a4{Zp(-D=jQj=l+)8cgDiIoH-xl|7pCw7pD1t z;*OJhg!;eYP8Zq!%>NT}{_y`|#{UyDKK`GW^NIf_#wQ)R=O&*IJ|O;|jvwC-|1W0z zznJm=V#fay%l{MO|NU_K)!xqee!JzLvKaqQ^TQ9s|BD&_PfUIw{-3y~`NsHv;&xVl z{lHC=ocmopG}Qk+cl^@e^G&<&wow09T(Wy}^3v*)ip8at-+=!o=6xsrpSZ-{kK+G{ z$-}_^6Z5_k|F7L=OM`z1D9{wlB5!iTHow5_^A*|0mAW7jq^r5dZJF z$Cd>DZ-e|OkN=VpLmV6+xz7#w)fA@_aT=4(I&$i5GsH`hVi3pZyU0KQaE_ z&o>_6^TGc+^RwUP>3osTSXTCnGx?19v;XB>X6yUHgWo!{Ugj@2ue9sU@{O_>|4;iT zZ_NA%Z(nWipUt0e#y`aWQ-AzJ{6De$znJm=#A__iZgJ((EXMz{{|BFQrCrbXe=+0# zmGd{j{}Y$k`*d>?yq)*w_9)|`G4BqGFu<~ zKk-s)$Nv*AGXD$zPmJ$}|0h=dpE%^dng1t#+ur};|A`mcdf@+w$@|0q6O%uP|0m}7 z@c+d45BPuLHRfyJ|B0!ujQ=O*{NVqI$>+lV6XS#7|KWU{Q}vc2)(`(rjBkSfCthgp zukruH_^le&i``S z^TeqSIKvsA#M-hL|4;q#C-DEoo9+6<{}WSB6aP<4JxBaMtta!v{}bc0C-=K67-v-G1-|5x+B z_KsN`Z-Mx{v2TR>zv7GCq`Tx0ePyF`9!|Ztf+!?p#lim* zmuCDwG5LS^f8vE!KO6r~yu$J=@&Ck2-v1!@f8vslKH>a&`(pe3!$%cfa9(8o6aJt2 zlmCYQC+7OM>%qCqt{412wXd;!F8n_+_Y3?#F}|4nUC!oDpJx7_+JirB{-5qY>&?$1 z|4+Qm`s4rUe$DSS@c;CEiI0u{C&p*S|BD&_PtQxMEx!~0FJ}Bd^Wkz5iPwMhW$^!;?f!=UC&qun{}XSv=b829|B3PG@c+cS?RcK) z+qqEZpZc`;f8up^ec=CzH`w~)|A{x+`N99wcxC?W z=lFkOe(yy7U*&5T2j7a{Ly`X{rXBxJ{qfU3dFD)KuAkYn&UWT{oc7ka&eWU5|I_@q zpWy$A`F_Lyiy8k<`=cHIFXpNJr}+Hv9T$$c)S0}$BgS9u%<+yr_sT4OX7Zn$@$i^>Z>G~_(xGng9;*yO2Cthv!fbsvtE7xue{-3yH-NxYmiIq;Qzg~WKr<{#LvxsHTZw}_q)d)ygB%P;%*%p2LG?w z%yq&4Yu(-IZCU+aabL>=qyDeB$MDv{{}UIP4@mx>IcCBC%NyD-_Fjm-_KoZ};_H%e5Gf9l}x%>SwJclbYbuC3Sm z^}bK@>V8rdJRZI4vp;zcE4FzJ$!Dp4@Wju(@qYL}9S?8F{6974!~DOv@qfBMw&VZe z#{b2Q|5M{}ng6FQnq=$O+Wfz`@qcR82gd(RZeJGsAN%9~)T7N4;{UXNfvul~|5Gy` z5dRl9{!cw=LdO58M~`eB{GU2+Xp7+g)C2RIhWUT$0ezbV|EKQPyGeroQxE8rzP^~7 zlfFL4dZJU;pOgPwLC@gl@Nn_Pc8qa#s}d4 z)U3CP|5M}H@PBIj68=w(@5BG8@niTuoj;BLQ}^kd@qg-`9oh!}r|!|QdGLSg?j4#1 z|EK2p!~d!Cy0#7ePmPzv|EckQ_&+t<@qcQzK z_Ho(s?XtaEwr4BO@@?a@d>iu(@rmCC96&+h*( z-YXm~3)AkCrss#V1u3W!C@PF!BjhY1i zr*3}AsbT(~y3vUZ!u-FspN-DU8*ErV_&+uC3-N#IlWiVki`Q@UZdkEG@PFFgzT$Dg z|EYVQP%rpDb<(0)@PE4hq;<>S|J1D4i~m!zo-h7S-L_ft;Q!PeTDA)QPujQKQ;Hy{694wbJs`bdh`1h{!iQ4AOENO!vo^~;>Q1}`M$^hsquUG zKQ+h0|Eak@=KrbjefU3hH~YTF|Ec-??5o-{y!+WaKj!~wJHPMX|J1|n_Z9q~n(ssA z|EckQ_&T0Iy?fNG5!V0J{y9~v z1plY=Iq9U6g8x(V^B#XcoZ345`^*39{J&l;(mrrN*6&L^Ki_@O?kBzb`nt;LL}nBRy0Q{(gSe`?n2#s8^CpKI%9oBvZ6oR=Tw|EVXPmlyn>dg8gc!T;%e3(WW7 z|I}m7?;rf1dcwT^!TMwmvHUPy6HN z@PBb1S-8yi$J^QZ6W;hJ`}e7-UYGNxH{Nbe!#7f0{fF1Qxj+1$9xuno|EW1X{!iyq zXxs03{3YLxkL!N(i{9KH{!h0bZvK(^f9esoo%w%i_Q(IJnYV}kQ{&I@e{tjg)c7d; zpU!WT&5OhTspbFFMf39${GS@{hyRNk|L1Mq?a3#f_2&K-Eq=zkc>a(i=RZ#$`+2m+ z|LNyd{!hoF@qcP=&-_0%9+3He>cY!L1^=fmxOjN*e`|GL$ZySzJJke5`x;!f|b z_I!La>ke;jkN?y8(7)|?n{UV8-C6h6RA2brV(*dV{!iyal(IrKzs`(8Z}o+_z1gx=e^plKic&@Z|3bW|4+ByU>@hRB|}TU{`cjUHe)LX3ae{tjg;>Q2QjsH{Q1@V9CyG8<_shLNJ|5Gzx5&x&&VP4g2!Lq@}y&e1?x5xjfxj+1$ znt4vl|BD;{r)IsoZe=fcbNwIxr~AWC;s4ZlC;Xq9>*M%8HP^>)eg1K8)=&L*$s^vJ z@3{*e^j>Ax-}e;X>&?$Q{!iz()|&Z$YJ4s8|J0lx{x5F)pSOJ;;Q!*r|Ec-B!2hZF zJi-5|@x}N*HQo~cr{?zfKQ*2a|EJz$UgW9YbxF0Y-|fA^w%a^T@3+kVnJ@9i|22QO zmiGp`ew|FH?EUJ|kAwfikl_p8u=~gVsaM(ccKn}uwOx-lYqfOcf_=gN@%fGaQ!}p& z|EK2s@PF!Mc6{!d*#-!IknA5g)} z@pySZnui;x$H#h#=EJ<%ZZ^t0bNu55>G=C?JN{4oj@>{0PtE)#{GXcnOZdNI_m}a1 zapV8gtL^sqKlLiRJyuJ-)_e|sRG51Wkz2nIH!T+h(+4|PzlXLa+%6i-8m%Z1S2mI@>r@c3SnDKwQ z{rV3+3jQx{{GWQA{e0p7)bfAcwjKW$H~vp8{}(s@FK(L;>*t3rWB#8W4_?;h%jW9y znR#sX-IS~EC+3mi|Ki5~sY~tW8UGizegAngztg@Sz4`Ya_&@Eh`G2~9_Q(IJ`MkmZ zsl(^3`9Jjv`~49A7dQS-jUUGU#f|?{Z~5f2;Q!QH%`@Wv)O`Nn|I{20|EI?9;{VkA zerofNkF`CYIg1*4^ZMHSWN-OD-Cq7rjpzJsY|}hFU+h14Mssi0YsLR*JM-{rzTGNM zzn{Kqzb{QX+Q$2UZGZAF?Y!|@pZv3fH-4)}wa(tmf4la?oK&xE-pzZH9sh(bJyLDI z|9bDX?|=NC&WCw%_&+tj58(gQ+#mi=&G~J*A}`hU`}?uB*WZ4>_r_=A|MYy|@9=-> z{r3Af{!h*Gga1?W`ChiA(2s|wJbC{(Z$9twe|~;;{4=Ib$kTs6yko!L;{Vjl2gLuy zjsH_KUl#v&#=2d>|IzqAHQz`0KkZL{V*XFP+`J$DFK+ywdfU-IC8JiK=gs`Rx@B{{ zci8p=`_4}_{!h2Zo8$k~ctHH0&hMbTU+{nG1Lp1Ue`Wu&M`?urc|I~Z!{_%h6J?4Y)fAR6~e`-7*{!hKb{`~^}Pq(M>f9fse{x5F) zpL+Y@4}+_DqsIsz1O}!nE$8Vb?{Jf$sPCj`N{w3d};ijdY%3I zjI$oO&wI7a|HJ=j`)*qw82=YH{!h)kKm4D1&7S?i|EV|acsuw%^_E@x!~8$>_FZoW z|EDh7k(vLe#sjkcuX^pKvf%&J@_%aiKlRFT|EFHQeq-=|4|UuX{NHP9Gwc7VfAP|b z!T;&+@1FhXePR7yTN5>Szrp=-g8x(Z>{mPZKXrk5zGU)?d1k1B@5BF{@uQc#<^Qxj zcYJ34pL$?XX8xbL&$w2}yK7$a+Yg-BJ{ff2b?-3G?8`U2SwHn3Rp0U+JIUrpng7%A z#!c-S{GWP)`9A!gx}<#mpL)#9KEeORjsH_mp4mJ2KlLQ@gUtU^Pb~L;YUcUj|J2Mo z!~dz7m-fsZ>+>GE?{H>)+$lYiAx~{c_2E}GdiOTZxM=ex@4ohUnjhZmjb~i`?H2EG zcD|?AD)Z*?|IlKaH=fRHo1c&TpP!%2|2ufrPT!w-f!AHR%bVw;@jbh}c|P!ex;@+R ze|mh=ZT=wsPd(MP#Q&-Bm-s(*$;^!ZQ*(R#pYET=|EXtMygY?Ip@`L^RFH-G8Izc|l(f?eF;3x@pH2!T+gSnQz4Zsqta> zKQ&$g|EJdczqs*#YW&1gEpGP4&*A^H{j^>^g8x%bx8pPaPtE;hzdz&7_HTXKr9Iye zo3|71pFRIC+s9?ko6GiR+3V3xwfR-?@w0nWzyE!nUG~o(@7MTvW3tvS9@XN1_mBf@ z{!x7U?B^%@@n%22+2_MNr}%i;jo*#854L$PqYsaHMtKXpXZD8vLJH{!cCcr*6}@88STkH`P%^~AF=|4)qv#Q&-BfcQT(-VguhZQcw2 zr|zE9G59|}fAib;KXsG(wS)gtGk@{ILs$6r0WF&a|EKN!?fabhf9l~j-w*$%F6xyN z{GWPE_fEn8sqt+1KQ-T{_&+tDZ}>ko|2_f#r^egi|I|I~`=9xLYWzI&|I~O%{Ga+{ zoA-+UQ=i(UWAgmMx!xUYy>tAZ-fx|3-Y))6J*b=gzHk0d&H3a1)c8F7pPKW<|LOkl zdiXyz`{V!A{kwDx{x5F)pPKu_|EYOC@qcRhKQ-PH{}(s@PtE%S|EK2nQT(5p?=$Th)&24L#`?eN zldIMU{!d-)q*H?bQ`fhj*ZBLQQJeJld9$p4f5W`acz@;xrn=cFspj!6{@Dkm4?Oza zpnv`5zWgp7+Xnxa^Uk-y|MC3e|J1o-?0Dw?uKUL~!T%N8fA8Y|)PrXC3jR+$@bsR+ z|EZZ*kN*c;bJ^0>IZ#*9UPy5UNsqstrzqs*#$9h=sf9irC4NdTW zYSvf9|HX~}Q*(cxzx;Bl@qgMr-aH-tFK+yw8Xt)NiyQwJH~uef{GXcndicM%@qcPO z9sWGv5#Yr)E3;FK+ywn)QA0fBJc(@qcP=&-_2_ zPvig8_&WTbdiL!|0OGWryBpKM;s4a~e`?MDiyQx^#@pfl;>Q1}-?4dj_&+rs5&x&> zo8#mE)H`iE{!d+I*IV&_apV8gTg=ZrzyEmet>)+EY_93edb3TJRZsPvKUDR`^WFK> zao+en{GX1`?b}qT;LkVfJ-`09e=pPP!}+y3@Vz(dIp4eL8*k=6{`)syrW*gJ<8%M` zKQ*t1{n?x2;s3N<^Z(Ra?0oQlYUT~vwf|*$zUBYo#{a4Dd-y*!j}QO1XvxRH|1p0K z|EFd>VEmt2{x5F)pBfK~|5Nk+$N%a6xE_uFiyQx^=JxnMHT&cL)T_-e;Q!QXZ9D$& zSpOyXKlOV1`5e~$F5kY!u9v@9_cm|l3F7~BzC1qsU)=aVHS4wF|Kfi0(jmQe3#Fga;(i`;Qw@c=8NM0)c6|wpBnFn|5M{h@PBH&3I0#L+U8B+|J0>6FAM*t zUUB$?;Q!Rj7sLOlmzqan{vR{r@NhK#&)eqLm=*HI`{Dn-YxrsKf6QmX|HX~}Q}g+a z|BD;{r)Irg=KsZw|5MBV#f|?{%m1nIdiXyz+nN8TW;_4WFK*`l z>3H}Q{GS@1g8x(F3Gsh%b^LfbpKb;?q|5Gz>5C0c8^Z(R5fA~K&&maCzy~%tL z{!h(3HT<8t%=TygpPKoA_&+tzFa9rX{GXc75B#5+=MVp<=JxnMwfvu&_1(|wdTO4Y z555nd&u#3DFU0?8JH8PAr{0Rc+SDRX&o5pd|EI>2;s4^s|9RW-@qcQ37yeJp>xKVQ z^Ld8yO@qcQLhyPPE4-WsQW?mouPtE@LKlK)S|Kk7D%)i9{sd;?(zqo(- z)8XEDK>VMcFM7bsqka3^cKe%GjPc%YzdzvrbUfy};{Vh@ z|HX~}Q{y4=f3Md0Amjh6@qg-__I&RB`ZVtyw!Osy+B9sW@PBdR|J0ige;WLs zdW-Fk|5LO5#@m0K>Ny3AymuTipF8db@0~|K3;s{H-+uT{$?Mdy99O{d)`M|LOUl@4x6a-_E?kzL(zaz1!v|A6$5c zH}m@Ne}4P&`G4x2<^%D6YSshB|LOd<9DF~_|BD;{r`~A4zv2JX8*F`I{GWQ;zKs8i z`}=+m`s3g7&il!GgMQ+@-q!nFGx#BI=KcM4_`}}J1H5PSBi_vayR7h0?=9y4W)wf> zy>{pBB!ALRy;qiP5B^W*vv%wDF#j*^4ZEN8^IyIxv;MEP)2#oi*K@`C^`jw?i zlUwIM6?F{j|7v^B@g0NzQ};8!g#S~Ad1mJS;>Q1}^Cxu-{!cw> zR%ZU6n)P4te{nPaPmTW@`M2eH_x$;*jK{P7u-Zy*=F_qMulA?$e`@^Q#2stA$J%^3 z{GYbd6)#`s$D{Foy1$Xrx(ELkH~vpOcv{ck|I|awui^jH91s7e=6vvfapV8g_&}Ro z=goY8yrLc6tlx|O)BeoU!~dy^%@gAP)I7gSpWWj<-qt6=|7km35C5lTej@%)U1aMg zv;METaB836|J3+O{GWP)Js-^fQx{v~|MYw_j}iZ;o;ss%@PBdR|I~QF-oHBH$HO1) zUV7A<8~>-~_V~ZEZ~klWe>DD2&3w;MIsfn;ZO;$$|8#r#KehaydPYfR{-1i% z*p9*fsmF|IAN-$s^ys$1|LOjR4{aCxpL$4s>oEUM`xo{~uWwq^JMC$P^+|i0p}o5V z|5wndB=|q(f#Ltu%mc&!smJx~ncR8P+*ITL4xTG}>e`=18|5M|~@PBH&AO0_H{GWPMPW#~h;>Q1}@tNP>bVL42e;=Pa^3}iP)7$@% z?q6PfV`}@4KRMO~ox2DBr{mH1KQ&&G^?&2W|EaUrqaI@Op5p7@!&;~3-3@7(o?qG3 zJWRYl-X-pWcIoTuoKL(R&-%Z0v3ZGjd-nXg?0I+D^YH$gk7GVpeEhtu^#MD!NzXg% zo;5!(+xunD`@^%u$IteA+2@^Z$}8 z&zIem%xA^7$H&F}-`4l7W9zrZ`!mlkZhYT=Yy4l)&~tjeL&W*#8^Pko|!x)VRT%ez7C6OwH|I@S&A)=cjB@=o7= z;tAE0;R}y-^_o?ZAO3ZRZ?94dLiiCMV84*7&~WpWo`+@rL+6?O&}@<>3F+HIA#2 zZ*Oj|AO26<`!sJ7{GYmh`=&|vqMQAE>$Pi=e75r@Z`Swx)wFb<`QDAbJ*Rog;Qw?y zn)QFxcp&_rUXOORzB&F+&3sqG$pIY<()Xa;;|HX~}Q+Mgw zG59}qr!MV-|I_*7lkk7)QySI_{!cx;LEYg0)KhG}8T0?tcrg5*8ZUQ1}JDE?!|HX~}Q+G2zzxIYX z-rc)*Pi&hv$H)Jf2@IZQQ}g=_{!fj^!~f~{csu-`n(g>MHNP)0|4+^O^7ubB z>+|CO)cihz|5Nk)F#k`DC&d4$d4J&l;>Q1}IY0cLn)!id>AaiSd}ikVX*-So)8p-& z(;@gjHSfRMCQtPJdH+5!dxAGVANW7*-=%%aWW%M!zMbz|{GaZx%}Mow|5Mkqub1lg z7y0%U_Ib|wzuL~{L;QVF$A13eu4})~#@*PS@3@=V>k)Ssn-3j#SNr{J>yD$P2Vbe2 z`=_?|<@fHAng3TcuX66&&)%Eg%|4Itf9ipwGXAgox=Oigo8OyXG(9u_Pu<;o9`pa= zey93@(&7s$j1{(Bn#r_QzYc=3O60f;qXt|LOc`{GWRGoI%O)TetZBBj)BNe|ULwst>i@ zoZ27%r`r!b-`3l;`G2~<;TH@J{!fjU+cRLDZ>JZwT8~!hD{GWRI{Gq}B#f|?{b9?+> z-1t8=z7YSXF1dI}nE$7qv0zy6e`@Xz|EC^3e`N4~dOex%#{9oyJt+7;HU13$r!HEM z8~mSo+{Jmp|EUY-4+{P-Zv3Bm(nW)kGcR~L)x#$~<<0y-{Gaw8XU_-zPmK@5|EcBw z)Oa!0|5dX;>;J0d|I}>9|EWjX^NIh98~>+fJ{|M_)P?2#PtA7xpBhhy|5GzRk@ikRcga6b0GtZIvf9jG2LxcZQ z?6&HDTo7*S&ziqX@3I4D989jslQ=fI;Il=##kqZ9rfnWSA z_&@dbBkv|(|9euYdaHR9{GYnau4m)_)Xc-e|EcjVcKywJvt6(2+j&f>?w`J}#pqN& z+i;{e>#gGdv_JF8@PF!E=9ln)xGGYW_}y~Pt80!{GXb6cKAOv^ZxLE zI{r@cfp&e=d$;*S{GYbJY2FS0XEW!5mwfB@qC4St9#?^@PB%KSnnDC7x(;n zm3)8Z-QoZAeB%&U-SReYwh^> zKQ;3yng6He@v#1{nTOyzdA#^PHRo^hnNp4a({|RY#{b1_YXf?-UhPwxS9*u*_0KKy zW_`iy?|LKE_`l_+d>8zn{GS@XhyT<4;j8d}YL18hQ?D@}fd7jd|EFfXU;LjM&xik0 z;~kj)r^W;0|J3Vko(%p^z3xN1KK|8B-gt%PzqsC;^Znu6g{gkG?fg{Z|8%?+_IZK- zQ?Ihu1OKPS?@j7B&U=$x56A!M`NF5+|Ki5~shNL;|5LMGI{r_+%=`uZPyMD{Z^r+r z-?I5L%>Pp_H6MuoQ@>@OxAy0yYW$zsB=3zjAJArjd2>ECKWr(c3@`Y$-M`JJ^WJMd z(EOS=`{Vy|mVF<*AoIKMf8O@^@qcQ(4E`@}=KrbjGx$GsX8-kXsrmfH|EcjD_`kUA zKX`(P*{!h*M;{ViPK56&G-kd-FPxsIJ z0sp7w{mT45HS_+M|L1K!gIR8IW7E{z4`lqGdfPjPdAzymwfl~S^?%h%x3Ru$1KYKb!66v-q0DW;f@0@4WH6;Qw@fD;8w@pZCJi!T+h>ec+tn|I{0wzK8js zxqAP9v-M5phkCErQO5e>-kaauZ$DoTdapT{@qfDgy7%7?{!hK?{lmfksn?nJ!~dyQ zANe5oKQ$f@|EFd?ApTFy`oUjZ@Jg;eU*58xKl^<4X5QWj&n@%DliBCHH~!5&|Gn{U z_&*(w^+oZ2{{3U`NBp0f_cQ)ay~g}5{x5F)pL&&@5B^Wh=e^meTzy~Sr|^Gq3|IzJwd{n;CzhyT-d8vm!pzv2JXcrpB+TJ!(Z;q%4(pPKo3_&+uC=J0=NzCZAP zYQ8`4e`>bl|Ki5~squ{XKQ*4t{{2Lr9zUP&_&;^2?T`OcueQ%O{GWQA{r-UeQ?uSU z{!h;@pHKKdHIEnnr{?nr|L1M57yd8q)9>h%r{8DseC>YH#T(D~)z7+mud(AT{cZPD z-||XNZ@i!Vew=Fi{n>k`9nXHh_TItcKQz!Ak7>W3d*k1Rf14lm7yN#oYWw})oB6}` z-v_C-|90c)y>qZerf?Grta= zk9mu~+cr7X-|n00jqk(%X@4Fc{!h*PMEsw6kDV|6PtEg(|5M`$@qaoW<{#q!)ObMr zpSsMxZyxS^zTX~icck|P-laAV5C5m*FSqZbmmi*=H|AG=3!ZN4dmks)|LkJ#EeAhJ z#{BA1Z`Px4`26MGTkZIVUtQ?E&OF|8rB`{cH?Mc)x@){Q+WieHyDruEKb_BJ^M?38 zH9!BmzPiEpr}2L}U-rlUd7Jmc|LOL4K>VK?5BS-eEr(V5#U+{nGl*x@dep3*Vg8?bgn75B8OIot+u{GToyPyEhtBMo+}w1P_i*!a_&*(=f4{%FV2y95&z`;3n}5%b z|I_itPwN)^pBg{L{695*4F9K=|BD;{rye^sGyhLL#^wp)|J1C9jQ>-QG0%tpQ}cN7 ze{tjg)ObhypL$%m|5J~d)hqbFxbc7LaW=m%uiD#rpZ&H%Ec;s0uuRLK4Lg1hr+{GWG8m*D@@!^d?D z{!g86^E2^(>Y)=l2LGoXS==ei|5J~$`GEL8wfvu2{x5F)pIZJ;J#k`>;Q!QG;L=c~EWAzkK@y z+y3c!|Mo5^=^Ez$Y5&5)jQ=~)JHCv=i3MO z>6!fe%=5j6_3x9sQ2ZnBY5fKyrTG_lPw3Gr*^+aicR@~0@P9f!9t{5%H}n70ctHH0 z8V`W~Q{$iTe{nPaPmRyR|Ecj{_`kUEf9lD0eH;I$F0uK0ZN9xC|Ms1y2QPajKt3je1rw0ThYKXsAKgJS-l zjyJ~UN#Xz0tpA7qQ{%nxf9h=iH@HpO^NlnQ6ThE_Hg1~g7L6OGx=r&_Q=Mn?wc^_k zw)t9dXV2f8VDp^f?b*IByR+BR&7QZH?cK6_cqh9)pRBlE|2LpT`urQTI61YQd5+qb z|97Z)pt$+@h&$WwW&6Kkd%ffRng1C#^D5&Wku?u-e6RHSzS-+1GoLHIePPeEXBg5q zefyDv`lt5K_I=s&{3=yV`#%kJ!Xf7y-qyW|h|FTb(o zrNQsfpY=M{>_6wN`+Pfnc*wD?QLAe3f4V)5|5GzR5dWv<`N03F<^TS5$7R7E(yafh zW`E}YscY4$75tz2xD#px|EFes+!^No)ObJqU)=aV?>aSt|5MklUMcuLbyBr*@PFRs z>E5{U4!?c9nze%e({|SH#s9_q^}gGen+XeE@YMPz2LGq7c~b4*|I|s%ioySRn>WP& zc~{N&KXoEyGoPj#&YKlaA=Rk-dt zZ|3`bbNjX4Z2$D3Yf{bpKiyvoTW=iyr*386NBBQ=KbvR9{J*$a|5wjX&kn7F|5LXx zPc?1tLf_u4$tl7AY5QRFU-oC;jz`1)X*=H^_&@cij$MQQQ;+OmzfYL|QxE9UBltgc zfAi^YZM(?NH^+Q**8>-NceQzd_&@EB55)he2lee2=KrZ#e;EI#F0_9yan*_Q{CItP zbxS^PHrE@khyT<5_%8gP8sBA>%o|_#*Poo5YW!cdF$;qS?9;Pr@PBHKpa0$2zI~w0 z7yQOn@Y8m@-|woQ<&D2Pv)-BB%#XwW>3sP22KYZUzklHW)XaOv|EW1&{GS?ci2sWl z|EK2l#s9^P|5M}p@PBdR|MYlrx^)WvFK+yw_UG~8|Ki5~X@7oy!~bbJjsH`(ZFN%c ze`@1?!T+gQza0OkKG}Yr66jsH`RvGs(R|EFgCUi_bW z`n=5liyQx^#`A6ZcUh`0_;9N?^8oRG+JDU4yx{-TBj;u2|LOU_3x0XiM&Cbg?x5iR zwEs}^Z_NKw7oKnPzs&!s$IcrZ{GWQ_yrIGW#r<9Ws?v*}uNk}^UhuK@E4_=%s|~EX z!h4$eqIbV9^`3G;esbNBW!|h0jQ`W|X#8K?_&+uC1Mz=xh6 zOS@OR@q6v+yqs$MpB^uMk@$rp|a>;I}*-xmL;E;1j9|5MBVsX0I9|EWvn7Y6^Q zp0J=O_&;^Qf>FW$>Gj21;{Vk6J?8(#jsH{2|HaMxKXtKrK<59cOU!rS|J0|=9~}Ij zdZx`E#Q&+efBc^sUx@$no?j6BpSt+sv0?pR_4xAnf9k^d!;%*#K6>o=F;6ye;3KKV z|7m~C|BJitR}cFBc)@q}Kj4igWd5J_r}2Mrm)?7?@6Yo$`^qKWV=o$*R5;@vZ~Wdf zqwY@i@UC}x;{!izcxS3_`QdhN-XHBhy3L#S2mVjzQ((_O^Z(SNZGGZePb~KR@qqY0 zySk=ze{ggm}=(#>3ql9`oG_| zxYW1P_&*(Q_+=UYr|x}juVmGd3w(PAo9}wu?DM_Pd2D_%I%lr;W6wPo{GXYt+&Smn zl3#Y{Q1E~14Yt0KT^}pG_r;32r&PA>HowNMpLugV(XOwh8vm!;bG;J(r`vNq6aS}P zW8M${r)E7+{Ga-5+m8Q>8~>-{Gfxcvr|lc;`YQAP)c7y_pBn##|5NWW--Z8E@3h#L)VH(0T|f0+XWq=_tN8x3&0q1xgW>;drd{q;pW5?h-VXn##?#^d)Ob7m zpPG4n_&+u42jlb0TT&itf?~Qi-75}H(|7klu6#u7Y9w77o)c98XUyH9Q<*pxlYd+Wi z@qcRG-}pZ@>&@c-;>Q1}nOBGZi`)E&_e#6IjQ`X2Rd#*Z{E0UnYF5z;-uyh`|Fr)G zyFQHnQ*Sk|hyPRac<_I5KcD-!Ki&-=|HVASBi?wvJ1Rfu&Gzp;UgFJm{GX18Kf(X0 zSK8+Z{!hKa`~m(?&F2OFPtDIK{!h*M@k zt@-#9{GS>hi2qY>Gf#*AiyQx^W_}m`Prdy84}`|A!&N&+WAR@qg+a<`eOM>J4^#^KIVv7W|(Xy4=ejxGkUU z=DB=3ex|I(C~w|h_&@E>`^*09z0KY~=JVdtc3v<1pBisre@?ai2N3^%;r^MwXn!7< z?#15Rzdhc8dOWoKd5{|aI`zFa-khJEzc+r>9-lYgAI$&L?U@IK|5LO6BK}X!`l|Rp z^?LIT_&;x3e-Qtt#zWx$)c66cTipCvy>jp2;Q!R6yWR`_PyOnqkHY*v^=*%5{GXn$ zA1`<__&;?~{_Vm4smJzsHuyjFl-$hxKlQAsj|cy!zF&n> zW$(Td{GS^CXFfSsKi~L2^UL0=tnKs7n|Xlt`4{yOJ|Df;96rkDr}tX(x%T<$z21I5 z!vE?1R@%RZ!2hXNna9g-xh!{R`R@a3?dNT0-b!!Q%ROi2T5mkvHw!nW8vm!;^ZAAU zQ}cer|Ebs8=PCX#Zv3B`^>^`qYSw4B?>}#RI_v*xJ3o*3KlOGyKK`#o`S%^(%WRu( z-)3I9tn44&+wJ)|xhyU~6XRUWP=#uxsgo?SFpI)5L>(#7TS8slQpVz*- zH=Yy!=eM`}$N#B$zVLr)j)(t?8~>+fek}e^z0Kx>Up6n_?+-7x{E{K5u5s-!ZywL& z#UoPv)IFoTS^xJ>4;OeJG~d_z>9O8?zbyJ~kvINt^GoBs`R{{<%Sya?KJkBgzVPYz zzqs*#>V5Y68U9bb*B&4KPyLQ<$N#DK+dN|YpPI*y|5M`$U#)YF_uICAg;US--evE{ z!d7#=@qqY0-JbP;@qg;|_Wkqek_+>8eN`d%y8OlYH2zPG_rw3ijsJ@q|EDf{|C8YV z)SC`}oLp4ps=RORuaMjA;LZ8?yfnUH1D5 z{!hKb{(S`gPhDpJeggle$Ggq8jikLE7o?FaLJ>XGK%@PF#U={eJ`H>y6LD|LOi&pBMk9o@Ddv@PB%LOfkQQ|I_yA=J)V_aWnrEn0pkDElO}XaHeB_C z_eAr6zrE`}-o<0vBx}Ye`P!d0+n4W;Z+M&F|J0)gw+Q}E&Ah(@UsUw{3%aN0Yh`<+ z?DbDa^+|i1(R~L5|7Qj-_`s>=1DXG)o@Dd=@PBHKhyPQL=+i6sKlN1ef%rf51iK!M z|5M}jnE$8d`m+7md$e62$Ny=&*8f#=d;Fi8+vESd?fO3cPmPDd|EcBw;>Q1}Cz|(L zSnZ1Z*}uOqc)y}H?SlVP_h{cL_&;^`b}bY9pL%$Qmcjq23v7L1{GXb~ga1?Gw^;vI z_s`?Q|EZZ*hyRNk|EK2l!2hXd+C0arC*9yZoq2cW|Fj*?#{56se?d-8nE$8d{_%fm zJR<&2jo-un>3Ez!{!bmehWS4={s8}{=Jk!QcjsrVf7iElyVUkxEz(}Dd7}oY?b-gX zPn)!tV_sr>e_Zd6oB5Yt7M)lzW>VRz2dHsaX0z#lI5qLy(sscvcKn7t8rX1`nY3#oIT!u=H9#9j9A9|*?hlOS1<9deq6@? zX*=hO|5LLb?uV0(b(K1q^?$XU#{a1so=_+Fzqs*#>J#c_{GYmd&B_V$|J3-H8m;c| z$5*L#wPf*cZuhR)pkDBQ+Q0V68ULs5aB`zC|IcRP`Fg|5|5GQno-FhKysK0Q{?FT< zAN-%XQne~!{+}9ui2qYJJ?Z4&|J0|Pa!T-jYCIt8|Ek-!XcYXPpRf5n=KrZ#&zJds zYStUY|Ebyj?87(s^U>neMv1)_yel<5IeGZ!i@dAa@$r9pzjSKdCip*fm$vN^{GWHZ z|5JCe?f5@+XPb|T|BD;{r}JxT^H}kJ>W=pLj{j3Le-!_xW_@=2pPrv?w*K#va~Jyd zR;Qep)Vu5o?=Gh{Om4gWa_^xwuh%T0cVC+yeDOn`bb&YX_)huiN8Y{d^J>Yz&-b3xw{KFZ z`mru9_kTJbzklKX)O|EFet zGyYG__dWCfbUfBuXZ~N@_&+sX9RH_g{ww}3Zv3B`{qcWl{3QM_Zv3B`d4c#pbzl2^ z%hrlZ|p+DdCv%ZhB8*dqZ|1hsQ?#{i_{x8SAKWFthQhMUF z2EqFc@83H3KlSu+{e%Bgcb#V6&*uNs-KJ;O|5f)py>IY;eZM*}_`gBs^YDM_foJs# z^Z(+;|EUL^-9Pxhxbc7L!n1k@|EDfGyHD_c-gbQE|EUYl>>K=_y4a47|5HymcVL+R zr^f5y|Ki5~spbFF%m-xtpL+DXK1uQ8o4iNP=@tB+whuh7U$X1v^`&#pKQVZ{ymJ_&*(w{r4_hQTou4`r+@dXj}imd+faY;QzFL z;rWC4_oK(Q+xo-y_e*Pp+i@}7A90RH`|_Zahn_&*(=#{a4Dg7`l* z-U|Px#(&}e;@*Ty;=O9di-TWlW$r+?9KTX1*f+FK+ywn&%Jyr`GzvdOex9i2u{}B748!|I}kHACYYN=t6&f`<&T5IsWw@ zd3Qa%ds2M+Jnx0SyeheW#vJb_Ui@S7&4H<Um;dzpC>{GYZjH@|`ZQy(h#f9m&aeO3IQdXLS2!~dywefnkae|r4;?0Pu+>y6j5>$|D8>%ZPypS0`4-uT5UOPhJ)|8ibz z;w}HD*K@D=xW^tn#kbS=Kb;?q|5Gy$1^=hUCo=y}jfZ3YpPK8b_&+t*TkX%@cscx^ zwsSoEpL&nI9{4}?ZhO7$TDCXqH{<`boyPyE@qYL}HS@dhf8KU~_&+ti691>>{P2Hz zzF0pR|EK2p#Q&-Bq4+;F`{V!A<^IB(`8)VOGYP>1GS3hHr(SR8i~oxo|EI?D;s4Zl zKm4EiWxGC%|5LwW*PHQwYOd$w|J1?jn*USpFyDp$Q|~m7g8x(Vc<_H}{006`kC*l8 z@PBI7m&E_YjsH`#KmJe0V_p*ePtD`Q|EW2D{GXcnhxk7=?^pbvnt4k2KQ*5>+pC=J z_fJ2!b+R|}r|^H;pT_^0$#egA!gIO49S``$1--p_zVLtAf4hBN{`QO3zI~Nl&$jir zz2*P3|MTx23jR<1g3XUHyX41PbLfNM|FoU;dhvhi6?T0b|EFesVf^2}{#7gZzs)vp z5dWv%V&{kdQ{x5ke`?+z=HI;ee8>N3JDvmor^aXC|F+(IeDHd#w`(@c8{dNe({>vF zm+s@d@q7GF$H)Jg6&slDo4xTrwqEK$J^s)WDi2cg{xOf~&EvDz*L#_r&!Q!ByqOn? z|I__3e+mDm##i9~)XZnY|Ecj6_&+ti0sp7QL*W0^+suRF|I}sgeZb?*RWExx^d0ypZfP3J`Vm*z4)o+ct^ke^%uRFT-G7SyJ*mDcD{YQ$MktR`Q!3D@2SHw{!g#Z z+2;Q~n>^mPUvl2>?D0(XzVVtHg8$R~UwipA!T+h(FFKd?xpVb;thnlQdp}?4z4rQv z!T)Ldr_U}7{!hL3xkrQlQ-8K=Meu*>wL7+j`G4vi2M+}Qr(XWO*O$-#Q?E7e_WR@B$kpc`jsH_K ze-rRBt{!h*K4gOEP+9m5BavP_dE7^aYyA7z43dy>oxRd9w7ct=gaet|5NjM zga1?Wd1t?$<>~hg+J1lY=JO5zr|p~U^9TQ@=Kk@2YWyYsPyLR4UgH1M`|R=I|MdGQ zUJw6waAA$$|Cr~8|5M{7@qcPQKkyO@PF!q*7!g5A^Uw2|EK2nGyI==t9d^BpBmqX|BD;{ zr{@0ge{tjg;>Q2QjsH{g-z)e(HSaI{pPKJG{GS@Hj{j4$9sj51{fz%p^L>Q>iyQx^ z-f7+(|CiLO5&Ylwa{uRT-#7R_^$zz|r9U;>Q1}H`{z%{9oMoKlO%pj|Tsz$IJcW z|J2Om!~eyN|MNa@IQYM~ng6HWZvP$w{}(s@PtANk{GXcneysl+H~uef{GVF$|Ki5~ zd7JOU|LO5E?+^c{#{aD?d(fZX)w}j5f8OyE@0I2A|Fr+=y&3F-bH77h&lPuPc8qa*8D#;UaI}AZ|1#uZT;Z;hMG6p@c3Ka!>05I{!iPP&xZd~k3FqV z@PBH}|5J}T&HjGe{GU4ii~+&_#f|?{kD1*k_&;@lc|!c3dXjlM{GS@{hW}IJ?eKr< z0-Kk{{6BS%shxxWQ}>+KB{`$b=Dbh8t`~eBUMd-|CDl)j+v?5pHTdi@Z@kx`h1Jz>kFIziyQx^o?yP~hxc}SPqO)U_&;su@iG4|Zv3Bmrg=g9 zpL&LQKm4DXd5ZWy^#q%bfd5nD6Y+m~ewY`C|5Hz~^ZE9gL*CQOhvNUV{Y+brxVQN~ z_3WuV!}`B!<_9kO&r!cW8vm#J#~U*LFYe&~medRW5C0bYU)0S1tEDzi7yMs&{GWPaakt?A z)Z+`=1^=fmENC6p|5c9}+A6I7s~(l#JZbP*g?zR9zw+lN+yCLY;_Hdo>w9uNn)QFp zoCWX4^?T<3sf*jT5B^U*wneMp|I|6Hn+5-;=6XN#|I}kUwGIAHJ=(k+{!h((IQ*Y_ zK(~zlQ*-?s|EI=VG5=4^cKn~3?f5@6>)GP})I1;fKQ-5Xng6H81LFVG<2q;jU$5J) z4gQbyWSRe`X8kzk|EXD@75}GZejfAx)Ep20r{;Py{!h(z`?ELai~rO4@ObclYWx=d zPt80!{GXcZ|M-{u^s=XW*#B)|J2NT!~dyS zFFJmI4zTr>H`Oz` zr=PEJS$^Svc)%?GmpxA~G0zsCPlYPB0Auw0RJHYE|NnHh_si~V?^mNnjnw_ssaZ8C zeCNL9rGLFOc)b&9R7oyB^H{V0Q=i=H+v$z-k2UKLfBo$e-_CqO{GX1;i;1g@tshPZVdDOLQhxvcnA0PPZ z8}IV{S^u|X^<#~f!~bdj`n5CuPhHErCH_y1*Tnz%{nx7<{GYmh{rbs&y58>F@piV& zyK#et$tU%1_v6*Cb$s&dqqljpzVB(xjy3B)v;Oa=6YmIKFsW2A_&;?`o9}n`A8+y7 z*REeP8P(@lH*8ct_&@F6s8OTf|I|&JHVyty-KANJ;Q#b^J2!0}{GXb6f%rdl%a$4c zrf<$G6P*KXsipje`GEe`@(ZHR}W8|Ki5~>HM0T zkH-J0nFomfQ}cO*|5JBv*(~@!JwM%=H3Z zr_SxyKlnfO#QwR#|EUYQ_DpuXzQFg#pO08G-<#hz@PFE$`EvL_HS^W*e`?m}#s8`0 z|I{P<_746}jh|-yUp;=j8SDS5@o4xzb&h?%GyhM`{W1Sfji1B+se5(p7W|)@^^95n z_vfeFnel(-C0YMh+nLYD`oC)C^Wp#09lLi6{!iVxXOA%dPo3YRZ}5L{zyI<~e?EqE z?VU_oF~d8rbB|=>=IP$Oa(V>+r`z|o*9ZTnX1!(nU)=aVJ)d|u{GXcV5C5nAyW8(e z_&;?w`#!|~soBo_KQ;G<|5NjQjsH{QS@C~r=JVnI)OG6A3I0!=RIMKTpZa8*SB(GD z>(R`-=}EPVme2U|&fKR@{ZD>N^Qc7)3cWkqzyFB8zj!~y&HLx-@kdLmwrCo>A6^sx zr!E=LJbCG+L#3TxX%hV21(OFRlYaERck9_blW!-ym+FTH9Q4jJU&s7E-9Fbm9{x`~ z{OrEL|HX~}Q;$8<=6l=vzv_b7{Sy42nt6ZB|BIXXf5*Ca@PBH2AoKs!CFf+;|5Z=4 zd4A0QQ{(yYe{tjg)c8B*|EcBw)bfAoQFD6-|EC^w-hkl$X18gQ@qacC5dWvf7vlfo z#{b2Q|BJiNJu6G^{Ym5C{kT2;PtEz^|KdJ*Y-y_Tf7;IDn_>P>&GGPm>f$+lg8x&O z%s$E#W6cxV-+y_J{84}Ye$2bT*0Z(0Kl9f7KRrHtApTFy{5Jew+%-4- z(Hr0O+>6hry6~re@W%V$|MYrrf6V{$Hm~;mm%mFj>;Gyyz6$@RpBH=@{!d+aNnY@O zapV8g@_%ukJ?iJF;~&@cS#LbwuNpq%J?)ZF$><-R@}9C_MDpo}Kl8@t-MRJ2RCj*m z3Ge9_4^PS-f83k-i}P>(sW%?4&IONobN~21J%0JWxbc7LiI)yd*4^+Ef4(PNG9;OE z{)67ko2x$YfmGxFbbGwo*w*(Q+iuS<{!gzrz7qeZ9&_P!7Z=^`&G9GAyDioDKb;@G5C5kgc5!C@pPKcF_tm`FZ_oU{tG~X{dzj6O z#Q$mk5$65ye`>rR{!fhu#Q&+~|Ki5~spbFFyq>R4xZJn%{Nn$#o!9q{1`GWB3NITK z{GXoR{%7_|rX4!pe?Hrt-Yt3brMcdh{N|cu`NCx150|HJ?3c&rDD|5LNxD*jKs->wHT|1WO*pL+YBGX77!mPdK37;QzIMt229`x4yKQjZt&$8aF z`HN+0wwupLwfPNi{Ga&_Z|2jP|M2GL!+eN0e$M=eH(tYhNvfy!f7#CukFd7+A5;DJ z=b!Wa@et=e@M~|bFYmhI=iba88a(4EZyq21Pmd2zh5w5i{}(s@PmPzDv-wW%<>p`T ze>QU|GcVDu|KtDEYs@#||I};k^928=#*3bO)kS_hK99c6KhK-Tga6b0)A&C%^Qdlp zuqf5t|2)EvkN3m>>He7ihyPRK1vhu;;*IaZ|7rV5^I!NsHU7{3?ER`;uQr?F{hD2G zZ}C+n?=?1m#@3!(s@tzU{88|KwuW%Au;U_apvKk3Y2eKQ-%3+v_n%&mY_E_4QtE z{t^GD{a4%fi#>ktowh&zPxrsA-2bWN|Ki5~skhpEP5hsl^#}2PYP=u*FK+ywdey#+ z|5Gp9^=^1>)PGp_LGXX-#ZSBy{Ga;ja{s3uHSpHp|J0-VKNI|)deVqL@cR1wpFQoT z!T)Ld#pnGd_&@b+*DMPDPkqxB8ULp)y>fc+e|mo3ylistf9ld}rw9M1e)qA3{QT$Y z^;-GDlYBmSf3SNce%O1%&h4x(?p?NTFYAwczxnq5;Qw^IrTY&A|EIjmTg)T{^0{6F=oqaOwTr_UStzqs*#>h<>Xh5z%m&sY3k++|y~ zI{!h*Chxk7=Kd<;dH9ybzKlO5(CyW1!+w7e;e*O9V$EOw`zf|HX~}Q}6ox%i#aw#{a4D zaQMHt@qcQ3AO26xJUINHem`YiDgIBtpVRn1HIE1X7x&BEdwS#B@qaoVjsH_K4;=re z-fHt6@qg;g*7!d)-yirt-5(wj|EK2n5&WN;&s+STdbfGKo&Ow}*QI;C;Mw@^fhQ^z zcr(9mUd^%Ithd{%evvop@#6nnz1^N){GYeIUid#X&j}E0sc?D+kPLx|EYPs z@PB%~%Ixh;#l|5L9s&xik0 zZ!_Pqww)K8l|5v@m)&s`>dB2_Ue|kPx4;cTa z-mw2*@PB&!*1dfo_&@c=-3P+_KkZL5|Id4S#{a3;m+cAuPrY{A?%@B_tF~n3|9O|s z|5L9n+m@XA=O_I2S-B-M|4-+$!qx+3{-5{8jlut^<^R;{majL-E|0-J_c*4S; z`}uG9^)tc$>F+bIoi!!+KlQMpoZ$b|14pzC^Z(R?irNSNr_Qr^fcQT(>jSg?uX<2P zPFVj}t@(fI;WiHp|Myyl#=-v$Hm`*LQx7wb#r!|@V4L5D|5FdM^=euFS3Sbk3ugUa zb-@`K|EDgof4|TAzj5RL)bfAov37g>pL(*bH;n&_8~>+fJ|X^3J!(d`q{Y8Bf#w)lL@o;`0+-Yx9f4~Uhe{1Ke*nlZ+mP0 zpKed%|I`y~fBc`Cd5ZWyZ`&XLr{|B`|m^_?%h{X=iocgFwe^-){6Dqk|EWinn0K=Ie{tjg)ckx6fB4J1{3lNhzK{8ut$+Jf z)EWPGY|Ki5~sd;~WeZseS7uP;D_xkhi%BT0V_U)l@GiE`ALjq*{KkxG8T_BRU|6%@|J0+0 zHVytyJ#=8#-y z@7X)}KlRY=y@LOX8~>*+vGc?Ksqs|!KQ;6DnE$uj5RZnJgX_%i&T&WGm*|EK2mc_r8T{`juTn=SG#>ef5>KkZ-G zwO7*W_#1pX&kz1j_fO;h)U4-<|5M|`@PBH&1O89Pr}2Mk=DFej)Dvu868=v;u6x?s zjm=5>Gu}V(`?EM}ecJ5#d%U0G{j)oJ-d}cSd%o=Z&+h->{p|Hg-M`Jdj62)&<@QWJ zKD=bSfA;q5&i1_7zHfqgkob7n&tLZb|HJ>;>lxoZdp=r{x1Gc-MDu3sPj2U1zs+xG^9$|I-pn&({a;%XIQYH9{2%N8#?Ab{ zTYB6VJYZ$>hxkABaVOLY{!jZe-w*$%#``_>&fUI0z6JlM?acqf|EckRKV5RCcYX7i z4I8HW-pB9o?G4N?4xVZA{>q=9lkNGOcjPwjYIW)-56(N*RchBw%sTpZo-h2L9uM9R z|EI22sdDgtai9E)TYY;&d;NEHJk~86)(!qo``2xBO7MT``b`=I|Cd+k{@@2&H#sTz zKXnJ2zsLMPHS+ffBc`C$yyN-5ndOg<$BX~d;~mnwZ}5NWLESR`PtANo=Ktw<_{Nux zO!eC{-?04`Q&Nrp)9v|v3je2OULgKY$HU9v|J2;yf_4*pfBK^yC8@^$X@7hm{!h*N z*!Vv+-WC6+ZrrwYa`d%v%fH@rfAE$qZ2ssYD~h~3G-{X}sxof*FJF5gct6(v#s8^U z{}=zKZkhG_LM!|CEAjUY^Bm{De5ADbm2HFX!~fNN{IK`TL5+j|)ApOs9TEJWy8Q(s zga3;g|EJD9e`xT3>VD_u2LGonI(I6Allf}f*5 zdS#b);W;+n@5!Cs+#mi=x1Vh1!~8$>6k87%|EHG!iyQwJH~uef=KrbjZ_NLToArO= zX8xbfpZ)QF>XNzrg8x$&ozpA%`pwm)w~ub)zV9bLUzKY7U%Vavr{?k4-~W`pxVLrq z`=jyaXzoYOD4{o*%L{prltz44D@M!uHn z-*tP{JJ;4@#{cR3^5^9S|EDgvU;ux==G(`b5480+yzyI4=e>|>{GXmL`Mtm z=QsV{8!xrwg6C4*ZSwED*&qMsubPKF9Hg$jfAA81|^TYr7{a-pP_&;^QB}0S%Q;#+8h5w6tcAF>scr)zw zN$tnIr`bHYr@wv7yX4}*$9dKFwgH0itLe(y0?3`_RCa-Vnc<-?OJe|E2Tk@>+>Z(kDi;Nbss{ITZo z@PBH~AOEK=w$}syrygP6GxwA`{CMsQ1}@qWzz ziyQx^o_NXdWYq9W{Ql`Z{pb7n7hgImIqCQdy$7D&Blti4e0H4Gh4raQd#*Y)_`Iv1 zyN>Hu-alRXI`b{O*L-+5_`h1c8U-J?&isg7AM@?ZKe6j)-dta@>uaSmicbyK{TVZv3Bmjolvq_kSq63n;nj`~UwJmjn_*f&~I`w~c3aXXEY)Bsj$a z5!`|$xR>HqpryEkKz!pHm)*FB5S$iTC{*e1{rt?n-ut=Jo}*vBeMQ5{!fjs#Q&-Bb@;!y?Ym^}IksLg{!iPB|NK*!|EJzzm!JAY zWxxJy=KpNgi}xy9PZ$5E^P};9>ec1`PtAI`wsuyu{Vz$$9};iQAOEN8FR|;#|EZVR z{f+-q;|=kD>UCdc*Z);>|KtDEoFD#A&HNbrU)=aVHS2}mbKExX#rA#t5C7ii&GX%S zhBxy7&2M;@*z>vb^yS|8zgM4K;?4Kr$4*(`&G+@UT{hR7<9{=BrZ?UX|EKd~{uBN$ z?!3d_^5*z2eESD)j*tJd8Aib~^7D@WQ?Iwj3;(Ca=i&d;{ViZY`!7>PrcS&uYUOV z2*15stZlt=Z{{6cIHsrXk9R4mQ|P_OUJq-2+17iR&C~no-Dat_^}D_2+58>5Ztpqf zMa+tLFDUnaW(0$OTv+b^)QdjeAN*h3vp@fAu6mYTzpXdzJ=4z5JltGcb2#|G1;HzR z=-XKj+2%WX^LUw;@@9Qf^H<)?bFz7g-pfAW_`Ur2Jm2ttogO;KfFx=j!MPkr&or-T1fPdew7;Q!Q9Z=4$ZpL)s-Q^Nc|_0k*93jR;` z-<*lVga1>{x_LO5U&vS{b|7))=-fOmO;`PUS z=B6#YK6&E-?e)uh&aU0OzIo68cptBS6>a{{e6;tXJ=ytxI-lZC_6Pr`p1=Q7dwrPh z`?EeU^Z#_dE6hJJ|4+@&AO0_H{GWQUZMXM_LcM-3!qb`mQ!~F0|ECVGfB)X-&HncO zlxlnb@?L0O$ll+)na6DJf8O|Sdw)!|`FU@C9`JuUUmE}C&H0-DiyQx^=H~_fr{?nb zKegunsagLP|EFgCV*Ho{!gv>e`;Q@@PBHq5C5metKQ2Q=ZF8(b{=2+pPJ|2!$Z&V=6ugQ;~a1PJ;VGz9gpV|{!h)nujWqtmG95I z=DV-I*qiljhu?N-s%zad&YQ;v|EKfe@%jF<@tG;RPYm9V$NSO$OvrrH>%`#w`1e>% z`=iI*8&4=)_tTW3Qak@IhF#^&`x*XE`>)=)FZe(8Dx0T=|5LLa|EFHFE9?Js{j0Wr z68xWfrTM-q`!WAdkDvUX zTK-S>$Fi+Ega1>PZqBa%tNqt)+#39!de!=k$<+g%_Tw*KQyToAwwJ6eO8NdJO zb^D+7Ua)?B^26uPdCy;$^?$nl`K#B2`G0Za|I{;`5*kBws#%XJorC#Pg`#n z|EFd?9sW-}c&z<>yv_epkG6S$_&@b1+m8QJvp(?RzDv9_=XMPKPunlB^=|Qh>hsUE z^?A(ysaYTQ_Rp7PKFib#-fy7Iqr?BHnP2$+)D@Yd*VGNZua|kUN1s~h-T(Bw;QzFp z#{YSbZkyz7T;tu>{1pCA+wp$*zqre)lzKD2Zd%Dx^Ac6EdAV}0QZrheyLIJ`mdf7)I&vQhAV zYA(>L~n)x~SKQ-$I>%;%4 zx&QEgYUZ=y|J2Ou!~ex?v+?};S#J;jr}Lrle`@>}{!f>e|5M}H20U?_Z>RBp+Rp94 z|Eak>M-8~WDDS)n3ZEMPmms3U^^Q?ozw|Ki5~sqty}zs233 z2>$OFJ01L=n)!K6`cyRQA>;pAfBt0F1KRq!_`hA7p9=o(&?-j+|L0xph~WRU|Do3S zKQ;6Hn*ZwoZ@eG=PuuGsb!6~=>RN{$6#So>d4>2tHGUHRr#|lRBZB|a?LEPKB>qp0 zPsIPJlfw@Q{!e|t5r-yUTz7ZH_CpR#s{Q9K@1qYoDEL3!-s8+$UUXEn-RAo}{F^&{ z{}XE+myFtVr=MTVQ;thYFR18~%&Q$Z_fEe*na8(u;#A+C^?SSgG{u|wx3ec#bhA3A zB<&8aXy*Ol|8#%QM~=MR&!?XGH~gP&FOC0GH*DB2tpBUagG+d{!h(%q6?DS z{QPIeU)&Nm;8|5M|m@qg+zt(pb@r)C}+{!h(%x%fXd=a2tWw{O)p z_&;?)`_5thpSnw%j=}$_nRkc(Q{&(8e`a{*U#4wY_zl7Qz2L zI_>G;OPiYi#{a3C+vgYN|EckN3kP24m!~_Nae;Toy!OeP7oP8(->y?qd*XTCZSvYB zPuz5Fsw>@njyKnT+po{|Zf2jS{`&k`-drF4Pv=kL|I~aQVg8@GuvyD6|4&`NS<@u5 z<#gZPu!XI^YyMB$@qGBdxbc5#<^kjX)a-v()e+wKzJJvmo@)G`_Lu)t<5|aKhWK`V z9`Jvgg`G0DB+rlQ>iU&N~BKW-_7k5a`KX$7({_LQCZBF&? z_iysf481XzTktplp@P9f#yc_;c&HB2-OP3T+`DgRs{b>B38efP1 zi`#yGQ~b`9=E3*%F<)oD-$^z8&$rv{!~dzdJ@`L0J`n$>9&&Le_`kUEe`@?7{!h*Q zhyRNk|EJEFC&d5h{N?}DJb&;8BTu=#}eKYzT<2jc(KctHH0 zn)!72KQ$f@|EKd|JN{42_U(7P;K}$|Eak@@PBIN!{Ptb!>{WT{GWQ*wY`J?Q;)RuV}JbHZ~XonZaxnGr^jo^)kVSo z#f|?{GhYz@rygkj4gaSeGO=?q`^tyBhfc~*#*BS1>MqH@dOncq=UU$H-Nzmu{GX0T z4V>bV%W}e@Hk4^FJdU^Ncm7DMIW*#8^Pxlws zKX>VE-uS;+V{c9Mznf3?F0%6}`p=EtUCc+`zW#b|{NkdQu1)nJS6%ImPkij6Nq#=8 z|GUZjpU!`v`Aqzuy2Clml1DR_`Oj~&GwTNbclPIXg8#ew!&`#?Q@^uhLGXX-b>{zU z{i|a2vb~=L|EK2rDg2*$xqY96|GRrao#6lQ6Zk(h-{0Z?;>Q1}ng4?SQ!_6R|EJ@# zUMl`CZu|bwdxLor{GXY*;1!t%hW}HuzAXMPZv0=|_&@b#^Mm-mxS9W_=6KBiQc>)-Z!-2_?-e%h?}_gBd*kcyf4V$9q1qJRKG*J#ncq+LX1&%&7G2}b{dd`;S9mio zvD>-7@@9R_lUttU%{){5pYD$`^KAG(^#||1(cBSNkvC_o;cc&*qwG3tn)Zoj?9B zZu4;7b8TLb%_H;1$Cz*O&~_R2XBa%vGt3+ zc|PL*Sd$jd$Nsjyt~cJ(yj!a67jD6@#r{v1m;clC;rsA^y8Sf%PtE@J->Js`X*=hG z|BD;{r{?yWkMv$)&j<696>UDs?qBcac7L0{Eb#NQd5`!%^%8sh@qg;IHV`;YeW$+ms^Z}P)CHZU2LGpS(Wj~M#ct2&LY@DOH&0E@>35Fz_11H|J{0Qtzo%?b@PF#1>(&JSr(U_SEcie5`y0xF|5MM{wl(-a z^}?Myga1=6-n~2cKlLozAOEMGzh}4oyuanWaQEKi-qr7UFR}T6_&@E>JV5+k-1t8= zo*4h9UTmHR|EFGJ>u2Ks^!ij{^SJPTYJ3s?PrbsPkM{oK&Fd-tPupqypL)qBUkCpe zH~vq((w@)wzqs*#YOW9er}O1}@PBH4UhMtZ_viJ*-oL%^NjBd%qvPR|Z2qtJ66;yD z4)MmbAK3J;sQ;J@=x~HL@1Hh**c-2A^NGFr{EGk6`SJdT|I_v3)9`<4d?5ZWZv3BG z{x5F({FTxBH@D9|pLv(s@$B=PH}5a_KV6>JL;G*G$pIZJ;*U#s3 z{GUEQ^LXI@)XXo%|HX~}tLU$ipF6ipb>AKxyzyv{5A5W<-k!gEM&)~R`tF zf7+ki#b$>1?Jcr$+w|L50d&HO)| z&ua5|%>RoU|EFd?F8)uAA7uWYdQrLm)AMJk`FYm=Rj)A*i2sWl|EFgC;FFHN*Y7WU zep2l|Z`Sw4|7m~b`{Do88*Tm`{!d+I^Y`$7YP=rn|Hh5~iyQwJH~vq(cI&R-|MYm$ z%>PrbwDo*h|5x|Nsx4Xnr^fre(c?+qU;a;*UsJX@_&+rs@XR64`2Ki6{GX1uVr^OQ zf9gf+vi?tv_hbH_dXdfd>++`;yce%rnLIcAMSnglT(K%yH1fCJvllH%z8L+I_x$3l z|I_oQc;15G|GYn#mOQZJy^MZedByqXCC#?K@7-@u^JLYx)4aR(te1>CWV&~U!S#|# zH9z$3IHZ2?e>z^?pvJ-f#f|?{;{)-3apV8g1?GM5f9fLhQ}{o1#^%>`KXG2>(@&ZO zU)R;`oQ=<^S~o%bNxNN8|t0%%7Y7?aEBA)lGx%qJMMXYH!x3 zy}HJlRF7=5wxUP2N!sPF^Bz2^ZG!*P@tG%x|5Nw2^=0vYYL1WpQx6`U7v}$|@rw9A zHJ%awr^dg1|IAizJZ9ND+bViYUNUXb_Ei6R^A2x39{x}F7d{aGr^fTOskX=Wr>iyC zo9gd7eVpnI1NV6|{}2DC^QG~BYR&(P8~>;7cSiHz|J41@Y!UpQn)QnDe`@9};{Vim zH|GDv{c*={{PDuuE$shCZ+za%XaC8&+wg|L|LOTbwVHS2FP|4%Ld7k8U) zzR%p!tZDFm%n!u>shQ8o{6974hyRQFhdY1Dyf(c_@O;b%tnuXEQr+&gzk9QOF#b>b z)A&F2a63N!Pd&_TKmJcWXmHbH=f8jU?%S_Ha?4>!k#Fx)KlneL-ym!JpSpLZN$`K_ zK1FF?G_Xs0z0Q7x>Ge5>*!S77Z=vyjRW5lv_`ea>FEzioXzT;O3I2^9RPz#V=G)=_ zv_FmiQ;)RoFY$kIGyhMG_rw3ijsH`3Z=YTNSIzpV%>PptK4OV6Gp`o$r_1 zx$6(-w@G`1-1&XE&Ch3ie!1PbL;CjQcCP=+ZRX#_$3Ns3*89!%e@9eGd%^$eBaTQN zKX<*~|KO%d|Ug$`MaKaA^5}^RVybaz5al= z{NF>jz8E~=3CC1R#?QFlw>PO)C3z}S(e)}H5&WO_$NzmZ;6C4<^?7S-yx05q8Ycz+ zr|UoAxSGNLsgq-?2mj}7UXb~J-sb)Af8OQ~@qg;-HV=~Zf7{>m+u$EhtyVSoKW(pa z;_<=%sjHrJLNdFi`M&b|quR+QCHr5V>dpMW{$EXGG$Ux5NLb8?Qie}4gODEcwoDP-fbH-3I0#VKi;0N_&@c@Et>`Zr^dtAdVZu|p7oiJ zd1Hik2lM}j&KU09zDcv-|8)6U_W1z+7dQS-&3eGh|BD;{r|#J(JOA&q^Ii%bvq!^b z!T+i8vCRKdv%WU|PhJ1`YGM6fHS+*j|M&4eF9#2J^2sL$|Cj0UO7MU9L;Rnb^?>8| zlZH0`5C3<>&mDsQ(Wf{f9l?snSbiG-S;0hE;N!&E@fbYHknyPd&uEA^tCJ=KrbjoA|%D@qcQ~|BD;{r|y1fyWszHduZ1GRdad# zpStg5_U}paf9f8W+P@#o|EXC|82_gpczMU*|I~xWcMkqf&HAkMK7Gsgr}2N<&U(1` zKlR8fx+I6a{JJ;$U)kVwfBfj`RbKPP`+fM+tEnEf_xIj-!k?D^&U>JFLj0ee4+G6F z;{VimK>VK?--!Q<8~>;7GqE7}KQ$f@|EFf29rORmmsXn&gDer#f z`KH%@(wq5%BdR>%&F#Ve>Hh0yKi~L2@9~|2|5Fc~R1oI>sqt_4KXt}_UhseF0pmIZ z{}(s@PmQO=|Ec?3k)PoI)IF{!2>wsq{qp?a|I}O_{}(s@Pu+Eb&2O~%e{tjg)Gfyq z1plXQYV$Jje`=oJ-7mV`dw{K9jQ`W)!SV5bYStUZ|EcpPWrF`xx4o)M@PBIN1LFVU z9`@K(etqnZ|I_)jH}6;V@$vri$@PRufBN}ten!LK|L&>WH2A-V=iD3o zpL&|D$HV+T_3BSQ4gOEP#=f6s{-2ulv+Vn`;^_}H3Epp!eSe1kiyQx^X1y%@U)=aV z^;+{%_&@b}n~#D2)Aixo@PBH28~#tt`o8x4qBrvg?fXaXEp|Nnelpee{iQea2JwGp z_JSYe`$YVon(yoIf9lP4eEgr9^>gum>ast5ALjq5HUCd7|EK2m;Q!Ps%h&%^Z?oea zyZbah-z|1~mv5})&Gk=Sb#kilf4clu^L+TfxUZ{qyf@zO?PF`C+SY3GUT)Wa!p~Jx zJ@EUZy_t`P|I_igz4$-1{GWQY`9S=iTK-SH(jE`|pPKoPtpA&Lc(dRYnU{k9Q_r!- z7yqZ8SMLARcuoAD8ZV0fQ*-_JKQ$f@|EFGV+rM~u?>wCk>yZwBaHludH~+e=-gE8# zXnOv}iniy|69d+#`hX6ry_eheD{3$ImjBcBvHl|dPmO=T|EV?qPv^_`?f5@6-?!uc z;>Q2!@@&WdskuDD3=Gi<#*{GaZhcWoYw`4ZoMu6;jjUd4N!tq+I) z)BZDUJ`Da(jTf}_IlX7wdU3Yir#I^hJqy@ z@qcmS|I~}jYuWjDFSp0Te5Uted%VnVdb7UZ&%gS~d*!B`_{l=uzIj_dPELEWa;jM? zSKBrJPxsI5Pfo{U`u1^G&Pmu;`{#AK!`6dtSJACsPWHCTc=zr#Bh3HP@y3qM`aktK zXTA{ppN@C#jZ=dEQ;)mzq2T}2>n5KY{Ga;0v%3cWr+)uR`}d~#Kiz+2kDVL*pL)it zj|cy!$8TS0cK)Aw+1jlCQ!ih)HuyjF+hrSq|5JaseMj(r>P0(t1plWl*|R73KlO53 zFBt!)UcGBi@PBId$N#C9njggfsY~|S{HdWc3-$W4-2AT1Z}l#**AJWT>W#Oy`LEuq z?ezoyr_0m$KlNIhFN*(*8~>-~^_TU3bv}4H{GYb-`o{b}^%8qM!2hXPZxsKh=KAn| zYL1Wp)A9LvGJo&edA-K}X@463r)K^t{!h(3GyI>L^TGeAd40$Ksd@dv|EZaGivLsd z^NRmdGf%L|*ec%mMf-e{(fc1B%|8ElGtbRFA9>@w@P9fUm$%PXz8(LI|I_jCTlhcq zI(xmt|EYOBv-!^6@_#x$e?McN4}Cjr^P|0a|F!wj-n^gMvAwxJ@PGQeOymF5cy|1s zn)iSFpPKn__`kUEe`?m7#s8^Uj~4%@=KAn|Y94?5pPJ7fllFJX=<`2~|5KOQ`#1hi z&3e-KKlM6$KVkk~-1t8=>m%d;)ckt@|EDgs`w#!8X8t4oPtA7xpSsN6AMk%_ydeHB zZsz}~d4A*n;>Q1}ciQFgf9f5!KmJe6&lmnr&CeJ9PrcP{f0d1wWInFiB>29~_IQll zewjCq-`{>5m#KMaP+v9OZzbi7mzit$~-&*^5!~eyN|5LL+{x5F)pL)IheHi{P zZv3Bmlf7P@eD+P=o9*)!{!izN&%^)4jsH_K9~b`@H~vq}dcsqGp6d4p>kZ@o^!&mX z4nFj5-%htX@*Z#2FUJ4r{-p7L>NV!|KdW(ns#l%(fcKW|yOZ}%dC+^adB7)YKjh7P zznkkn?7eK$j^zBtk9gzp`ZRwu)y-S~+MD@(%>UE*us{A!y>jEW;Qw@gtlG3a%>S$C ztpC&gD>iHn^Z(SVteO88H~vp8|EJ^8%>Pp_SXUb6|EcG$T9XVO{JcNkmMmY9Ts!my z@5RfO2mhz%<06~?hyPR0S-3d(KlSY51!4Z5dgk2XWY4~r{rU9%w0DzU`(N=s>+CVX z|LON1L;5!j{!iVjYwh6w)E)ZO3jR->Kd4Udf9eK<8wCHSZal0pe?Og3cO2L__&;?g zo9Bi9Q+FMbo&TrCAL0Mhy+$+*{%`+1?SlX7YwPLa|J2NHo6>E*cfYgRBy~nF@MfOh z!f^{zeco-0yygFNee_GOFY)a|%oF1ObbU1bPc8qa#ut`OT%M^?sa^1Xc(~yIq7MGA zyzyxGzkV0A4gN2zPiy{9J=8oN{!fiB!~d!Ad-y*!ey_%$_1<{DAI~jK^_Hv3yqOO; z2me=oJhlh_7j^J|<<0uN!T&|uga3;<_`hg>*8kPxHE49pF#k{O{;zz0 z_kZO*%5HD)f8{;G?$6-=%A5P=fCgXt?d@yZ@qc=}x{b8&FU|j{i-u+WpBkUX{6BS< z!Ht9eQ@0!1F!(=phvAKb|5I~$=KsZw|C>6eP4IvG{Nex99Dmvcf6csK*v3ACK2XHv z%dY;>JNQ8Jf7;%|em?Pk>RvXl6aS}X{o_BZ{d?xC$MXtLz4QK}exve|mAn7pJz_+g z({?w@PF#z=9QWMr}H1$Jv;wT-Lre6;Q!Q_g4(I? z6Fao3o9a$^^;12#b=p4-v-RoX?;}~y6aQE8_h*Cuqw#-g`M+!TJ{P!afT)I)5Z z3I0z#)aKvd|J3*={GS@XhyRP4`G0D@kH-JS&HBG_OZY!E^J4ISYJ3I$Pu;skqcHzZ-MvY@F#k`@_vQFMHQ%S>|Ki5~ z#f|?{<2&$wYHknyPtEuB_&+s%?ZtC$E2`4y+2H+H9~%FsX8s%gPd&!w3*rCNBb#OY zpBnFm|MTOUhr|EHjsH_~zW6_NuJ_CB-1Vw+J9q!w=JAf7&$-)k`imc0c)(mQ$j?uFdvoV2;#=bFx&AP>bB~w1{&4Q~ zck7rwe(v_JIrj(tH$I=-d54Gng7?c^@ArU82d0j9c+UL4Bab{XwLRAZ{@41x=K13D z`(GXq|95Y{->3Yan)A;eW%Kz?|6O=}JowN9k`H%3=bCueTF)3-M`;n<|^*or=}X7%KcpG@`b%=g3p>H2B> zU)=b=FOUC2@Q^3hIzIS6^(m*G5a$1>>(|Q8|5G=vQ#bfOb<4W7lD%tg_v5#)`GEL8 zU0;{P5x^|jz1Y5bqMW5ewHKXs=@O@sea zGyfF-r)GX2{!iVp@oB;TsoT~+Iru+yixX-D|EF$zY}Ws&+g3R`_&@c)Mp^%-#(OdU zPtCkk{GU3nW!C?xHUCe|JU#rMx}|-d!T+h*pY?y$tfz|qQ}cSr`oC&kFY$kB*5Aed zsoUD;n<@`p>dy~6-oejY;>~vapZ3R>GyhM`{f+-qH*MZ1_&+uC;P8KH-mme0YTmE# ze`@|d0RN}v^8@}*&GGPmYCI+WPtE;<|I_n{d9C=rxbc5+|5G!s691>>=L7$z z?%de^KF{X=bw1|x;QxXb9XZIiH#Dy}``m%vHS3-h{Gax(aeUR_|I}5hRZ6{I@cPm3 zy?%cDW-S^f=gjWw&H2XfFRX_gH|sQ@JD@$P+T zm!x-x&E9>-bxXcDZBs>?$HV{W{PAq~KQ;bs<*w3Hk6X6hoB4Q^-d~q${GV=5&&xW7 z`G0Z0-FS^}$Hxt>w%U8Jc{u!^_GjK9{!fkH!~d!AjmP|4;@8jph5ys}bN%=~b#L=X zw*Er#tGhB;?`Pf(|EKP4`{V!A91s5&xBdR7_><H1G9}&HK~!Gk>kh__w_K*!;B#r@!fqw_D%sja0X4{<=3l z?+^FC=I2NEz2*<8{_^Zsy*VEKPmli~n-_@xQ_KIwjsJ@q|EFgDApS3I{GYe^L+1a* zjsH{Q>ssIXte+o^|I__FV0^FO|J41j=$YXE)ZAbAKQ;F!{!iWS@`B+1)P2qS;{Vh< zKUn`)jkja|pE`4ScK)9_-+o^3f9fLhbIkvX8~>;7I<8~ze{tjg)ZH%c6#So>{h9x# z=I0at7dQS--D6zW;Q!P;FYgxS|EV)qbPE1YU1%N^|EK2q@PBcCI`}s4UK2VcM_zS{ zcORQ?*uU4!-Whv*A3E_yZ|484`{p|Do>vwoRTo_2-Rr7Mg8$R?(fB`gpKH1V|EHgi zK{g){|EF#}vO(~F>iVa*4F1o)(+mFZf%#7a|EHe5GVA};Yi<2H=KrZz+4p()KQ-UC z;s5r%ofrHc-(TYY;>Q1}Sw9N@r!KSa{FB_1<93`oG#<2&oMq7Uv|EKe%@qcRhKQ-&c;s12J zQoDcge`@X@{GS?ci2sWl|EFGJ-NMGVo}JISqp$JChv5Ho zf6(|pHNFA=r{mN3KQ-&w;{Vim9Q>bpk-h%m|J2+*`)}_Bdp`~SPumyT_uV#&$+yom z54QjJHND?A--rLx{+wm{H{Vi+rG;_6`#{bz2!r(Dqv-xoNKlS?`f64qX z?+)f7*Ykc^>?q8ZU$YQ?LEZ?l1Fy>h)iI9sJ*)E^iln;aY2()izhX z+V;o)sabE*=Hbo3oYi>e?jqhlZ2ewuJgIrNbn`Eu^8Hzl(6;BtZ9Xqw$Hzn1?akNu z(dH)$)U0QW|BD;{r)IvU-M&=Y?N7DcKi>EryZ^kI$7J`fH}i7we>%Svd%}E1?-KI~ z_&;r5S?>ST%kBAL_g|rU(UyHl_turY7i`*V9b`p$*wbH+TMoVH+)_eJObF8DufzvQMnga1=cnws^0 z>XKW375tz259jtW?|7Y`@7wly6aT04Uvc;7;Q!P!Uwkz9KRsTbt(hO@|EWvXt_t)2 z)T=hE5B^U*ZDZE|sb_A_uK%lEvUO|lf9hrC0qyZERO18je`>rR^Z(SW2aNwyGY=5| zr)E3;Pd~p)_w5hTiv zX}kPi-1tAW{9oMoKQ&&=e7!fXulPT0Uud@v|EFGJ^TqIgYUYjM|Ki5~sqx47KQ;4Q z?ejxMukZLI`+SjV`}+g$<@Wk#pHEV4pI=gq|I_i9hll@D^ZJGVQ{$=Z^OHBPm-s(z zr)}-dj6RPsztR3a!<*L+`}~$_`+VoU%wCUecAp;)pN0R^@tGfp|5LM`JN{3-*j``p ze`@?8{!iz_>lOY_&H3Q})ObewZ*T5j{GYaS`|*G34R(3_pSsM>AOELjUM2od&F#bg zsrh_^|I_Dx8vm!}{RID~USso&54*HirfQSC>^wWWKZZ@{lj;|)>F3SAKk$FL{094b zBmAFw-IrPa7dQS-z1cp$;s4Z|?DHG`PmS-x|EZbZhyPQ{|HX~}Q*X1&Z{Ursga2D(pAYbVH~rWu_&WS0t_g-gz&+){E4|p@5Z_dmIy_ap-75tx$U$S{;a@hQbeLM33 zTP%7c)x(!Q>doAkXSQ*zdhr&2v-_tV}>R<8^5|8)GNYt{$cy23H~qc10G+TYW$zJ z%m2lV|5Fbh+b+!iiyQw}^^L;d|JaWIiyQx^9yX?J@PC8;QIPe2*3AD?ko^ZD?9YSyR4|EUL#$P4~YJ;>$>;{Vh`M%j9;=Ks`#?eeG3-|Wr$!yU`E zr2529w|aB^_&;4<{!h*PysOOr`Tb#y|5J1O@qcmS|Ki5~#f|?{bA9-~xbc7L0k)nr z{!iWijO_Zq>RxBG4DHo^a? zhm`w2^}wO6g8x(ZH!s}0%FllJKIQ&T=firyRUS!-)V+GwO>Lx8;s_3Gk zTB+|3n>INi)$Q8WNp-HbVSU{A`^P~xFDAEH|5u&`FUb5qHNFr3rykZW>;Ke4+cpdS zPmM3a|Ec+Y`<%D0C~AH2E5RGG9;|&nN%ib|CV2DxIQ}obeDw<_`F1?q!l75D8vm!` zmy)E!zj2>wsqsdb~^|J1|HFR=cvdT8^;!T+i8g7`l* z{t*ACW@qd1NYy6+LT_65WE&r#^owtY2h@Wrx(zx-ZasT4_x%T{v_s^YQ_e<;D z=K8=~|CW3C-1&N}{~TZc2=lXX^ZbmvcgOU4+@tdIQ`?8OPjAn?{@m`;GJXH$dO+51 zjITepnYS5l@0N3a=DvR9cCIJP^?Nc^9g^^ckVr{?nbKQ))f|Eak@@P9h~A%`3i{GYno!G{L_r#|lRBZL1_ z*RGWHf9ghdf8hVr#~*)u@PF!)PC6<0KVAQ6CuZmW#f|^#`QAIh|J6SExTNFzQ~Z4E zpLSAmUdM`VaO!Dc{-5@j|5LZEdus51I(}a5tp8J=TKlBn|J3+G=KrZHopxOCe>&c= zjcSGYe`?kPKH-8}{d`$382|U#;&+1wY*nv8nE$8Fv-L=s|EFesQ~aNrd4zjjxzUf; zqUP~Q*?Tv5H>_SYIe64{etzwbshXUA;kDkZ_xt9R*Lb%)@suRF{c7)S=Es@;r|ZM7 z;s4b5HT<7C&puyFdg3Z?=IM>AKgrLhZTr^AIe8OPjsMf-dHuov#a(#D6}~^)^DeqP z)%ZW{&+9$@PuHN7r@qg-~HtoXvKQ;4-S^rm;=ka6xUp4dj zR;)V1n|XxH|I_xa1?H!0{aG+&K{!fjs#Q&+=*nDREpDxdO&-gzz9uWWM zZSx`Ve`>rX{!fh$#Q#0C!2X86(Z7nA7ueJMpSH7p@oe*d>gqL53jR;~S3aRi>izNP zla5I>KhN>|XY-bgQqAp&xA*DZBh__I9~J!Hr0RWw|EoXdjNt#&O~>|1x_q^}SY2m$ zVX|+-F7J*PwY5yD^`2s{~jK_${YXJvg=B3&abq|3UAJDQuXED_(S}kuD`FXhl~GHcfYJl z@PBH25&lp27akJ-r|xrE*Wmxucq;s#y8rkBe*aVaaapgd|1+P3|5M}1@PBGN8vZZt z3wF#(_2QD5-UIA-_&;4A*N^{;8~+zK{!fhuv-LB)d4AaX8s7Lv{Gay6kK+I0#{a2@ zo3FzE#f|?{Mj%Vga1=={`fyN_aFXG&HaP_)8j+q|J1{6-W>ihi2qaL1Mz?A0`rp0|5N9i zuf+eUdHnEyYJ463Pc8qa#{1#_)NE({UvwyC!7CVhYA0pkC3dFBP;|I~Os{GY8k9Q+^N5C5m$V%zb5YP=!-Prc@wAClL< ztLMjC_op8d{GX1G55)he*V=l#_&;wuKJ)+7tL*mT|8#uTOT+)EH`(pQ|EX7*pTz&E zIUoF=da2zW{GS?MhyPRKA@P4|?jPp=spbFT#{YSnpF7k1pIZJ;&H8q%|Ep$x4*pNQ zy4?Sn(F*>LX8m6^^Zl6r7dQS-&3wsY)_&o~qw#+_KI;qP|Ki5~squh6Zrw6Z_dk7Z z$p&xcN3Qx{oj2d#w|i-oH}eF4`_MA)6*hnH$eR~?^L)Mf()r%2?fY!}pRONIh5u9Y z{XG6p&ClmwUVJyz%>UE&Ip(97|EHe!73&Ya;`a|85C5n8i^l({`T55GsqqE-4u8y# zho{5;>G(AMPrb~JSAY3k-X-S!@PFDa|EHG!Q*-<9e{tjgD*B7y|8#zwKmJd>)EfV% zW<6j0pBk@d|D9^HDBiQo``N4}?-_gc2mhzbPuufJ@PFzzx9$x7Pd(G-y)pk!J!9jJ z;Q!R`TI2uXHlO4DmaR``-pBjh-Jb;iXKNM*AISCN|Ki5~sh8OI?f5@6ehvTUZ9WqJ zr{?iv{$G{13WNV!X}2H$r(R|EAO25WW}d`6+?=@af6Sc21M+@=|5M`|_@DM?eMUQ8 zzIvPaKK!2=e~$mt`QdBve`>bl|Ki5~squyQKQ%v3_&+u0hyPRae8>M)^w+`vsaKe9 zvGeimynmX{OttyViZ=ge^BuiQvhyDcb-bmU_p&~;_x$zSga6a*pSJwd;Q!QjKR=tt zqfkA5{EUQIdg@L#{|{TI9^B;la9^u0>N-96KRq7jpYdGqf9eSry>9aiNBQL^-h6lR z)N5yZ-+a$w%v1C(o;ohs*=ec`>|I_{P z&6?T4|EX7$&;L`e-?TCKKlMi&vi?s!Z~OKz|4)tgv-zfeeJghD3jR;qOLp!F{!hJP z&%WUQ)U$VI{a@TRf3;9QuO+q}|EFGQ9*+5c>c#s%5B^WRwA}xx@pYYT{+~MgdbQe{ z^~&*o+P=yB6#h?*-)8+^b+P#({GXbicjo`8OKe^x{!fh`wD-qCy`E;h^*7$kcflOY_`!gR5|EFGU z>woUL?#PVZkJnl^yuEU&@qgNXmHFIxk5%>U^kL6e^XBz`_^Z{u@!-$Ddz?4E?TeWw zc;n~rf4Y9w-^KsMjsH{g_ci#xxb5?w_j-FhvCoIz%(MIc?+v^)|4+APv3WK8pL+fN zZ-W2R@zQ1}@n1cbcFgGW`%1gN?Z3TO+2gx?V}bV? zyT9!7yEk4D|EJ628S#H=){DmfsaMy)oYUWkq|Ki5~skuD!|J0l8e10?iY`=c|-rm{g zdb6H#vxVn-JuMkITG!K&RmSX#Agg zjd?!&-|p)=2LH$N1OKPy@nZg;_UG}&|HX~}iyQx^UTdEZ@PFzx_IiN-)A_A0_kVHM zKK6Fsjt}fz;|}kYHa{2tr`yZ?T>PKz-_mmbr(Rp`|J19ueH{Fsdb9aH{GWQ09UuRv z-yo;ho7 znE$7q_R+L3|4%*PstLjWsVDbu5&WNiKXOHWt>FLE?fTUY^Z(SH24&a(RkOaY{eCnP zH~vrEVQ`bge!rU0?_WC&ZI;;YU%iXW7vcZ3y^HxG{GWOd-pJPfRgbjwXYqe({NH!; ziZjRb?G?No^Z(YD&iC$pcDv-gPZy;6(Z4VB?l-n=g8$R;@Phb1^`NnB!u-Fu@qcPA z|L3vGQpdyp`T5v({GYn7t#7+w=ZehGM|%eEH_+C{W&U5>_&+tb5C5m`J2o%O|5GzR z5dWuUejxr&E&r$PH@bE3e`?lWW&WRfq|Fn=|EWifu=QHa|EWg~Zx#HXddP?t!T+g; znHR+WshLNJ|5Fb!-^ctv_2|>v2LGq~XO#Ic{GWQn$X3Ds#f|?{;}h|J>S5*$@qg+8 zXS50aFYethed5=T|0|xp-@BjvJ@5<5KK1S~x@mIj_RqX~*?Pd|{PA;d<^^_1zDza# zPqz;*iT{fm|EFd?9{x|=dw9#>|J1#PWas~>d)m(v{!iUwaHHgrkG{)1x~)g>ecjFD zPFntF?}9-M68xXG7nb`!b^D=>lShXAkXbmmNAP|$^Z(TNzd8^7HFLmI-Gld&|5LNR zF#b=?dcgQUHS-Pee`@(ZHR}sA|4+^FnE$8lZ}SN8f9k#iv-AISe*OA23jR;sr%!|6 z|GaxQ3jR;sqkFw%VdDdf)LlBI{ZqI6^!JUq^SA#0_`mr3%0cZ~CjUD8(xT@!z7f10 z{lYU3~3CZ|3pg|FoTX zGWb6=$HV`r^KE@w{GXcdv+;lGA@=<<^Z(TS%l)6awXKiH{696{?=$~TJ*H)g;Q!*@ z{??7Y9sh;@({_9u{!h*A!~dzdefU2$^Mvq!YUVfL|J2=Wy}I>fw-$Z#r`Ln`>)ODc zKj#0`d5!7@|EF%(v_bHH>OM`g{!iV#LDS&>)II7q3I0#lN8|t0oDcp_&HcsvKXvZ< zyR1JLKfhRiIBxu5+_~!m=XS1#%WZsPe7xM_^L&iA;}hb}^=i4E4=)<;-{0mB#m)U6 zciSfE`JB0zA7EY~-kZvU@&fAQ_BR;hCEe?x{&5B`tF|EcBw-s<~7 z@PEv=WB#8yu>pU~|MNcN;Nbt%tQTDS`Uidcu}2>n{GX0r`Izkbzv`+rjtc%yeZsL> z|EE5&`q2sgPmK>`{@=g5d>H)S5tR-O{!iPh9C>K)e{nPauVVj0ga1?GC-HxA(nwww^EZ|I~O-*8kQ1%ok++U-i*PAD!giRnf;Ddu&+$SKC?N_u=2% z>HD+3FZ2Jjy>6`&!u&sVol}laj&3s5x7Vq8a`1n?-5UR=#{WGq{|;}~`(^##m-~Da z{2=rGSpQeuy!Odq{+}*ivrhHk|J0|{J1+P?^$GQA2LGqapVq8y@PBIF-|&BG-XAJY zyv3W>mjfnG_HNyxr><4CQt*E|zXp}F z{!iWd_?p50shiic*E{on>h{gsBv1eOYQMgMmTiOoE4*Yz@QR(A=LP?#=Jgi;r{?bk z@P9g=b{+D9|5LZ`XdbO-f^Wwg_Zcug)%ZW{&wAwezqs*#x;}g${!h*471sY%;I|?I&=*4|I~Or{GYB* z{!iT{-{!wPGRm)SKz=6pKV6=`_rU+D@u2uWHS-4Xe>$H0pIZJ;&HC2(KQ;T~|J3~b z!}`91Q~l8~1O57H+56?2wFY<}Td#KVLeu`<)vH%ey}#sky;Dz2ZExMIL8|eY@%zc} zv7=HweoWT?jaxP(_`i#W4+{QI-SqUX!T+fnj>!5yb%FgoApTF?)jS~nPu=svj!CC~ zY%6}D!;tK}I`eMN?BD8*pTYn6cJo~LKQ;5;@PBH2ApTFyd_DZ1nt5>eKQ;Sj29~B8 z|EKfob9sm0|Ki5~sr!%1`aku6%iAZXeZ0z#H}cZX$!)7vdXKoIQ}XeLE4+u95A6Ee z<=*mtIv%$V|EK1B@qcROA1>~@#4q3P^6tU^>Gln>#{a1Yng?Y5pBgV{>pK+hy>4*u zetjnN4E|4z=feNRjsH{Q)$o7n5$412e`@>}{x5F)pROMdh5w5i|EI=3;s4^s|9P9Y z!vCpRzZL(d##7<{;>Q1}Szj9er^XB7|J3+C{GXcRGyhMGXFT-P*ZuafUhhSZzLskI zpB}Fv6T1Ze=WTup{}(s@FK+x_-1tBB>EpX5_&@dNE4n23KQ+D#|EK2s@PFz7w!Sa^ zPu+h)m*D@@_%i%o-1tAW{GVF>Pu2 z`|I(C zryBpK%i{y_e`>rA^Z(SW4~_qe8~>+XVUO1Z_5SY7{K$1j|J9rIhCBcLyHx-FlW)B7 zr}#e|55I^1i@WyEd*W&YsG$U)=aVGjQ2?isrfSe{tjg z)ZCuyYCY-4qw#+_9_!cP|Ki5~d6)Y?HU19&r=D*Z^8em`FXSd_Qo6H z|FoU+v*V{4{}*q^|HaMxKQ*@(|EI=#;s4^s|EZVR{2~0Gy2L!EoqwTvak>9fFWt)H zRo%DGT$P>wr~Bu==RXYoPkq^?9|ixX?$CZp@PFz7?SC8mpZbjMZ-@I{eXgzlJEF;; zLiNOp-wggwec9xDg8x%rQ||xNi|?Hf{Ga-FmkkO2Pd&%xN8|r=`_|t+iu>Pt_EUER z|EKNWt(_VCpL+S4)nWdhTK-Qh|EDfC?`P|m`|%g=+?nA2w4Hf>_V{`)u=O38|EKMX zcYPfEpL)LeKAW#vsGmQ6e(d$PP_I9W_wM8M*?Zak&w~Hc{!6Wy|EFH|nfWN2|EFf& z8U9bb!sY=o|4+?&!1%wo@qcPO9{w+G{GS?shyRP)-v27j*Ipm-f4V)qKHB@Icd_{# z{GTpA*Zw{P|EFGH^SbbVYCccm|8%@{_WFYVQ?IetQ+xmSF0u2&|7rUY^M3e0HOIHl z7a6@j^7$11r(R~~hyPQv9`}{^9qrBW@qgM*AQ1kW%T)g_n)~JpO$L;pY~_HW&EF-d5ri!HS^u<^QHG<^IP`$)0=s1 z%>UE=EBAg8{GWQ+$65cUUcN6o|4+Tz_P4)}@$=*M+uzT4m+a2^KiwYMK7af6rRD+g zf7*_Z#{a3A2Z;ZR+y2{|{qcX=&c7${fBHO+pTqyD@pAY-Z~J_N|BD;{r{?t@|EJ^A z_&+tr!~eyN|5G#X5C5m$XrDLme`@9<_I+opU*BeX|H1$1`b%v){!fkf#Q&*z{PBNr zk><^E6iH}e9S z|EDh7^=X*@r)D1D*5BXlmtVhaZ}RhN_js4u@$i2-{%Z4pH#E4;KAosLkIC{;#};+4{Y~|CKj>Z_-hV{doAlA+?uy#du>Y-=03G@HdJ;rAJpStH+S^uYI9wPoP zZv3AbKgj&QxS9W_#^>Sx;>Q1}S$`P+7dP|&)U1!o{6978rlx+LvnlpRS+n_&+s1 z691>}W$XLm|J1$h`G@~gbN%=~HS00s|J2O)!~dySZyEm=H~vq}{>=YVGyjtLf9k%& zvi?tv55)gHamm2o|L}qMKQ;6I@PF!Vc6sLisSE7q4ga@t>ww_@X#8K?_`gag4k-73 z&BFXYHR}iC|I|IrgW~_x1I&x!|Keu-Uv=-H&4d3__ZniJ&HSIbpZQ|^pIZJ;=htOG zqh#jsNs+eG%U`VMKIQ&T`_uS8b?^MNZ_4c+`1YPn?E7u=e>(pz z_3H=!rXox8?f2T)&pPywR0Lk3YD1`uWVf$N2hx$^Q*$k^cF}Jznnlb!*r# zb^O++ot)}Ujq0VkN7J+i?A1Jd`P}2@c44dZyrF`Y>C6Au@oc^7`1a>|$NyUY*yef0 z`{&MA9ANXN;_bQJKQDdxJ}uMFhg|P>P>$!zod<}wi?5G)bN^qR9DPV?du~@gI(_;7 zYFodS`F|g5oD=+CrAn28|5M`)ng4g}qS?X!C5I=$|9Klv#Q&)eJUr|F)Z8BYpPKb@ zzhC#DUtiU#Rm1#0T_4T-KlMq+RuA+4)F&KME%-n65j83&`>(y<_dlr0p~3(8cDsJo z|5bB;zo|?pPKo8_`kTB|EI?D z;Q!R@kN;D1ypMWCeOm1>|IfEuv;MD|%eUQmn|FiSHG}`tcINR_*>tOKZ``zA@PE4h z_<6_wsd;_D|EXIws2%*Dx<$QHga1=Evg^bDsZXp{Iru+yjjBfm|EE6gm`cgAdDr{? z&1;;P%w2h%cgNG}CGTyy*1K8V#>wyZU*p}fL9^ihbi7tgS_J?1c;)%od4<-@|5Nk+ zivLsd{)+$8Q2!`tXDJKQ$f@|EF$g z>zU*K)U9m&bNrtgkBI+^8~+zK{!iU1FFXHF&3sh+pSo9vcF6}noag5|qCJ_G-!KGi;t;s4Z)PO6c5|EPa_wNy8&b9|~hwn%&bT6X`$ z?@t5IJ1^Cf&Kwiw|6O?F8NvSzxA}>z|En(SS1*|{WOwm1`%e#kkAHujkiW~Df4^T} zf2a4rb2=p3s_gLYenIEp|8)5t7iRsRn)Q0|f9k%ro-h7Sjfcbk#f|?{GrtS}7dQS- zop1BN@PF#U@tu$ z$njbKrye$`dzk;HpO>K%y9NKJX8lzBU)=aVHTMtxFK+yw`YgMB_`kUEe`@(ZHU1F) zrygznt@%IoDD#2L|5Nv~>&O48@m}~pHRsR#zqpzIr|vnickqAe?&Es~|EKPCMUUYB z)III_i~m#ix}tmVe`@Ak;{W2t|EarPl3o8-oqt(jnE$8ld}%?L{}(s@FK+yw8h?xb z)8pO8{3rfT-P>*t{!h*A!T+i8c=$gxUJw7L#`od>bbUO(@qcRkApS3I{GXcRtynzS zk4NA4)J@*}eD}NJ25)|zDtEiiyVs{{q*zT|J1DCY2S|(tNFec|EK2r zT>PJ!`5E@#70tX9^MBgD!j5O(-xb?;biw1X{^XqVdwAoY?7Ic;HRko|j_TsQdjB7j zErT=OW#+#g=v&}jYCh0r6L>GT#{cR1@M53c(XRNDxBG_g%b4%?^et_?nFodc)Bbq2 zC3RbQm;ULm$@QnS@Lp$r5C7NhrT)Q3GJg*Lr)K?N{9oMoKlNJMAOELbW7miOQ?nia zr{?~}|Eckilg@PFz# z=Kt*bb8prMUUgz+zdW8Usdi*V+dP_fM;`9I)Ykv){i{R$^74NNbQqBJgysHEt@(fI zb@q7S|J1AP`GWt88~>-qZ{q*r#{a4DruaW~iQS%$s_vhs+goCf-HOE4m&O07=b8_||EcHMcKo0E1M^SJ|5JZx_b>j>OkD7P_=FexzUbSR znm4K3_F3VN1XO>+a|EHc|=il`F5#DpngV;9jIrjQyw#0j( zegA8-l)M*g+hg}{8}I2h|HbAld4FV{i}inX|IM=f@qg+MY<>&=PvO_^#_}?{_pPJ3=IBnx}6X6|I{CvXT<+`+xP4Ezqrj` zd2|2a|FnI!JwMGpdC#=R3;(C>+`s16yyw~F&BM*ncIJ`QHvfkyTh{+>TW>IUJ>QOB z;D6empC3D3zIwfRKs!J0rMBIU@4d*LU-&=m&-^F+pPJWWJAZHH1>*m-eYriK?f9w2 z|Ha$!f9jRyZSj9GrI;<8F0T|t@n%nQQ1}7nqm9|EcGjpTqy@eA$lwQ?niar^ZL) z|8)6cn?H*GQ!lpH7khv9{pXwC!T;&<_!|75dWFrq!vCpf+jjh)dXD)U{GWQ7&GW+l z>HUz#|EZ^&55)heKQP~8pI^M+x7&yR^X=vSPrbq}&-_0%^EvT> zW}nZzneT@G)8_;EKQ;4j@qfBJ{tf@9#=qhJ)Jx6#;s4Z&?ehTsPmSNg|EZbJ$NWDv z^B$T1r^YkdTBUw|rRKfxe>y+rDdPXs3$2;|r^b`w|J0iQr^YYh|J1BMi~mzEv-35p z<-N+D-}pamUt{+V{!gFJw_4->)Z6X;wg2|!{>J}lJC6tcPtEo_?iu3E_O%ZU^Je{C z{GYBL?}z_WJ9e(hyPRK_wawZzV-J0fd5nD>F|GQ95w=JO){Py6HPKkspA=C~932JgrFEB;T-`z!uW&Hcsvzy5dh3G@H9*!eU6PrYvM zm%;yOfBLU4T9?o) zisPsF?PdL5=KtybF0_ImTiqWk^)R&LpoR9*5wMQ`05{Gaw;X^sC=uQnfu|5MBVsquaIzqs*#>gDDB zFK+ywx@6Oq;Q!Q1He~&udTCkK|LOKGUSDS4Up?)YpS7+m+12NnR3Fs;S?@XPvh)9R zyxD8B>;I~kEMF1k|HX~}Q-8ExRki&iTN*Nw*qFkE^G9=MQg?RH^h~rrO=3gWoGO z-}hauk5aupZ$?F%KYF*<%v9t5bb02N;s4aV&HLg1)bfAo(Y8J={!cCcr)K`&(WlMN zoIZb4@O7i??>oQETi`u%OuJ-V&xPKD$Jlx{=Kpkg`q6QV)7x)ZlIo$4F7?Lm<^8TC z)zxM!^TzxAWyNxD))U76>HN+(Gwc7Q1}xjg<)&H0S$^rhcE&bNR6uTtIYtgpTMk8YbB zHQ^iYJ~nR=|EJ^O{qTQkJm9;(`_}hoULO9>A8(tliT_jM0r7uoyx@ec-)G9s8|mH; z|EFgC?E`N4A#>a_Bi#Gp|J3>Bby@#c&Cf6XPu*nIgU$2d|Ki5~sX0I9|EaqV zwD~;d|I|Hg{c-%Cx_iGm$)HpJGtCN zhE6-MNZqTm`OMA-c{86c{{E5qd~xT_1I+FJwSFh-|H`W{j|Tsz#^2%p)Xf{!3I0#r zvPr!#|L@9oX9Z7)Kg0j2@ecSuHS@yoe{tjg)IA$D5B^Wh{JQi0HmPXEhckoc>(r>J zdG;&43!1h_3QMo@#wX(cw13BDEfV~n8lQ*%Q*-<9e`@Bp9rW|HMU7vXQP|+nKNsP{ zj`{LBZ+sR0Py5sOzqn7VeX}?I0sp7%cscx^8n1@`Q*(X)kF@)MlB&-3_J33iqaX@` ziV{>rat=*Hcaw7lK@ky=jDUz)QB+hAvxqs2am-lES=gYqTvi)CnXZyWuZ`rd!rtiz{?8|5O@AEz^+$;{Eyj_iMG>7?+-d!kvt_t%!w77x5}rTf7uRjMT8m){e8#<^9JODj){AV#xpHOqe`@^O7cWkY>!b01+K%VL|EZZ5i2qZ||EckN_&;^+N>$wd zr5pdJmj6@B|3%w;LHwV(?giD||LOkdVe6aX|J0pq-XH!?-T3^o-2bWTpL4qVKXp@^ z4~hR%*R!7o*8f#kDOtk(pSs>zW!?X&>)7i*>;LNf8dk05^Z(Sf?R@cnv48a%?*G&c zYu9)Gr{_n5TIRXT|EZhRs*_xQ#?^88#?@=O|BK7p`y2jG&3dZ%KQ;5{@PFyX|Eck3 z_&;@1TW`MFq_NR>xe8OpWHjslYJa>N>;J0phxk98KRyosmu~!@n)!S9KQ-se{695b z5&x&gGvfbreRw?P|EZbhjQ>-&sc(M|X8upzwm~!Zf6>jFyZ=)&-w*$%?qwbj|EKP5 ze;oR~&n!&nbIy z#`{6V(kEv0d8e1m=r&C=-;et@Z=SLJx{EJPPXE{8!qfjXG;er|2MY#XTr~f0aGjy< z|5~=lasQ{T*Qv7mzgZ7oUbH^1tp|YrQ{(;cf9b~msoM-~?*31W|2uT{p2CAmhqzbk zI3hR6KVf$?>)}54%g$(g&c6@s$mq+~ZI71!)A8|i_&;^t*jDcU)CJ?(xc^h*TkwBs z=5xK!V`Cg2znA20$Y}hZ_SgKsbmRZj_%r;Un)QP5e`@?8{x9A5KQ;al|EFgC(aWbS zi}M+1m&gC<{=CGtVf8qnE#h<{GVF>Pc8qa=JNQz zbmRZj%&W8Ck3}=j5C5mz%ltX~U%K&s>Bj%5c|7rdYL18hOE>;6-T1$BfGTi-T$TgU;nr-?%$^7 ziwA!>BRa?Y;Ns2qMzg*+{!fp0CwslX|EW1Y{9n59e`?MDQ@0!2+WnuJ`GrGs?u`BE z<>%fJ&Fd5XPv_rid|RLYr*3VpSNK02kH-J0@rU@obmRZjcuxFZy77PM#{a41|J1E* z-sz(|E-5UxxVL+@N}bCl9k*N@-F--#>+9Nl zn7BOaQ`+~((JRe!oqy5U(ei(~Jl^qvPG`h+JRJT{kLM~o9{x|we2_W~%0w@+?<8fx2A?_c1&7N0|kLLD|KKi)WfBz4^B+vchnCP9h|NDK8 zj@!S<)~6lWImzgpDZee!?b~9{mlwzVcQjtG)Fr=0bNjFF^kX#h0S`C%J{oV@?YwU? z8vm!`b9?ZAx_z8K{!h(z{GXcJi~m#aFz<)|OE>;cy}`T^{!hK$yd3^d&3b(JKQ;5# z@P9f#{B7rUA4jjT@7M8vX58FUvVJc9FWvY*^&I>8#Q&-1+VwTQ?4@XYF8)v3SJ?N_ zjg~zX*T?xj`|hla#{cR37JTuw`#<#}o6m;-Q?K~4$p5KX4-@~V#=qeI)XNSXcK@fw zAK?Gg_=7p842xc5_m8cI9zEZ@huxOAJ$M$gB+-k^hv5HodujZidcJu({Ga;cU5DKN zsXyGl-|oNjV*9+U`&o}WdakYCivQF8A8*|0{!cw;!wz5n*Jc#Dzx-%p(fq%3GyhNh z{^ot||J3t#AI6_8d~4%{?*HE1d&vEt`aScC_&@a=n_q+fQ!lXl)BII5o(KP@?Mvi#efU27pBmqX|BJSt5By)c z?e<3F`S5?*ju*oJsqsblKlM6$KH~q>8?0IXSIv5a%>Pq=yza33KlO~~=J0sL_G_+P zX!Gi7N9VS@m|VrnX-@`dxo))YsoUJ=t>H z;JEyhsgLk{iC%cmIQM_r|Lq$Fn-9A-Pmj;S$-R@gzf6u^KJ_9V-{{4U-H{w!>z?Re z*3Pl@vS&oE+_)~OIq1RY9S8Qh|I_s?+rQ8KU%Hw9r)E81n{OJIXFj0$=V-hi{!iyC z|Ceriea+L)?<(^wA2#?PPp?O-?dQW@pQBgVd_er4_MdP2xBIWf8NK(U712xW=L7#2 z*Jq9YQ?Iec|D_xMr^W~3|I~Oq{GXcjzwv+R#{cR3*pB~8H~vq(&h8)c_0b#c_1XM= z^ftSG{GayUV6Q*;KlK*#e)vE2Mw@Sn|5LBnw#WUSdYR2b#s8`2ZQSAhPxtqN&AZ(H zsTZ2J#{a1o+41pz>NjmYPW+$xUGv(^|5Nk&kN;CIwAV}gpSsX~e(`^5-X90{s*tbu zYy6shK8s#w_dotm+j&1{{-2u5-!tLdX#W1D&-GQKndgT8OJ5)UPtE(Eeg2I7c|O|b z)94lU_~8Gv|Lnc{nQtB27k+NVH^1GbZyU6p|zn8if43B30=?ZN|Ml(+l|EK-AJpND3`oQ=< zHTNI>@Ai9ox&Om2;{VkA`;Ga3+Mn~q|7rVLo3DreOE>;c`)@7wf9b~mskhkY1N@(Q zE1wU{|EcBw)c8L9pYET{=8y4zdcM&2KYv%;zuWEc!T;(0-eNzm$5pxK$mPxZ)j4-s zM&ti<{I&La!2Cb;8uNQ?m);xax6wQ>{!iyeD$J=9$rJiv6FCzk0_mpZ}+39^gamo`~yT zZQc+6r|k;cjc>#Mr5pdJW<6p2pSqX%IQ*ZQ^@S(@VRtm%4*#d^csu-G zy77N%j*tJ-?dSOTKXv=!`G0C2??LAO)Lb6_r)E85{GS>h$^1Vxw-^7X=JNPIb08_VpZ1skQ@1Jhe@D8O`@eMK|Mva)Qulv;dGmki#{Zpj)}`+MTKBH!>;J0r zdlb$8Q@6Lq|D_xMr|#CXmis?-ck_VwKQ$f^|EF$e^F;A~YUcgn|I{73p6~uo&35Mh zshJmu|5JDDR>S?Dx|5NAHuIK(Q z-FH>KsvzggCGPw1f4`hGFfg#-m(ln?ZO3cj|I%G~#|_ckUv(DW7~RvpuWs?iP0`)!RCoWU>zDsibN={0 zHS_H7e`@(ZHGUEQr}N?VZ886+=Jw$K)T}3r|5F#7d#?LG9goKUsq39z#rGR9>irJUX z?(F$}`3-7h9FONm`uN$M?H`%PnchFUyPKy-Z^ys<-#YvCB744H_W5LY_WZ=`&h~r% z&z&_7@Wc}{eMWXOUoU-o&nuO=f29*L{U7Ip|GR1bI`@BgKm4B>KZpPOZ1!6Be|SIE z|5g9N*1u)`pSt7;$GQJgpYn$j-T$fad(8jS@#X*0jsH_~dwPvL(##XY|7knti~my} zZSx56f4aVtjycNxpSom;qm$Mrn-46$y(d_goMk?+xKBK;gs=Zw@!R$81M!l~|C@8_ zM)!LaPc7;5|J28yQO^CJ_CN0Q)7<~5%aKaumx&KqMKlA_6jsHvcryFn2 zX#8Jnx8pPaPmMPmd_}75{P2I;&h-uZ{MP8!70z`3r~9MejMLr!shgEK)%~Bkap{xY z|EY6NKH2@Bx|z+d#Q&*VpK_}EKXu=8&vXB$X1!JXpUw~e_U6^sM*HUlTmM(v+cs?C z{!f?3Z{7dzNpXG5XS?I1Bh7qX{Gax3TC-^WpSpp)zv2JX@_%aP$Kn6djsH_~{rEq1 zef#`^|5M}f@PFyX|EX&>sPFzyU8`XO_kVgmvOX~WPtAJ6_&;^?rVZWysaX#g|EFgD zApS4i_&;4A+wp(t#{a2v8|S$HQ#WhS#QmSTJM$O+c1b)wT`s7V96aVo^Le2`nSrsL zzh{_Q<>F{O_@25KWil@?$)SCa7Zv3B`&y)B+HSdr3KiwaVYhK{~ zPhHp6=e_EJKCzwo!_5EFaZ^wA9!nnz0o~} zHL`=hyP1A{!hne{a5^-x~t8H!~bc2`M-4I|J3q-YWY7k>lfqy(*4KRSH$(P{iw&5 zXEgp#=hJUkWA}gRzE?D2{f5HRR*v%DH}xLTgx~LEwEg}ky4Uc={C+5!{q65Zqw$aS z_oW$azkiBmo|*l9YIN7DTl@S!ozJD?+qnNzUt;qL@qcRk8vZZc_V=^V_&fXi+Gyt8 z4Qu*-G`?@eIqzk3)l%<9;~nq%@3*7zYhQl;Ry6bXI&6M3qhFo>Mn>cRbbidk!~dxV z+2!$ndi(~Om&5<5@pt$?br17(_&+t*Uv}wB89nLE7o%Bk7yqZ9S9~4*PtA7xU%K&s zYUb79|I*F;KQ;5?@PBF^&l~>zWL!Vb-#yr+3uXjVr5&ufoGfEssVs-}0=Hk3_c{k>~zT=hJC;zOVnQZa=g|(z4ovu|M-gpFQP)=+>9# zB=|qwzxA$Y=KfFJcvMUGf9m$5^4$NaIY0cLn%58fU%K&sYUUL(|4+?)LgxRe*^d8H zw;5gF{!iW1UeBtQx;?fxAJ;lL;jgzvx0uk*{h#)y@qcRhKXu!QMf3mE%mc*#r5pdJ zWr9-05AZabz?(yhTIg}2qc*uNjD*S~UN{~bN%`oZr1>^mvA3#MT0e#{Ug_q9CKsn3)&-Df8zZY!Us5?SI>h=Fz*&cj5nZKCHim z|I_)fJ}>@Hz0=nB#s8@fegCujKVANyc|81|dRMXkvzZ_6DR-I=!~d!AjQBtGI-4I? z>9%Uo8*M#c`+hf?^@Z*G-{{@8-You4m)~Xc`|y8i))U76sX2f9{yCa?fA~Lb*Ze;< z{t^GD-fG?j|EFesO#GjEvpqiezjR+U`=q!(@OSt>-9OAz#Q&+8w|M{a$42kAd4l*q z9dEn&x$Qq66}`pg4S`*YW>i^db- z|8#l$9{x|w{5$-g8h=%K55)P>Ntt`2xqUXTB^v*={pZ`GS%3D1 zRX0a3|K#(e%WIRO@d5ZhT_27AQ{!FizoVDh_rqo%qFH~{W*)nUJGXGEa&z!A$-2bUx-@L>9pZd8KYu*2;Ut74;{h#{9j~BZCJGc zTj=ZmrW^mKp0aG6`@eMK|1eoMetUPpRU5Xs|5IOMeg^-io@IU!|EGRp59`m~8U3bx z-;e*(b{hYuUSvK9|Cet3pBjIP|4TRiPrbw*FY|f}bpAXa_@A2Ri*0YAX1*W(FWP?o z@qcR8pU3~H_uBIx|EJz<$H)JvH(BHV)LU$SJAO3&cF{GDM&onLhedBRZ*y_;4>KD7 zr`yN8Tl}9IkAeS-F7|)v#{a3;?knXo}basQ{DyT*K~&Hq#1_smD`|J0Kv&U62# z&Tl!@{hzvXy=UG3sr$ElgU2_HH@f!|?*Fv?wvq3+|5H!Cbs`SbpNM*=e}!_ zF%OT+)BXGWAW=?Y_&o|6~7Uk56&`r|mzle$V}%dhv!e?*G(V4({dg zipy*MpU!95-aS75PhDv1apV7Vc^dzxUTX81@PFzR_WHp5zi6BPhyT;h?;7)c_&>e= zto!sc_kZfu2M^)5WBbRpJ}~}Im!D_z0`Y(9W%hY&+&OEaSzq|5W*egMcC)%|$!Pqa z&X3nK{GWQ|zE9l$r5pd3Zv3CFf4SX${GWP-d1CyZdfU#u?*G(Vw(oZTr=GWAi~B$I z>kF5d=l(5j|FWlF!1w3t{#h{dN&J8Gb@$J3|EJ53x&1cg2gmmDci!&)PnVxC^$z!c z>Z>1m!2O^4hFLS+|EaHj;u-gU>bu^2*ZrUR)`ctF|EV9@vL~^>pUBty@xyyR=krzc z%me19%>QZo67x~`KlS1RUnCX2tC+9P2g__d-4Q=kj%J=8{!jbQwbu*$pL(9XU*rFD zKD>Y9|I|zE^ECcX`!D|dYxjR@{5Aeh`_HlG7yeJ%=i2(x_&+uC0P%lnydM5fjc3IF zsqudJKlNtwhxkABCVT(J|EYO>#Q&-B(f0R0aewgsjsMgA#e78kpL&bkKK!3PuhaNH zHS_)Oe`-FD;s4a@?e7oP&hHt$&i?+u{{0ij-)!6Qf4aV{wjMYBPrc0^AN-%1^>ppO zqc_;&iT~4f`qMp^#`WPV@qaoW{(Xf1Q?tG|{!jnDqw#-gKJVcF(vAO9Gk+2Pr^XlJ z|I}PR>;I~`e%Ak0ud~M=|EK2hVf|k<>+Q1subTOg_&@ayJ3r?CsquXHKQ*@p|EKo% zWAlINE$020|Cet3pY9)C|3*ABHSS-YU-tb@Z0GWyR=hhJe~kar<(cPKdeJ>`eAf59 zu5eoP2K#%DgNvtUH2zQLBmbvnfBav%@qg()xaxuE?RyR+ZPz>)y>Z(v_kY@d?e;zH z|I{08{b2l`dZBH{|EU+*JV5-PdZlfDbIW5Hed@MZ(Oe(?Pxr?<^M3e0HS++O|Cet3 zpPKc6S^rlp|EFgD-zWQ@jq9U39DFYNqqXajw+=lY{qFLj`F}e9g*Fcm|EHe6WSRRv z_4^AKy8rw5zKh(iKJn5^?*G)!JTTq;pSrcpA7K8Uem_{FOik>Bj%5S>G4`r|xOK4*#dd^Wp#0ctQMMbn*PZbmRZj-3Ax=KQ-$M ziYaYb$j!B_&@ak zn?H#EQ{(aQe`?MDQ}?j@2mhyL|KmUXJkF<|J)ge*>5J&@18OI0j`=FO*T8zo>*c7)1L46KXngVUzhoR>W=-2=KrOe z`G4u|S^ww!&nJy=@7KZnApTF?rFUIl|2N(EzdFwhcmLO}Z(a9)>elx2%ltnz-VXn# z?%K14&;L{71DXG)?$EQ2`@iU7|EFdiApTF?wMR|&f9fvXYq z|5LL+{!iWCd>;N!-KWL{?*DW?cuD5}sTHbfRx4f?Zt#NsJYU|rF8vm!`bN%=~ zHQ)E+|I~Ow{GYm4&1%W;?~ioP8s{h9Uw%hyXFW>h|LJ^KKN$a~ZeyK(KDDiuHUH1N zXL>sxG~L)7O{X+3Wdcd%f)K|9?CC z_+@NfUHbf($CqyA<>CJh4&LVekNJN1KehZ{=UQ9c|1l2_|EE6gxZ~Xask#2kmOK!b z$NSanl-c+{9iQ#xrr#IGqaQf+NaF`jcxpy$FL~^7$sOk&>En++Ci&+Z_r~_)jyl@? zpU&s_V~XbgsZS_zjQc-bKaKxWm-@pA?*ArVx8408>&N2%PJLsC`@gfwpW^;c&3wQA z)SDjL@qRbXnHF8?^fTQ5Y5yu`R&f8PKC5DR_kYj+&rbJ$6)T^S4Bc{fT%LJ-_&=Qw zz7GGVKG(c5{!d-aUVrd^>RMILcmJ1e=KrM||Cet3pPG56_`h`H|J2os{hyk7fcQUk zt;!YL|EVuHtGxR^b@S89C-Z)q9Q!vZTP7))9O+tRPf3QHd`oPvcJfK?|8)OVD|w3h zKXsk5r@Q}C*E{cg_kZe!)v6~Y`d=T%!{6cm;(Qtx`9C$@FERh8ZdI>g((l1Z(ahKV z)3aA+H2zQ5r}=;CCN*j$FRz&p`=4v?2mifmd~{X&{Lt;oanZaV;{SB{`gLmf`oC(t zApTE{_rw3C8~>MX{GXcl1Lps!@ooS8>d0vP-}fJkh{pSUwq$rT-f!o|VbSc5|I_oC z^@j0(YUb_X|8#u~%yZ`~yew{SW1G)+-@3ukTK`x3x2V^^{ht~ykN?x-)1qb__kU{s zz5xHH#{1#_(vAO9^Zr*mZ$R_~b?YQky7rI8OYXS%!f5IGY2{1%`oHQD zPPavFnaPo4M_tt^L?$$s^6SM>9Wf_IcZ)yV&}j?*DXs=J(wH6*u1R z)9W|K_2a=>U9l;n-TxKuk1uoomumc;G!I*8f#&{a>~GU%K7@ z6<=TPQN{kRxO)t5;`9G>|Mf7x_uiLF;`Y<-|BCOg9#=Fk@_)tMeP|B9|B3y%|K0y- z|6$FF{9kc*9#N3IwRB$L6;rSB-$&uGHoP-8y0y(?v)@le+pmTb`}@^6e!nqo`TN$4 zcK=s=dwPxQP~`to?f$R02TW*F7=Zv3BG{!iWA)?dZ{soB2cu|Gz4 zF<;nZ$_vq~PmBNS^XMe^yfpq#&HOt2pSttdHp#~|o{7uz{677(r!yM=r|a)-`{V!A z-OTIZ|J1EVw{icMZv3CRjXnPOKXu!&?cD#VyN~VY{!iUyRJ-Kn-VewA9f##52UQ!{TA|EJCw*4+J{y7_Qh&)eqzspbFF@_%al9{w-g_`h`H|J3+C{GVF$ z|I*F;KXs0ISp1(_{!h(%zh~^bC0?KCJ@4HVjrV)x1I|v_FmiQ*X7# z|Ecj`_&+s%4F9KQ{YLzs`k?tN{Ga-Oc|ZK0dY5f)cu%wFowgnS7u&!6#r>ap{}2D| z{!e}I$G;`Xb@gKZJ?8!Jf4V=mo9AQx-%q2iaQ{c+|J2NS8Ee)ntg z?|+?_(X;=4PV`>$fA;-wM&tiapr+G#EU%K&sYUT+t|4+U7n;+c&sX5=i zD^HE<+h+S8zqoWX=f7ZXspyS1{|^7B`-8^+MVl|g|EV|G{eQptKQ&&m^^?a$^Z5Vm zk)xtFd{gBAbbf1XehdCjjX(Wt&flY1zq8A0zZ_}veE2^zVeSK254zH{?=rUEbHmrs zt8Jbl{!hne{ulmF&HBv$dTrk#oj>yvM?AeNn)y8VKW*pxUi_b$^?C7sYW6>V^r~pS z&z~@8Su}nM|EKGx@qcQ(+zpH7M6a^jkN?x{#Uoa({BAVi$n%XzPLE|J3*w{GS>> zga1=APi3(AKU;IyedQ9Hhr;|n^~bB$xc^hXvuLsVKlSS$e&qg7{rnqm;@1|LNpt@< z&A!jH^)wf%?|Jb>U;kHq+beIl|5HzU=L5XmLT0ex|89SGj{86LgNs(U|5HD)c$ND< z_1io4yZ=*vWb?7?zvFmwZJrJOPupkjVLjoh(H|fDn)8qIoonC!o6lRI^IKr=C+54N z*V+4x?H`Sw;(ywo^_gvZ3pLM2{GXcjpz(j{w*6bG@f-L*^(K42!vCq)m@l;d&S?DK zk?r5Q|5M{n@PBIj3jQzMc0SSg8S_}tYt4(8-;7>w-oPH;jK=@z{#|X}kNJP;X8xaA z{!jhT3-jFnsV7`D$Nir=zu+$Sf9kG{UvU4Y9?J9f@%Hx}-Uh!nn{6Fcqtof|S|EX7h`lJRpQ>Hbgs;l8gD z`}`N%=b5L%|LJ&(Y#y8a{YdmOdp)wxm(l!v0RB(=^Y;PF|4Vn*=julDe8c}~JB|NS zvz|5nFWs*j1 z`9Jk$`+R`^)8}>hKQ-I&e`@9d;{VhuzWUnzU%G7;S#0OuGeej6joxVf@14~bMsvJ> ztRE1~^_zW)=Ki<&?9r^(i~rO0v7RyhPmPDO|31?8c;Nr^?>Qb1{GXcni}*h^^AquZ z>J9e%!T+f@ncv6%skhks7yd8Z_&+t?5C5lTo-O`QE&r$9Y~B$6r`G&G^%lE4{!h*M z;s4a@%@Z>JPtE@LzjT+Lb4N7m`_4RbYTREN?e7urf4V>Me{JU9b!310dym%_+#SvP zFaA%*r}2O4wf6TB_&+u4`{Mu9yX^Xy|EFf2DgIBr-d->9e`?nI#s8@{S>ylItoO_O zKlSphyWRh(SKH??{GWQM?Z5o8NAv&k@DTTJ^q3(tqgQXU^@Gj-X@463r)K`&_1hnh zX8zxy9Zy6rGvC*4*OM9j=I*DW@qcCZJ{`?Gz#H~G6TM_@k^j^6(fB_#^Z)RFYR&&s z&s)CA{h#{dr7PV3spl3hasQ{=|LR-sxc^f>``C=6-!(7i4{dW<-d9`hC}@>q-fGe- z(RG@iT;%_Xf1lc+&jmjJPruJ@)vIn&>$;Ef_50Pl?zIy9pIZJ;-Q4Dr+3#Otdkgb^ z_WRlBmgbS}+c7^n-@McKuNOqO>R&(U@sEYk_$U0Ij*p+i|3#aB!~d!AefU2$p6-X2 zmgc|v@&xyHc)iUZEsJKo-uG57&*+Euu83xS-^A}$W^|u_t%~OOjY_Y{=+n+w8;$S7 z|LOW^=KrM||Cet3pBlf2|4TRiPc8qKZv3AbpNIcb1O_)n*Evo7i}Jo`G4ug z|EZam*W|H1`QQIG-u)Rp;MKj+_`jt0{v-R_{J+nJ9*FK@^Z%Azb1=HAdA*nJJ`~O6 zr#|sXMh|=A(`ar_`-PunbhS-~qx+c8!~f}gnb(K^Q?ouX{!h*N$M`=rJ`(?@#z*4+ z)a>8!wQuA0(j({oIa>Zt`^*2SSw9&6mu~!@8vk1AK^v<$ojwPZas_U|EckJ_`h^B|4-e{UJvkpYCItG|I*F; zzjWjO)XWcL{$ILT|5x4D&IkXe?ql8$|EJdczjWjO)NR^S@%4Xoe>7=Q*4O`4cg$LE zHM{wKKJ8stk1gHV^SW4X7XSCb-#2IYKQ%rO|EI<`4Y_@6!D*jva_>ju|I~c{i~mda z@Gq_`nDW*}_jhccw0T@c-#LGLG@k9@S0+TaHsA65LsvyNs!`SbpN^kfzgDtf#MQCA zpl*X?ZSP4LjsMg2Bj%5x&QEgYCHq}PmO28|Eckh_&+uC{_ub5Zni#M=f`f2 z&Z|=`xoFBQ(ag6UF?Mn^-^b(sba}q-#{a2v%oBDt|EFdiApTFy{fqxo^Z4Qa)ECuh z;QmiNptgAj^M7h?5B@LiU-NwUKQ$gR{d~&q?0I?F&GRjN`RwNW)7!H4df57r>EmU0wnxl9UiR(9XQq$G{r`XK-@AOaU(CLJ+4pC* zFU;=jd4#{$*`6=k=Vi|W%wFF&`|{ac`h-m1m)+UNXI@_V{>1m;|5_j3>;5mX&G3!H zcX6fRyZ!a}7#m;s&4ouA|5xUd>9HOEmpkf6AANL@|I_hGlqli;PuE}W_!Hd!sn0&S zbn?(M_bwja=74*@GN+aD^?(2N>_PW=<ej|5G=%d4Kpn zb(PX(-2bW1Ii;-oKixm|&NoNaNjo;e#-i^`K>(zDtr{mSN*H`?Xn)!Xq z|5N)sR`Y-A+#0pr|EcTMtmXbsjVJu=&55x;@0Y#iUlol%#Q$mkQ_P>^|I}s8_u>E4 zwQYUm7k;@in)P3QJ?co~|2myAHn!u@@PE4f%s>6H_UPEodc5sgjLK;IpY~@v{x916 z9{w-g_&+rs5dWvf53bvHMKtd(_&+_rnMeEO+e6~|YuI-DpKfo%+-C0o(rv$QitV** z{rbjV4~pjV4gOF2=hvz4{!h*PMf{(d`vd={=KT`?r{?_v|EI24zq;c-MnV?WJ~9s8QuQE9?`XH zR7&O#=^kCKOs4-%N*$f?eo*S{ObU^8$hyP1A{!iVt*#D`! zo6o`j9qF8;;iO%K<&U|^eIH(}&t*HK^KD)i{!iO!{GYmw&CkOBsoRb%NVb*U8qNH! zpZ>Wyqfh;2Q}m$mt&)a2HbxJ;GT+z#jq@w^f9W1_{`w>5Z`+rivM!^~`E5-!-thLX zS4VfY`GKEpTNT~M)&p)`xH6;hf4V;A1v39n-P1fE^Z(TNK>VL>KaKxWk9}fSg z?rVOm^hqB@cN^b<-;YK2xT;gq^Yhu!18sd>=KtyTUR3P=)Xcxb|Ear8#8bT+&362s zw$u1OHS-7Yf9b~mMHlFWvaRbmRZhjsH_~ zdmbC}d`ACQzvrTvm)O7H*=W2U{!f>e|5G#X68{%%j~D(=&AdPSpIZJ;jrYUPtE*7{GS?MiT_jc`osLcbbtTG?eYBSVC#){ zn>8hx`HL4Fb6Yg?{qTQ!zR~vI(ai6||7kmo|5JCd=jYBDlj7%z^?mJk&(Zk5ek~_N z=h^EA{!f?B9p22>|9$i4(eCkvKQz?W|5d;E^h~~=DpY^<$sWGHist)k`+h5Wh0Xu4 z@4uq)3;4f5`^LB*r15_`-fH{43;(CaXW{?UYs^pK|I&^BQ!{T4|EFdi9sW-(|EHG! zQ{(&af9b~msdt+%!~dll|EI>wG5=4!`-flM|EagzcKn|jANS$JI?;H*I;Yo;`-k;x zKRcynMn869^=S6T|LOkRV)O6tf9kEazA*kz&HO?9pZXK?e)j!wH2%-NUyjBf;{VJ< zxktqN;s4b8e)@az-PUrkKii*QUpAxhf4aWSHa`&mr`}}q@9=+W<`?4s)LZ`YH}`*P zyd3^dy`k9usaZc4|Cet3pL)fgfAIN#I{)S0{>A;Ddc8eg&P)EjNc+<>e)&0it@VeG z|8hRmMqvzSYw64#+ z6aBG$U;W_&Z$vLMkJP2at8qN$2hINbAEQ6A>&O4;_;bw@;{ViqKac-Y^ZhpdPtEuB z_&+uCYVd#Rjpq6Af9b~msagM*`G4va#r{vtyi)t`*p8<$tFg#t0=oBPy+fOI6wUgb z%>UE&cdVKJr+#Die)oUs#rAzF{!jhk+D-2N)OfyWC2Pg@M_+t7vGu#7U%u;3_kXW^ zex>`s7i@kN>;I~+n|!_dKlO-lBU%44wl^I%7*DfM+iP9iH!+_RUFXul?*EvvHgd$> z1&yv4hKF0I?mX^#_kU;HINm*AyHQuW|5Hzxc!T>t^?eUK=KfE8*R1E=|EZsOdk%gs zj(^*d4fwj~hqfNX>qXBnA87N;7U=vR`Q%%>eRo9jeLMb7=gWF~{7=2q=JVkH)Xbm4 z|EWK==O6wr-S|KCLic*-MdMTPf7*_}HS3kp_&;sO!!EMBj%*{$9K1GxvXLJRts0t@VG^GhbWG)QP+3X)JM5LjB&Ge`;QjSpPTO%>Pp_x69-I)GO`s_&+rs3;(AsG|!CxQ?D|Ag8x(FbB3(ip6bt& z|Jt)VdYR4dyYIXG(J$}XlbrMKPoiHm&phXpFQVt${8Id%j{nZ`HSYh^v)_8p{h#iS zNA7!w`Ma_IeM2r|K5z6*J-WO9)8&sFdWri#b=e7{-2bU3O`PcdPksAsMf3mE!|s{t z{!cymg=gLWsi!{sjQci714=l)N<)YkvT z|LORw?~4CZ%m1mFr;7hmFSpkp{GWP-z5d|;)Vx07|J1xcpHj17oFDW1F0J1H1k;7XPR1tF7^W>1O_)nt7`DKYc!DeOvqY zM>M_;{}&mO(l&iBm5mqs&R@2jSlMRR-1Hl_M&_kTLxIy*l8PtANk{9n55zoVJQhyT-d z8vm!>Y`zcwr^eIa|J2LO&*A^n%wxp=sqyd3|5J1S;N!jrYU-xeE#@(z&#oLndjH) z;^`Uv^~Lu_@37A+_Ya&A&3e9#FS#$8^?&zYa(_nOG3bG4))TIN>4VXH{=xt0_O04= z!2O?^{VQJfNbHXX#Q*8`uC(=o@qb5pPjc$zk7e}S%V!=jQ$ zFWa;|dFzTNGrI4vr=knZ|NUdw(;5B3@MofzZrGS~9Pw;);o5b{4ApSnrz zDaq(wALQ%zqg{JdOS)X~VRS+7n(qI!y=9LJ-2bT?^s4If|I`g_ejxr&jSs~CsqumM zKQ;6J@PF#|<^l14YWx!ZPuev)})p{K%4M`9JMX z+ffBc`ihpj)1|5I~*_`h`H|J0o>Y2fq!(vAO9cevQr z|1$rlW`F#jTK+HHJt}U^|Mjlx-Q(foCe+;)jqiJ?V0&~&n{S8z)8%RWpBlgR>(#qr zfBLkkyQ5j}7XPQ~qw#-7+WeIHKOL`^`A+;c&3rukpSrir&l_g`PtEz{ zRr)NhkG`zl;b_+1ozm*_jQ(TqFQV~(%Z7fL(VtKHDjGjn;;yfw`(E5QIe*qS(ei(B zdyD;_n&UJ7Pv=WB|4+^F@qcRWKm4D%bFu%^@j98`!~dz<_p9grFWvY*b=N-i-2b(G z?mG8>%mc*#spbFF@_*_sJ?gmsQ+MuO+voqOnZJksOE>;c-KksA`oHPM|EZZLi2qY} zv)2RspZenNb=?1{2Xrm+e`@^So()OClpn9n+j{Pdg7!B5Z+gF@qVwAp&HvN>jdCjb z`oHSV^)lzLb*Y~@e~s_s)8Aiad#G&x$GkZFpS+2$7x$;p1$VaH<-QMZ^vldK8IAwb z_CDsV@PBINi4FLlu?0Vu*y-Mn#{Wgz`f&KabmRZj%v;0%srkMb|EK2mF#k{2$M^sE zKW*<`zlr-lb+>wr6a1f=@5AwbYUbxn)L+ne`@A8;s4aE=ZODP4{FrR{h#`x zdX3!wsk#60f4YA;KK@VLyGf=m?bSHb-(~xU+`|--2*O=Ye`)B*R|Kk7&-S^Q;H$E7R2W0(UZ9mrL2QvRpebh-s{_o}CpSd3_Ve{FT|EE5;Pa{s3;Tehsv|7-d1VfS`tR4D87|JLpM+&y50 zv&*^vQ!~Gh`G4ug|EckPzqZWm@yqXt?bR!kOTOuRq-)rGJl6l!^;bEoocljDzK;2S zYSstF|EX))`o8!-H9tQ&@820+t6CNJf7;%lQU&*a>bhs0?*30*v(lOF|J2O$!~d!4 zRxIo5|Eg=AS=#-dy6Neq-T$Q<|EI2F>m@V)PhGowS@(bH3T01o|EFdi;Rk2m9Q*Tr zbwaJ1qIo|X)cnS1Jl}gAZ-{1nT;~7jc=&ewU%K&sYL3tRKQ*3=`G0EOADRD`Zv3B` z{qcY5oZ2?O-Ta^W0`q40KQ$f>|EK2t9sieZ{9n59f9jk@jgx08jfrm6xT*U;ZEu&8 z>;6yOwt3U!iOwTq|28>A{!h=}Ryp%>UE=^yKUMX7tvneKPu=%lpLr!TI6;y0`h# zeKF^U|5Gy`7yqa3YM)Q>e`?-O*G%fQc>j#A^8Q}^w*v0}Lz8<(*U9=k{D+d6-Y?

H_m<_&;^4;Vs<%sqsJfKXv=jt=<2rndgQ7 zQ+FEMD#8D$ncs*1Q!@{+_mU0K%s-p>*7}Ub|LOekRrtSjOSTH z@qg*Y|Ec?rY3cqi-S|H>eh~ks^QZ0aHw&BWo#Nh)`GWXAb;prS-T$e(+dMSXzpF@PBIjCH_y{dU&4uKXtoNt@!;_Y{ysG-?v708`Fy4e?>E&5C5n0r}2N$SGG?k zY<@qQd3_HqcrUuMdAoOCdpDyuKl)BI^Z0(a?d^;%edSxx18sg_y^G$==pOCfi0*w= zn`C_b*P}V!184s!n)QiS-SS#I9(clPqh5{1_ubw1m1ySseU<-m^Z@)}&6hIzwQ?^; zcfYz-a{N($%;=HdKOf!Y>LUNApKlufr{?UEzY}XdkGy2VH)1o_? zcRZ=gJ<)i-vH!X&x`W-m4c|AW=#J*3)|EZZ@ga1=A|G~Z=i{|?({GYbt8SsB<)*r?HspbFD zjsH`#UhBWi|D_xMr{??4awirP+ILd^eHxyu^YMAn+s%{RQldphzk5{kX!$=KkH-J0 z@p$+@^*-}=tpBUVd*T1o_(S}k8b65toAJxl?j!Mo_&+rs5dWv%Yu*q4r{4aTBLAn} z_Wh6U|I}M;JN{3-?T4S;|EYJ``Qrc7+sxD1_s`MH>%;%q%ry6aJMH}Nf7+k*i}8PI z=I`PE)SJKl(fwb#@qg;Iwtg=DPrdHzzq+_{^kew zf9kd7;qZTI<`Lrm)EpoGr)Irh{GWQ6oe%y`?eopd|EWK=@0;;|YWyAkPrdZ(?~>P> z&WT=Z{`Qobv!nSw`-Y0|Wb|h?U|5&OH{t)(_$K_Hnt6j2zI!&B`E7R|dNP`ML*H$E zETj9bd^oz$zJFaX_x@;nA^uN~C-Z*re`!j*y~O6R%&OTp`U9KyHTtBk(eIo8Yx#Yf=)!H=ZQf#T^xI39F&`;<*6jE2 z7SY!{^nm-nQkPug{;>TW6O%^EDlAfWoH~j5Qqlbg3Xk-Tytb>{|DKWhRcppDk3MKWP#^Eu+n^Mc2G;99}BA$?Z3||7$t> zI`@LjZo3oD729e2pN`+=*$>?RsV|wc0k0R^Z(g~_{h!YF?k%6Y|5Gp6eVE(3K>hLd zL;QovZgbK7v2bsZ|I_i8nqR>Gso%2oH1U7xcWpgQ{GWQc?a%x_^-A+3_&+tzNBp0f zp9k}aEp`38{~SKy(dbn+ztVhIG{?L9qYt82n8(2X>3D1H`HlZeH~vq}d`bMDn)O=k z{PWcKzgcZhie6>>ssHu{70hi#tSSLvHzWb4IVnWy{nts6)9 zW2;_z>wx6%%_qn9jrU%`{U5z_)~(6;YwnKz>x#GB|LOSnzwW<05Zm#8_IO3F-m}mB zpY~t7?|}P1UH>BMH9MZm)6eIUgSMXc*Dpq|+<(Z{TYWW}d3!cLHF~}^{!f=*WS^h# ze`-EY;s4T&|5LM`FaA%>{AK)~dbM5N)`!p2>)&$wdyUa2t&d(~>zV(j!sh6;=5=P( z+#b#P<#lp*N6+1Pfc5L6-`lY#vH7;qZ*Sen{M+bx>oz4eA2<4yIrH)J(Ko;NjQc;` zpY5+4;r>tOf5E_u-T$epU3`)IKXo!}sQW+lao0|A|EC^$|8wsD)T3v<;`9I1mp}iS z`#<%Bw?A_Kr+(nWdG7zz)8GBj{h#`US6+Ajr=D`xboYO{zc0Lfn)^R>pIh%r@PF#A zlW%nYr|x*;weJ7){#o(K*WCZ9TP^U%K&sYUTyv|J2MY#Q&-Bi!B}$P|MX;$>2P1};XKRq73bmO+9+)qzL;{kvB@yTfB z|Kb01{WShhy=?Oq_kZd|>(;yfJJK6`{+}MdIm=hN|5LxSc)8F2OE>;cmtR=C{;zuO z+_}jyKfV;__u?OCx&PbUc!K-Cu3ZY;|Eco|PEB5VeRlrf%cm5rPuugHWa@$sqC437 zox?YN7~Qse^`yfmA4TW%td>;!X-;(WUKb?CA2T;P*XDbDbK1P<7QJdGYpczVZrR7Y zOwNL6=KtN>Wnpxue)W^FgBC@1>EF=(U!1S`HvFHO^#c(vAO9 zvtBR$PtAP2lK#7*eEyg`9GbH{9n59f9b~mspbFFz0LRG|J3+C{GXcr@qg)N{$ILB+WfzC zPh0z4G#(NEr`yl{x9+>Y9NBLD{ck@+%m3+kH2zQB=E4T<|J1GR=LP?#?%B6!{$D&k z*7!fQ{GYm~c|q3yjqX|G|J2>P*K+@-&M)?VYSs(K|Eb&cte!CcPu;#(jbv@N-}3Jt zd#igr=Ks|i^skJ*f9$`b`rMa3=<4m00$m+zcZ zQ(tK7=i&d<18g1){!h(3H2mN2OAomJqw#<0Znpj%{!iWAz7NO$sk_!~u-PwLHyR+wYwyS<##`QI+li5w{ zX8OPE`y;!VkCZyuxhHm+dcq@ACM#^!5L*E@i+j_4;#ER%g%q%Wl@k zO<(?Gn`f8qSzum7w5 zLxuA0|4#V!8~1=0lt0t`pZbjBPjvqm`yYFZ`@dfczHK z{a@LN6_Qq$Okb=nbM~3;|Ef*;&OIR8@qg-amCyF|f7Pc|IxG3+`g`K?beaF$9i40Q z{_ua=zlqHY#Q*8~YL+SO{!d-|v{T*xsn0#FwEI8x`KOn0|EI>+;s4b2E1d5BPhIzn za_;}q&HBIUI`()n|4)q%#Q&)|UgHB(GMf2++Rpx^cixuK_&;sOAL9Si^(&s~{!d-E zYGwC->gG284*#dd^Wp#0ct8A~n)!S9KQ;ai|EK2l2>+*MzA64s&HE|-FWv3BUmedM z*0>#C zn>((EZe{cFT0T59n)!MUKYw{N_YeM0*T?zc|J0lx>;I}-Hp_AUr_Rf1?*31mlau5A zPu;9pGxvY$HcfNf|D_xMr{?nbzjWjO)GcxvyZ_VcLvFK1?*Gz_|I_}=L&X0@n=i!w zr5pdJ`Lr|#FXmHR(+XPd`||5Nk)!~fN7@q_!n*3BBb|5I1X z$$bA$PChE*^*`IA4;p-N#`cL9U+VtvZ@uqv|JS`qbN7Fhcirv&kLM%n|Juwd_kUeF zw)ORY)p^|;`ue}>_7~>*`oHSNLt421GxOqJu*u~`>;I}-*?d3d|EUX#{hykD@88;B zZ*1>9xLH!>p528rUbxG>UzZ`x-T$dOUzX$kPtE$B_&+u4ckZ6Ft#D4&yWF=if9}7A zY>n=0K8^W*+MoG=_&+uC0r7uo)-%Qbr5pdJ?lY>j`#*JGTkjPAr`y-x{2BgFjUUAS zsWtyE-T1$B;P zG4X$D=B3%+$7b~OyxGxRu56dQUi1CvuH)J#YfgVJ8V~hNiFY#^|EI?bkB9$L_cjlO z|5GzxaKyYf;_}QFyzAB1qw#+DKkeURT!H()=m{;||LO7Sc~zeKKehZ{y77PNORlo@ zht2<`8~>;7d{syHf9b~msqtLQ|I^PajsH`3nAj<~=bdL_|MqsgZ=QTQx~KWdPIo;O z-QDK*;s11bt^cdW1LFVG{cZmz7tP9O{GZOR`{;J=|I&^BQ+FBF-u<5%?}z_Wx3=|w z@qg;PVXcxeFFp{>^Kae#_ebOZYTkHXbiweP~9?FHlP@$7SJJl~l2 zx3lIg(X9V#voxbw|M$ZE*Jm{TPtQ;JzjWjO)XmI`GXGCqV^{$IfmlpZI(&cV) z|99QXH@W{)zw_=}?*G&W4(@aRr(Sg66Zd~=`9C%5N#Xz0%sayWshM|V->((g%m?>* z>&#Es_ixe5Z2nm1avh^reDi%WxlH?LeARoU+eYKn4wq~l&Ad4LpN=p8r`~EF3;&mH z{GWP3nzE{5t%fdY@e%{!e|tJRkl~jnBjXsquOEKlM)YeE7e4C2w~BN8|t0 z+lu|4di!60b^jM#?ElpAf9eHxJp7+}ksXiue`@9h;{VjFzl;AaFJanE#h<{GWRLmqq?hz3z*@xc^gcvGs28f9lPjf9L*BE&r#M z|5GnEZ`u3I|144$+T)G?Q{(@xEBRlG^mxz*kNG*8+k^kp{yWU~;s4a^&-}l1sqriLKlLi}HTXaE3VXdWD-gZhd=CCk+n3pTmiRw4 z>-FOQ)Xek4|EcjV_&@avE7rLGQ$O~>`|khLeJ4(E|EF#-a)|psb;H2}-2dfFxyAio zm7A`1|EF$r|6T6?)WaUWAFr}VJ^Yae@NkPTQD>I8yWslAXSx4V-}Kaz?*G(7-g(FU z-`rm&yZ;;c(MR~Rh3Y%s`_TPgy77PNTiivHL&u=o{v{|5LZ^Gt>Q_x_9pL$&@iIAXl&zsj>;r>s(WO9Fhtks+Ev-N?^|EU+xob3Kj z{cYiE=4J1V?eA||>;6yM3-|AG|EFHFdv9`mrN?9cP3HR=Eqf|Y&qwATy&{uV#MfqB$9D>$gWUAJEo!k7k}} z%kP&(FE)Q=?+r2}EOEg}@-hZN>*|i^^9zAQzPW*cGy!G4g?a?oN zv=ILu{mfHO@%|V+Z0Jz;f4YBa4(p#>-|5G=|Edq|XRpt{#QArdG(P!k&flYNe(_o6 z_eKwzKM&s@J#wY3PyX{!`8xhvD>o$1{o|PE_ttJPFMeF~JL|W*|I_0)d-HDhe`;Re zFSxyAzWSYQyWIb&=Wf}a46SiW9PjOwYux|o`d_s5Cz=1Jp83&SK0oE_@tFDQt9-tS z9y@um`#){(cgs!g|I}B^nC|{hea&khy8lx@v3`&HKlPhi4!QqR&)JXHuNK$$u6Zr| zpSI67Z-)OGQ+?skhqs?s{xQH1quMe>y(i zZ{ibUQro{u3ZJ|()nB^*)A3jj*eq3S-*3JX|EKMH?fnY>r{?~~|Eckn_TSO#ZGZe< zY`6C}{GXcV7yd8Z_&+s%5C5m$ZqHZzpBnFn|BKsO?Ekc#{qcWl*5AedsquaIKlNtw z()d61I(t6j|J2Oq!~bpj`g-?&H2zP`{`f!bzkb(2_kZfOJNCQ(i?(@z_&+uC{P2Hj z`M-4I|I{mY75P8)ik(INPvBj%57jG-_f9m<>{qTS4l^cruU%K&s(HplU zpa1w&M&tilwMG6*A zhUor-nkIk#c4KrOyS?~7oliGgpBMj^Zv3BG{x9A5KehZ{y77PMX8xa=^=p~`rbB-xS^qcP_`h_s{;wJjSa|8r`MUpm**s0w|5f7w@qcRhzjWjO)EAle zWBp(CfNnM2|EZhysP6Os)Hyc45C5m;=X+${Kl8gyy0d6LU$Os-w$}&zpBitB|5Nuc zABg`;H~vrE!F=N0iAllu@^{+zpZ6BDwezd_KdJ6iC%JjbQL(*6tITonQ{w^fe`@9p;s4ake_{Tgy1UKaWB#9-`8xQ&bmRZj_y+u6 zx|#o{=JNPIHS=Wff9i(jvG9Lt)*HtEsafxq`G4y6HH+r|sqt<2KQ;62@PF!l^=l`k zYusGWX3F8b8w&qg(8oO6CuMGl#;Y;^Py2Jew|q4@w&M%BY`HZW?^a>{ZPBdP_-pSe z(JgA$N%pTg((TT#>Hbg0Z+iOK?*G&kE1!`}+I>e{|9R(Ea{s5tx09`hnSMTXtC8u| ze$Sh6f2A*<-PxY4S@le>SG#8B_0_MNIqxp}`m;UZ?=|Z;r_Zma`I~hAfBD(;_H6H$ z-P!Z=e(&~Ydpp*9OkW@CL8d$V`m#Iwc>k}R?JIeHrmsKS-?3h9dV99#%if;dzqdag zF5~#->(Y&{OZU+>Fc1ItWy!y~|0`kh_waw}$vHP1>2f8C=KpE`V~#l{x&PnyF5Wcm`y%gWjsHtG^Z(S`pZLFYGyhM0 z(n%+||5H~kd7Aq_b&c|sl9BDE$N5#OT*dw0*eic@ugJW5K0;=@<8Z<;s;yW{#e=SliDyhu?*G(v&pOrppBf*?`oC)C z@8SQ{l`EX){!e|*+2!5;spbFF4b4a5|I`htobCQk-SC`>3I0!A{hV{%|EX(LJ>UJG zy0-c8At&Dw`?Fpz{!iN*)~n_IPmO=Z|EcBw)V#mq|J2N%!~dz9*!w&FPu;0muKT}q zbt9V}i~mzMwE404KV4swX7=wJ^MC5b zO^f`W8b5~rQ{(6Ge`-7&{!iV!d2{!F>Yg@lkNJPG7eN|EJDx(ah)n z#r0X^|J3+F{GS>>i2u{idv4>L9d;mv4#AO265r}2O49_IUAdGt@w-N&~` zR!(^>y7Rc4M$N%a1*Tp;_{!iU=d`I_x>h5+v zf4b_)*p9#a!=NWJdUVIfqx+fvTib9}G+q|}r{i@T)yDmwy8Vb&KL1ahKQiC_pSoa_ zdAN}e#qGnBUfK7-jK=?If41ZQ(vAO9HyhQ${hvB_Y`*(Hb(<@jC$$eui{rN)m-~NM zyALR-%5;7E+ng|`QA7a|kenJC=&mN`CPzUO!~lqj88Igen8gSpii(KjOw$eBO?Q)X zP(jccN5P1W&WvH^|6FfzKkTZr*36pqeP^w+j@Q|{cJ10#UDZ%Oo;T`THqM*%kVnpc zG^NeTdE@tHjDOf0zqj_zhrC-_e?9C$?-u3(ZPuPQ9Y) z8V`v7Q{w^ge`@?+mFYM8>#wbO*sC7C$y@XPw12&!N&lzoQ|)s5_u%yh=G&S{!QYK~ z`%b=p@_ujW;^6-(o%ulUf$R1r=l`i$|Bm^8YWxB7|GaJ91O87f{}*rkpYC7&Pn~D; z$MApZ0`p4vKlOU^SolBn2J>3@KQ;5#@PBI7-(~)vTK-SXd_MeNyzzfJU)IOP|EYJH z2gLuWKl(c9|J2)TeO>&YdW+2i#Q&+8=ZF9M`S}Ne|6_h2{!h((KIZ?$oB4lg=J~Py zubO#(tpBTCWA~5$i#PsH&GC=wT;9)To6YlE*zP=U&KLiu{dqjh|5MBVspbFFTwnZO zyzzhPGV_7V|5KNIk@SD+E#}?uf9lQVznK50#)FMI_b5MK*6Xcw<`Ld2%;(|%v_Fmi zQ?oz*PtOO9|5M}l@PFE$#{a2#ec}JqY#;O4XMTH*w{O>;ly1N2BkyJQdYxIi-Fvyc zp3W}V>|JQv?_Rjxd!-%k&mXS#&a=ml|I_{Fn-|3Ysq@Si;{W1}|5M{@@qg--hvxsO znb$Xe^oNJ<&wd`u4}U+U@qfBr{Cwj7)J5hG@qg+9n^&{2-K*Zr%egQy!5csLNXB#C zc&cw|J>`uTtTN+qKVRniJvI3eZ|3{ixqCBj%f9>fE;0XSvw*zueYO^$cd^Y|skL&b z_bT%}f4p~@_p+@!%*XWfp0j?ld74h%FU?)Z{2}j=QzkLb$h*dsgIFKYJF@Q+?dRS5 z#Oto)=hwT^y$`S+_i{6h!8Q@5VDN)8jwm%{TF#-Z$rM2>wrx?}4>@ z?9WRP=Mb*Pd|NLQ|EK$3xhMEM?`8IRh5ys`Jo5_pKXvhEtmkU;{|;TBl0SceU-V{v zrL7m8rTe4pzrA_=+Vx3kn-AyBd_SA_=FR$yc0PXm^?&{=&yV+7^If)nvv;AbFN^yk4?(y%#@pL-2pQg75*>Y_&;^&uB87{<3I3!>bd4a@PF#*Hs1;V zr=GKBQ}BQ4G0(pe{GYo0BTohYr;f7Q^7-kvkFv9Z|I_un^oCKv|LO4zuz8{QKlQUV zKM?-qi6yX(mQ_IX;tJ9=h9G_lu3-W67q1plY|pHTKm@PF#5I}Zf^r_QtW)i(~S z=C@zEW1oG#U+O*2J`b-ORnvQkc_{n+)tmXb_&+_KB6~l@|EZY=*x{cI68e3bKI`{J z-uS)G{?*tUzlZUElTefR2^TB<8=2_aG zAN>ASTI2t8eyhy8;s4akf5rc)ncw=?hr1-qm<8|0zhA=t#T);p-fVt*<6}Kj`hq8V zd#~Q}MKt2czTWHheHASl-`|_{xQ}`IGH-lg&u0dCZ?yBl|LOiVn4iP{squCAzj)*S z)a;M{Q?IxEZS7NUZjb-db{hYuWwf$Kdq1D^!$j}=wdSJqr^h#NK#$=6)Ga$!2>wrhU)s9! zMPdG*x>eUpg8x&uwt0Wd|5M}pnEw}V`}t8Rd|EuQq%>Pp}-w*$%?%JZ+swsgng?r*-z=KpDXw*hs+{6974 zi~rN{y4&sXe`@?7^Z(+F|MNBv$NWDv9*_Bd@y7qf8~>-q2QvRJ-uOQ?^ZoFDYL1Wp zi#PsH&Hng5HP-|G7jOKZTK+HI_&+ti5C0c${GYm0--f~esXO**5RJ|L!LK*#0Z+_5 zn9}$^U4QvMwfvu2{!gv>f8I8)6aS~q?V9v|>g?Pa(K{FZGqG*{GXcndHBD0EkKXpdU>cRi1 z@s0RDH9nB}e>$If7gY}aPkqUS7X|;Pu2!*9^jnvQeE&ulr~1Dvdp_ddw`bQ%T@N_j zr=`C>xnA+xr~AKj&zC;$FTK-m|KGe{x_|p`^Z$C=JgxZo_ObOY(>s0t^z%tSe){!D_k-!)FWnpe|LyZeHo^Jf{M#tFzzt}uM zd|kX*4>#WF+wp_=zb=pblAH&4#>vsnqNfV7H~$oTUUYi7=*`^2edOsUN2L>ND*A zng6H0;I}*KbZA@=3qxxxRbIX?bRE&r#! zq+)XYUv;gD<-`0xHR}W8|J3!WRto-4jVH(dsV_9&&HO)gWt)FjE;`)I^TYpXyZoP; z^~{<7r)Ir#{GS@{$NWDvJ`Vq)Vv;8|5u&aB0Km$HIIk+f4V=e2mVjZ^M(IY^ZLO5>F1r-BmPg# zyh8k+n%5WW|Msr?yZwIrYYy`d@qcPOBmQs4tA7Ol$M!qk?OxFT=znJqf9{W*UgkUF z@Am`jdc?b3Zf;6<@7FJ-8}{s-(tk3aS>fx?^UcTv@7KLq{phErpXHCwc{=#KtGl&} z&ZxT2yWwToQNuI#dS?vE3I0#Fm;X~|4Q?DgzvC0%zw_l8!T;&_U9Zdx{!h(%zWBd* z_b=Fyziio4!Sk`c@0~NYr}QhYZu7?b{kn2X{#Q+&3Z9KVZ}w(y{9oo9n^L;}_>JCe zuC?zE?%I&jHviunA86|Xq%{6d=hyMt>}dY?Yf>8jr^my5JN%!T`F8j}HGb{jpi*z< ziQ)gWogRH}u^*p)Ze)>nck@xR`WJfV4omt!ogcoB`G4vjHs25br|TvEr)E3;Pu>5z zrosQI`(D!|_&+tb$N#ChJ^oMK?HZeRXZ}y!_3EtP|I~Ou{9nBBe`>BD{x9BzFVFGD z`+fe%Y;Ug55x36rZf*Xp;?S8Xozwk8?@qS@Mb>Wr1Phzbl&mr zd*|9bzfXR7FQtF`%e&s4%!_?7>RrG7UCayO|MYyw|EW8g=W3ntwr}V4F|_hqDgEH7 zQ@opwY!kip`(*EC=JQtWf5V&klArCE#mx|J0q$7mok*CEvf}h&IuOYbJPi7~VQszwkxx&eyhzzJ2Qj z?+(LqqH@nX@10@mdDj~IoOk1EvV#B9&xib9yzRezf7YYM|LOd4hG&QQf9j^@|Gqxz zN#DQO@T|zJn|GVxO@jZ^@!Q)xP5hsl^}+Ff>YgLBBK)5kzlZ;eH~vq}{6G9(yzzf( z{Oa`a_xbbHZdB`N|26k`vp#dxmSeqHpZVJIW4!Tx@BDnbcN<$T8vm!`vpzQd&tHGm z_&+s24{r^=!8>cH{riElM)~cl4yqsg-zSS74*u`DH*N|3Pd#D&Z01wstBXGWl=&5h z+rBTc`4%Z{>tA^n@A)(9V|nBMY<`CKYV!>EKOKMFU%m|U|J3*+{GVF>PtE$ML+@>s zZ{OL3@8eh>_3V3EcyG1sC1Vrb__Q&1WqEHgPgQeFvy}eyj!bXXf3@!?{r>T6_Wh+d z$FuJ@z43ozf2rra$@;^e>UeMd=BH@i54F7Ue)vB#Oey|Pz0G_d{x9D6zj)*S;{8>> zO8NF@l;AZt*m}M8{jm3X^LzIFvG=Y+{!jaVWb*;>f9frE{-HJsPJi%U7PVns?+x0%S;&I-) z%(E>me~dTJKmJeWOXL64EA07szrw$kt2zFuXaDNWygmG%w$u1O^(wpnHotxA&Ah%3 ze%$YkS3Tpv7v8JQui^i6`{KVG2>wr9YRAX_sps1H;s4@||5NAL`Qrc7_(1%hn)QD> zzO%}k^?&C~TPwC5N9r)Ito{!g7}-(TbZ)cNKa@qcQ3ApTEXVDo8uRe9W-`7id`S+3U)ZQuQS zGd~Fbr|ovTn+ul&|EC_8w>;G^Dq7Q3+BT$S1&ftVDkl=YybH+FUpRW zrCwzI1plY~^UU+%|J2Lv^9=u|{b_sr-n@SCf7(vt|J2O?!~d!A9d+L9dfc1I^?%hj z-nlIJKXtoq&jnG@pY1 zi#PsHt@(dy&Hqy`F@KEzQ!h5ZjQ>-!-F$bp-Y;nUpE~c5|BE;NPc8qaW*!v&Pd#T_ z(*LR7E?F1+pZe~iqTv736^0E9{!g9Tu37MZ>TVsfg8x(B)Vq5$|K;!f@#MWZG59|{ zz6X~q4gOF4;@Wk=|EWJ*y&?EN^;}zDlKFq?;`Q5t|5LBt@=@@A>i5@e3I0z#ZSCgZ z|I{O!2AsUPumyUJV5*R4GBFS8vm!BZ(h=VKT7EHYr)2?!T+gOm8=f_ zPrYdIvf%&JQ{S2r{Ga;9QP&6mr*3rH^}+wChrIP_@PE4hr)Dn-{!cy29zXN{)Wuu( z1plYouiEx$@PFz8^G5hTb&35xZ@<4L^!qpd&wju4US;zt?e|~rBJ*7MKkZ*)zc1kb z)Vs{@B^6W%Iec*VxaK{reqn=C|Sh^my=q_&;^=A^)fIUv2M?_&?nr zjsH{Q+wgyC{PrskbxP>Z7c~Aa-uOQ?^ZM|AYUbecr9 z68~TV;N+YQxcq*3Ui^d>DOe{ad{8e?@g~^Jbp2%~m_y_WWO2Ym7I~|I8X=y?K3P ze|eAJA8nS)d%ev&z5b{By*JqVVXvPa@MiyheID}jUv0lH+GFuvYrhZR|Md9Qm>0$W z#hdwm@y7qDneT`HQ;pSsk1H2zP|Z<+aM{GYne=EdUw z)c9-spPKc4@qcRO{rx!hb?<_8>!b6>PE2Y1pYDIjnsvedsppvY!~d!0uQ1>c#f^@3FVP<;S11U}5loI-eOIychhRdWik|9p?Y3`?k3t_&@#qX75(#2mhyT z-1Xw%|J2QUCD;E|XY{BY{GYm^&FjMdsqucy|BE;NPmTY1Wx>+KN!!N<&xik6QnJju zllh;IcjkF_=~XZIKkeVPf1}|4)a?dj1plXQYaVdowJQ>tJ;n#WM(5wL(i?xbcU)mg zAMr|&H|xRT|8zVW|EI)0Q{w^gf9gKwXDzP^ntN|_U8V|jsHtZ*Pi%AN_U&_*Oa~~@5{q&KJmGAU#0Zi z-TS?BdpC%-eRIIOYoCT;{+}Kn+wp(#&aCjA@889I-+zO>13{(#)sRzWm>oRa57uHK|f9_&<4&Y?}|q`oHol z_yN}cl^ zKXq$6U;LlC)g_k%|EI2I{*L*7>Kf+n@PBINsp0?Bcq;s#8c&G-i#PsH&GlpcU%Z+B zr{?(hzj(9$Z@iiR7jNeOsXJAv8vI|K3I~J#>rgrA|I{_BRt)}6UB~9@G5=4^`QiW6 zoDcp_UB6cC;Q!PO>(mYYPtE*A{GZN;`Aw|^$ zZOaKqt?M7|=!heN|I_h~I5huHeS*y|#Q(*c`G0EGJI4R1PdC4Z|5I18^_N-yH{Q(u zoA<{b!8hXf@PF#_PC7RDzxucQJNUmd&HLg12458=KHl*6oO8@O;{VjAoOx34f9i6l zpAh_?`i!$q4*pMl);XsJ|EDg0*4a_>M<4a$(X9Wg?U(+keDHtjn&(#t{!d-wybFT= zQ?niar^ffO{;#@jr3-@pQ&+#ZLhyg;$`#HH{!h(3L)QOQSFBhu%>Pr@x}<9GfAPlu zsT))^-)-yvsvB0jH26O?@6Y%@HSf>(KQ-(7;{VimK<59c<^R-;8z$HP^{(F__&+uN z>X%b)FVOSb*nHIE7vAR0ygdA$w&S<(e`>rH{!h*E@PFzi4H^djr>@noLGXX-IvL6N ze`-7${!iVgQPThEeA$lwQ!~Gh^?%j!e`@(Zb#_j(;Q!RE+qQ`69)GRhU$+*CsPNot zygS=GyuQ`0_U3p88V^h9d)r-=(x>$un$lCR9^&2Hd|&>TLklWgctj$%$v<IMsiR5efVs>lNew)NL}G1^+i;>XC`RSN}Z+pNjwMeZ^4; z{9m8O%~L*~uFvh6(nGJhGNrq9PxXKu%s<9I-&&bh-J1J(z8Ra~{kpX>e`o$reMQes z!T+hd+PpvfpE~!lX2Jj28lAxpcCdMUw;b5*+uIM$2>ws|vpvlJJ9K|O|L;)C|7m|3 z|Ce>#^TGeMzN%T2_r{SE)~()chh+x;r|ry}!~d!K*#7vxc;o-n?2rG8 zH~uf)_`i5>Z)5BG9y%X<;m-|hecwaPe8H`|SNr*QFt7CE>N0QU*PXGb^l;n!zXnrF zygQ9(8ufT?l{dZ*|EKGL@5BG86Ia#`{!iU%SVnZp^DF#(@O8F6LrUZSbiSM)^Z(R% zM*N?;*R`3!|HYg6e`@CQ;s4Y;KK!4$x6NO}|HYg6e`@Xz{}*rkpPKW-|HT{s7jOKZ zn)}E9d7Ed#|EW9OkQ3qmylws-{!h*PJ^Y_q{x9D6KXvaLvV#9p_py0v_&+tC5C5m< zhilONnSXfSov(N^UvSiqFCYH-x5oeJ=ee!?b-gn)((p)wtgf2Prc536#h>g=ChgqQ*Zj~cftR~8~>+X_t)>EXK!zu()d3;o*iHQ z5d5F|qXRz$|EFgCT>M|W@qg;=wqCG(znX8RDR@2F=C61&Z_nnlcyBk)_u!S6cr(AR z@t})S8vm!`v3@ZAFW&e+Z=3JO{J(hP|J3UbB>kVxcjGsI3;s{N&9>jM?hJoCTg(IE z|8)B@`#ux@r(R<|5dWuMWxj24^^?3y%(vnHwEYu1fBc_%=Yj8o|5LL*F8(jx_&+uC z^6-E0#{a1c?D@z4saM+halV}{-h8<2^*yJ;dhcR;{P;iJp4U76PhDpB|9QEUzW)mIbRCad zp3?X~?O(XpzRx!Qr(X5>0h`}5$6NkS+iCotdYOH{kN;ESqnQ8ay>EZ;f9j>5Cg=aD z^Q`fI>H=H;4*#cKW%Ft9f9hg;|FHk|X5Nr}x9^Qd!2j8dz~E`i%=_X0)FsScG5@D7 zwE0HN|5GpByd(HO_4Lgj1^=fWH*;a|f9jhjPYeD}eNO8x!T+hx?%FN*KXu!C?+gA< zef{_+g8x%LKi9mq&Hq!sFn>|-f9gs3D}(=2PqBF>Rc4&v`@doHOz?lUMso0gug_hC zr^!=KoVVE4H~zEtV@vb!WqEt-~^ArE4E;H|E^BcXHUuC}2yU@IXJ>G0R-hyp= z&AXlGoxk-{Ti^Cf?1eZ3I6Y;)=vgs*eCIJ z@PF!Sy3G&%Pd(&{x1tT}x@4=b8ZyUK?RX0Bt{GZPE`mxW2`G4y958V-co^gG) z9{-e^hS}r2)qCcxy@UVL_8B+#M&F8cA z^HRF&#Jw$=b3qJ zBAZub^I22c=C^t;wd3RebbI+fb%DMAG5=4UZ}Xz?f9hhJ7sdL&>cT_w|J1Y1&zVop z*8A_Ir7QXT@_uaQJbb%%%^rRE{PT|5<^=zz;~n3>XYhaOYsZWU{!iEA{bkF7|5MLc zu`KvM^`f;U!T+gem#z!`Prbmr9{x|g%+@DUYgIGXGEg zmU(adpL+Vn9l`&pXPIZg|LO6}vCj|upL&t4Z;AiY^;@!WOYnc{QhPsT{-3&_uq66) z+n*BpePiLmh0zB)&-Z@x(MN;-)Bfk)dSmc^>a%YiWuL#5{CM@=c$eP~y|1Q&~g@PF!3dw<0LsW;jD zOZ)vgq2ISR+UwnZ|Mtdv;s3P1{GWP*d9q=z*w@yFet%wXK5@>(mfp`nLE# zHGdw$|EbxI|5M}f@PBI7^Tq$EnWu>VQ?nj3{!fkf!~ew_|EFetAO26xJisCQul4h1 zeqr7H!@W0|@BHJdk>0FFzwWD1-s^3C?#@OxCiaaV7rYp$cF)NAeY6#u7Yz9jxnkDoRR=Url-ulPT0r}2O4 zb+%qF{x9D4-`>pU!~bbJ^ZA(nr~7A~AM^jzr8W-`|EK+F=Krbjd-y+f!M2Zr|5L9p zpN#)gvp@bX-uOQ?>jN|YPhDc``Qra{KC8|5;s4@&+yfK*`mfrO^nZFjm!T;&+|GH#e8vLI+)8+x% z-;XBL+1;yz`G4wWww@>R|I|&*1L6PFn*XQ91Ku%pN#dFFo(tX&FNFV7x9^$se`@(Z zHU2NN$?`=0bI%6P$NaPb?eo3c^lKQ6?N{L4WkAE=|Fl2e5C0c${9nBBe`@CURi0Ly z()d4}Pp5&6qhVzwzMXz_SE+Z`%Nj@1zA8)U)&E%S&3dy3j$iBD!#vwb=dJU`x7EIM zy*FME|EK%s@!ZsLqi^T&;{W{oZT=qqPtE*4{GVF>PmTA(|EXC&cgC696Q9+5Hux^q z&pqYh9o~30=KpDb8vm#6-n(J&e>z{9`G0EW+2Q}x%)7(?saa1K|EJ?|J@9{Ot{46< z-uOQ?`{V!A_)7ern)!hEKQ;6E@PBH2ApS4j_&;@T^LO|^buaUG_&+s|5C5m;@%{4q z*WP%^b5H&@rSX5-A0LVTi#PsH&3eN4KQ;3J@qg-0y=n&kr^W-~|J3|^;s4@&{|`U= z^P6k)|33ToFWz{-)~Ei%oAr9}e|mkiwRxb-|5In%`r-ILb;7pe|I{72)C~Sl-KlHR z|EW9lNcul@r(O-h{697GLGgdblspssU#lLqg8%dGP&s1#Uv<64r=@%!S+jbo_p4Jg zbsk&hrPWgQ|35y;=D)H2ulxt|;LgpvE=OLZeT}-o|EW9FwAWYW@SNHO|4jNm>*g1a z@NQ+E5C5m_O{-oS{9nBBf9lL?N&lzj{+a(5Z~ULSY4w`Xa~*HYnL6?x!OPXFeQ9(> z!<$mNPKD9l%zMNC>Gt?B{GS>hh5u9I0r7uot{47KjUU7Rso9SIi#PsH%{;rC`;77P z!RNKixyu{B$NWD%9-8@oYR&(PH~vq}`QZQ5oDcrb+dL=h|EihC$NWDvUK9VP^Tl)G z|J3+A{GS?chX0Fq{QL2AFP1*PF1^$JT6+I~^?!|Oq`v;sJN@S&-4~{Nxc}z)(tRIZ zGJbv1y<^J;sUEOZ!_@uL*B4IjbdQ&Q{QuVJk1xH`eP8Vf>%k zmJ<&CZ_}?wB-$h-M3CZ<; zb$=Jy^}+wC@qW#&d))W0T<(Nu*ulrVtDSyI)bf-k3ObKHDp70PFFEDUIwh?CtG>Y2 z_htQG?{iNN{_m6;M+g7MJUslL`oiwsEr}2Mk*3-uS zshiq7QT(4e)8>s%+cd_H$M)v??)1jzZ}|QW?~Ho&qoM!4-5Z~W|I_o!d_DZ1n(g>M zbsbyp7XPPaULXEXjUUASsaa2$`G4w5?EQ@Of7R6+C;gwAd4KpnHOFWEpB`^*^KSS* zbzPfphyPQvUM=(g;(h%7>->1k|9kx(*LpW=l@t7*?yqIbmcjq2v$L~<|5In?*m{QM z|I|$q*%AIvjfcbk#T);pWz*BI*Cs_`UIK2K(dT{_%g>o{^PY z|5vT~e`?MDQ)eZT{!fjE#Q&-L*ztGO>F?d6d9&dEbpGvZJ|O;2-PWEz{GXcVAO9C` z{GS?6ivQF7;rZ}?>W-PsqdTW`_imSwod4JPz|p}=@_N{Hpj&~Od6oFTBlC_49- zRg)-d_&)C;eL6*h`tJ4ae|gJjZ0k?Gdk@Htdi`rpz8Rn32bu4;tio>JPJevjCn^2w z-#_xswe^C}`(l@O%OROj=9Zl)J@N0`^S>*Z5WFAj1LObHxwalK{!iUyX!GFz;*I}P z_cbqv|5M`u@qg;}!?J__Q@6V+E5iS&@rd}pc;o-n+&}&=-e*->?VY%)Y4Cr#-ZcJC z-E?S!X!O^seE*EWb)x4!D)#O&xL!27w8%U6iu%#U1%=)Xhcu49dwZpK<6%vM|I_*4 zpYVV2#{a4Dclf_}qszj)*S)IDsyV*H=Fx6La&uwzF4nS&>UzyInmym7R8)d$|4 zZN1lN^QU`vGS4;c?f1R$bk{sT&71jnZ6A2goB4QEZhF@n?|1&zcl`c4*!ryaKb;Tr z{qTSBzGKo`-pq4*`N=6My>QH%-mL$M|I_P<#{a3gf9C(G@r}&?Q@6jlRq%iD#{a2v zZT=hnFW&e+bz7Sk_{P;Qd$+N9g0?NCKh2ro-OAws^N8|szN9F|or*3KU{qTQk=KXy%ZM-*L@ShW&^sZ*FKm4EeztlV){!h*PN&KIh z*DL-{%{)*1U%c^uYJ4C5PmS-x|HT{s7jOKZTK-SX?eTx=`q$?K|EF$fuRrGhsS~3U zVg6sd@qcQ(AM^jz%=^RtsqwG)KXvmf>IMI&zId?x`{MQk^6!28$?$#6HB)Yjs(0+? z{o2f#!T;HJ63O+hb|?LxdYOIyhW}IN+xJ!YKQ-Sk*?bJ|O*YR0|EKMn%ujXwrepqP zKR%gUAIkdvZ`ym8TF?2Wt@mp4P=EQRwKx9noNrrtZ!jO#;oBVVwfk+}-?!P`>umc6 z-!}JVJ>Z%)|Ig3I8vm!ptKt9DYt4tXzO9k>C+6pv|94vP_~09No8M#ppPKo3_&@a~ z^KJM)HS6o*|I9cA|F`v!|5M`u@qg+a<^l14YJ432Pt80*{GWQGHU3Y%$@a(psW;j@ zKm4D1y?I6Z{@KrO?IHiC^QA{zd6qwZd|-tu&hTEh|Ddfub(-IPwO!9WC8v0=wa0r} zaXIfbHvg{m$`ex>|EKfWcxe7#yqW)}#&_cX;*I}Pm)N{M{9nAg4gBYFJ)WhuePN%U zy_ea1zVh7+Q~K`k6QD6Q9>;k9Vofr^Ns1eAe6k z_&*(w$AkY<;~VjR>b2%2@qfBK>kHp=#wy>={o((#KOPYO7w=g|Eb-oG`{Vy~JR1L} zX5Jt3|J3-u_Fqr)+vD+Od@UEv@leeF^S1AY@qcRO1>yhHtgmPP z?alm9`>x-6xqbhP|I_}g-)d_GdNa@E)U)sMF0%Pndycx;J0XwE0l1|Es?I@n?enQ;)cEXz+jP-kp;EPd#+_kl_E+lcr7#{!jh%+y%k^soyLv z4gOC(Wo2pbf9f|^lm!2$extZ7_&@dJRjY&ld%4on!T-InG(Y%1_47052LGpicK+hv z|CoWccFH3;lZ#66aCz#tSFaELFW&e+_3LZb2mhyjW5Xu=m2aPH>$~CqwEZpfFZe(8 zf(>}W%HA_eOYQbYdM}+dlk-`o{hxa90gmt8{QfcQ@7?Q_=j_i*QJCq*<9T)3T(&pY z?F%;S;`ZJ%%){9F!p(I(=6w7)*Dp(rpThs?_IOkLpPKn<_&+sX(AEO=+ZUQQFi+;q z&xiRiZ+?Dkz1Nh+|LJ%oyOaJ;z3P*s|5F#)dW85tb>Xgk!T;s{^mOo!OKqMP{x9D6 zKXv|^&x8L{PnfbK_&@cncPt71Pu;%Lc$){=&~M)-XG%0{UvuwaU1u{N(R=8?$-)2C z81zi=g2RWt8~mS+H~Qwsga1?Ce#g^X&ul%Ox%ZC_{!cx5)ZpO%)Qd-VGY>X4ThABG zTCCm=jtKrw`+v9i&EWskbJi4_=X%=rU-|L2;Qw^{qK}gPPrd4s-NFB<<^R+LAMLiE z-znMpdBh)gI{Mv|{_M2r-pr@M|7m|3|EFGL{ssT1UTnS@|EHdBUJ(DMp8LtCVg8?b zxp@=(pE}Rp|L}k6MZ1#zPd#VL_AviX{ldoW!T;&~_4;Wuga1=Enlv%^KXo*qfAD|m zK383akIz<*n=n53KOKMCYp)0Yr|Va?H0l4;AFeD6{!hKw=0UOkuX=`g5!U}z&ooc+ z^Ycd}bbRImwtV#{?-@4F^r^|mc)wq|F8Dv)erjQ9@PFzVMXQ7VQ!lX3gJp|P_S;Xk zd4u>r-QQd0|LosCB=mScSex{J@n-#B^@24UnXjDC=kv^>vf%&J@7O#m{Ga;qcc(>n zetd!VYY&W#+U>c}d+g9b!T;&__uVx%_&@b3^U?S}_4{kL1^=g>w>>%kPtAO?Grz0h z$Cv-p`QV-Lf9j?7d5-^6mzk&f`IZI={r+5P@0a%bvp1d(|EKNDW5fTcSufjuKld)R z*SpQ{_Qn^UePWK^U$OoCd|s}lH=qCbKb;Rg&Hnw6-yT0_|Gp@t@qfC1`9C$@kNJOU ze*eJ#>CZ3x{(=8fF6SN^(>Hy#lGr{m+p@qg+v^Mv?6^-4QF{x9D6 zKQ;IN_x(fs_;~VF`>*n5`wRQ8_QoGhYJP1(e;(Xwp786Y!@W1z^=_6q(tDk4f4uQ1 z@3r=N!2jv?%&*1&srmg4|EFd<{!h(z{GXcjq49re)`!Obsdw7;KdRs3z1=*XtHNFr37jOKZy0Ojo zV*a1HNw-Ub|I^=pw$8mY_&;@9^F_@6JKQy*bF1YgT5owVc)yP3eei$Y=Bx03YJ3&` zPc8qamj6@Z^YDM_ZUdV{_&;?IYy4llTQ6Sa&Hng5ZKv^n>h6Owga1==fA~LjPdu9W zKehayTK+HIU7K$3{n?KH({{WZ{?FU|8vZZd_`i5F|4)rK!~dyU^{W&7-*v-ZOwM;R z4~YL$*4>@JYM`? zyzzhW#{a3gUid#X-Vgs5Z~ULSyB#0@r{?*=|EVuOF_&>G$pSpFf`Cs#Y>PB6v2LGq#=O6#4Zq+3@|4-ebQ`Ip4Pn~7Q zyP@P?iSf~k!S}T=-*@`L5Z6BTo*rjo$luk5C^+YY~`~3L+e7}kRJ9*iWi6s~QoYU^oI>Gxbh1Ha!_7svdhV2d{Ve_`)&HTjw)NL|Sx3|wsU9WIZqe=M|HR{L0AB3<=>&jWyluW+ypKETh?GwEdH<{L!{5b^e@xnX!1%q3 zc0W~cLgvxo{fv2guUvDukFxVW{or`te#9|HL{E%8+?)^oulSFnlRnUz`G1ehIVSi& z&L97$W`F!&yzzhPV~;&H_&+s1691<@_4pH_ulgKr*4I5_@8iCm^>y)o+W&&H&k6o7 z-uS=Y&CB5b@OR~2dfdCx1?L3+r|p%?Ul2`x=P}=ozZ+iraI^iz;g1#M|8QLJfp|Uq zpPJ+2|I{4+jDJ7s&F%4j+D>0Q=n=m^`rAK0oYIR%9&Xkrf8eKwe0zIMsJ~Yz zg8x%z**rY_pN_|TI{cryb?er_|Eb%zY90Kax>a@}_&+u4{o?=PjsNqu^=a{c@y7qD znQw>xQ+H|6D)>L0Z;v*u!u&sVmz?b2|J1EpB(+TPPV9{x|AYx5VG|EKfK$!HM#pSr27SB?Ku*K1Ha_&;^SjCx`IpPJX# z=o@+oa|LOji--rKGbG_Eh>gJu%s7dgDV-_ACJYXaH{KNm%dHRIl|L}P6_xI~M zcTed-eN)%(ZIt%=O1Vm@zrUPaBh~xm)@_n-k1KKFJ?_%4@;vvHowxoR7U*nBU8({gHQ$%>x`xcN_D5Hs9a7m3cp#|9`m68`}B+-pn7g^#i=|fwsOtO5^`@KAb=E|8)I$ z{5}6D@$JnAHw^wy`!~D1LGXX-PJDku0qb^q%V5&loz!R7_x|MdEz z@qcQ(AO26>Wwfo2Z2nJ;_hSB^TJ!(ZJ#J|e{GYm;?T`Ocb9?+>yv>Grb3FW?wli-I z|EKOes%?b-Q+FJh^nYsR12X?l&3e!Hzj!nMPtE@LKXt1SiQxa@jsH_O7@nN}r*1eR zIsZ@1?eTx{#{a2#ec=DptQU;`Q?s5h{!g84UJw7LW_}<3FW&e+HQtZ;f9f2Y_lW;f z<2{-G7jOKZx~0vdWc^=ttD6!L{!h*81OFFq{GYnZ4ef&eQ}h1L{6BToD>8%sEC1*- z!T()1<*wlW)Gy4M5&WNhrx5(#irpVY_Wf1<&j+6gUa#1^gnhr|jZeV;Y5x-2j{j4$ z-qi))boTw%nlHlt>3H-cv3-^n-C z@?P`p-}rvj_otcvX9mhWApS4j_&@b_yMO#&yzzf()*HtE#T)+@Z~K1P@1OOG@qaph zJmBIX=lJ>3_&+^^P>1a^-62}U%c^u@y>tso8@|Z zg!W?;&Fvq1@h{%Y_rw3`_QkgTF8)tlV)GF1tMidJ^ZxLE+OGM3>Q(mm@PFzu zdp)1?r`6t@?R@Zm+P==#pTqyDS)UmH7jOKZn(KAe@AJLcf9x-_z43qhewdNc_&?n~ z&%VFK|Ecl6_&+t@pWpfML~p)7|8(0c-X->Zd7F(drnKEQrR}?W?^64|-DdT87u&p0 zTdU8T`9rPd-S5pju5JUzcrV}ivH8x?-ZneI)^i@dTt5%D%kVd{f*b!pO>PrhAaN>xCxVj|I_wP=Hu{x>S;Fb4F9L=F~|G~ z{!fi38Fypll*a$*_W6hWU%c^ux;^vx?7zK>YVoR_!olzTVd;a;{W1}|5GntvoH8R^-FIj{hxZwt&4;IQ|ER_ z`agB=Hg5<2r@pfLtlKv)6w{^2WIR1@4oxl;Q!R` z-Frjuf9mIl53twsE!nzW(?+%n{!cw~beG`&)Qj)E+SYr0)c5~k;Ux22Pk1j_RS^82 z_AlGDCHOye>9*|=^Z(Qv4*5Sd^Yobir(SOJMe%?7d1U?={!hKid?@};U2@3(sqsygf9iR*{xJSeJC z^WGDS)&&2j?YXy(4gOCZ-F9#Af8JN$5d5Ed_=szR|5LyF-c);D_KXw0WhS}$DMZbM?&+Wng>Hf3U z6b1jM#y^hvs;ck5$X+k)zpj3`x9tx8Psd+wzt1!OPtEHe|EFGI-fr5>^%DAhiS>E$ zf9m!2{)+!oueSMt_`i7L|GdqU;s4b9eBl4o+&}(L_s@FU_&+sX5dWuMW4|BZ|8#rq zAO9C`{GWQAoj>dUs+o6Ze||~m&ku#>2l0RL#{a4L_fPo0c;o-nW#+r_f9f@#{xv#y zpr1D$u;9Rel*a$*eDHJlzj$AI;0oWL^>y)oetc{EpSOMf;Q!){|I?qpHkhx&|HT{s zr)HiW{x9D6KXvJ$^?%j)QT(48Z-@U=vmO7Z#{1#_;*I}P;}P+H>W%h(ivLrW+UF(y zPmiz6K2Py~-nKvfPuFj?9S{GfF0uD-{GYni-oL;9@e#lM20Q+aA0JI={Gaxh|5MBV z>HhJ4%>RqG**w3!{GV=Lwlz8bPrbr?AnX6e+y2`d|F`GhvwnQK=-_kS#ang-|EK$3 zWu9>HgD?2?W1io>2VP8R{GYCG+4h}b{a>}_|EX7*$7cRtyqW)}mj8=4{!g7}@8`__ zQ!lmmd;FhziT!@e{6F=)<%Plj#T);pUQkdR{GXb6fcQW4Z1aEpe|;;_;{0c9y|o8( z<}F?n75w9E?{VXwifcC?+&>&g8$QY=7TZ+PtAO=U(Q*USbfH;!TYhkDE?2~#XJ=L zPtANf{GXcnbof8D{GYnppvGbT-{H;({x9D6KXsph$@zckzIJ>3pSt_yjiWwUC5i9e zeI@ufdQs<6@BX&`c>~M5``Wy|yGE?`?rHP+c8^)(-NWYdB_3bv&HBcZUs;#ZM@(Dq z&HTEdi#B-U*@{axdgI5c?%0&l-q1LFVUjsH`3x911{7jOKZx{sYd^Z(SnZ2lhe|J3+A=KraA{P;h0AG?0|zj)*S z)XWFO|Eat7t`lXv_`P3W{N2lM|KN>}{pZ|+-o1O)3;s{fSFav*ga1?G1Mz=qd?5Z$ z-PM};fAPlusqur%|5M|4@qcROgEIe5&3sV&pPHZV8t?y}IIH<9!S~VY7yaR#)1yZ4 zf7(vt|J3Zy{6BSz&Q+q`_eDAFK6p8JzZM-X2>wsqy!E-k|EUvM7o~hZ*&>nZ|I&TX z|LF$y{bS7IBx*GX{!gBTd4Ct>UY8>u)2X)2^EChGUDxIhng3HW{|*1AZeG7m@PF~f z|EY88)d~JD-uOQ?9uEJfW`E}Yb$Ixw#GU!y=ir<0e`>rE{!h*M;Qw@c8vm!pKQaGL zjrYR;shibH`ad<_f8+n+jsH{gc=3Pn`^W#q8~>-~@!cr*V`-Lpom;Q!+NiTOV@^9J#MI)6MI{!h*PLj0c^ABX=_r~5n}PyF@7^^SMC zCrj`2{nO_Gaz63nrQbiVm;baq-4CX(2b_NX>E12Z=3B*&-^+Z%f9jrT^Muknr(vo$ zXwfLuGxRl26F+{RwEIgxzw}O@*O%_~(*0t3ryno9+oXBK)(uk67taFf9Y zufFep-9OzE()hnte>pDrKN|lRZ~R}p@qg;$Y(ZcA-`H8l2mg1x&F{niHM{PFXaQ?Z$|EbGWI6wG5^|_TU4E|4j_C*&2|EIp_qKkt6 zQ&*@^APrfo-h7S%{(*wpBfK`|BE;NPu<$qH^%>|TUxXJZ@lq;YSvfA z|HT{sr^ff;|I{spCFlRCbFR(|{x9Cl|5G=$=MVpI>dS9v75tyNvw6Dh*G~5RY1`(_{5JfbeqL$(pIZJe-u8Ei ze)|EV+eFX){)%`1n_5S+4!rEmd_er4ZqM=Ye`@(Zbq8C28ULs5bbXuP|J3q-hr3nq zfAPluskuG=Pu+fa%i#ait!+La^Z(R%KK!4W`GCy-Q@60~!+vLoA$6bzA$?EA@2l@ny|EFd> zX8fPJ+YK$k{694w6#u7gXY(iVe`?m7#{a4DfcQVP=KrZR|4&_YQ2pTl?C<=8|GQ!8 znBf1^PtBXn_fz>c6CilMg@^o~y42QJ!vDqFzW?%GW%G&b`!R36-@^ZCf98oD*{5T^ z?vKX*sf*1Y;s4ZlsBZ@l0M-`Dp0#}hXHzNUAP&GRd`p@#2Y zZ0q~l_pkY8qLO~l=J(n6vnf5}iz?pC7u@@KWpBKpegEsd!M59c7;onN+58yqGTV;- z)BUj??=e^X$FW&e+HT&cL)H}=< z;{Vj!%-j8|&(Yqje>=PPk>1RMysB5^&HdG!`ulR-o_==9KT`VVH~!|0N4#v}58ik@ z{GV=LWRD;Jr_Qt22mVjJ#9p7@KDW=C*DwB0*O$issppvo#Q&)m*t|*R|EX8~B{~03 zU25wUg->?N8(X)U3Z}|Lx8Cfc9OzccC@@Py5sOKQ$f(|EJEg`B(Tq^(^xU z_&@b@n}>z}Q#1eS%QnNkr<=#X|Jh8!;BTKPV7$Qu%@dOTZ(!Hp|I}3; z8yoze`sH!sg8x$&&z~RspZYDENAlTeHI}R2v-x|h|Eqq%)`P_Vsb941w!WnIZ2SHb z|EKM$>wG7f9i>=%J6I6Q*3{; zG2T<{`&#^;_MfzFQ}BQ4$s3aM|0d0PDfquRHva|xr=D%=cQXG^J#)kQ;Q!PwFIpJ< zpZd+`9%KJy>f5g!Y=54LBK2jr+`{(e>i1Tx;QX5Fd>+~IN$`K_@gF7qpE}RJ-^c&O zJL{WP-uM&qjo!=$#Q$mkBJ&J(eY{uNJRmmQA^IdDc5C5lLvvY6o zf9kTGN&lxV-LW^!|GVSDmxKQ+*}m82-JO`N?L}L5n~glfJFjeC)Ufb;?^mYgh53KF z{rKA#1^=hMveT0`53-@}-?Qag(cZqzy$5#sfcc2tqxwvYGNyF)zVpiW?D6#SzT=MP zg8$R`jU787_&@cOdvA&^d~9U4uFoSwdk6og{%}O=;Q!PMZtl$W_x)GgGc5Q&ZU1@h ztHJ-NXB6cH|EDh4u`&2R^;+`}{A}sxYs<&G?dS1T??v{0bN<(pycd3)^nco)*9ZPj z%{)o`U%YL;YPQ~Q*lzPzy;oY>eAbl4|LOM3o5cUA7w-7P)<0e8`>(KhPPRV0_extY z(&oo{Gw&4tr~98~^F;A~>T$LnBJ2OEn~ogC=U2AgKPwKqlFv8qIyc{dfA@amzI%fI z)9vSc@P6=r>NjW44*pN)KewQW?LTiz(*LQa+xn!;|5ML0kA?qJ<6H56@y7q@_aS^1 z{!hKdKELsQYWY7kJ`ew=E;cWS|5F#*=Q;jQU0{9-|EK$B{agH>nm?c5|5DogpKi~5 zIs9L|@qg;AHop-6r`~D*egXfdKR>X(E&eaw-*xMj(4SXWFE^`ekCcA0OD}KMEB?4s zAMcIk`E35WxBQ=uj}ISzV4&Y0+Xo)FJf-n}@%{0CYWBzfsn?s|!~dz*+V#T!>HJww z7ylP;{GS@Xj{l1{{!hKiK0lfN7jOKZdX0S^;{VimKm4DX^?UJuYWyDlPtE$ftpBU? zr&<43ji1N=smpfl4gOD!=fnT$`IY}ua{lS5C5mzZ?xm%|Kg4R)BfvrCg=aD z@qEnx)Bf^*YJMNU|7m}=GyhMG|EvDvQ-1prTi^H8AD{Nd7nXGRPy6R|t`?m&dZBM`X+9ADr`vb6`Ca%wb#9kx(cE7aC%X2U z6ntN++^W&mW0$5h{!iOG+5ABKpSq8&Z~Nt(yu@vPnHaoXOIr`O!^-6;jsMgB!FTN| z@a?RhJL>xt-kk^8zi0o~O7AY0XGZl-De~?=xM`UGr{ndr?f5@+??e7i=hJIYM(}^? zAp8Fzy83xvrt}ll zzw+*6=l6A!{odWp>*cmT;N7E7-Dqatuf16h`Lt`k@n$~a&9{AfxNZNf4}a$^|EKHA z@$r9Zj*tISU*4-x@PF#dy4Mf>Pu;^jApS4j_&+u41LObVjsH_K9}xc+Z~UK{^??8S zt;S9{(4KFPnX{Rs}D@S zeP3G-Gk$+uzj!xooVq=`S*pKl-Sj_qfAcf(Gzl3>Ao+$)BRq$&r9F_f12@uF~59dS|1nwABX3o{-3sa zgZRI@pFJt~KjshO|Kg4RQ!_6R|EE6E<{9Gu8Vo5H{2%iI@qY&|JURHky%IWzj(9$Z-skLO?U$LDe3>zHP5dQ{GS>Ri2qaL4VnL^W_};@|I~Ot{GaZR^TYqCYh6+`_&@a}ms}G3 zpSo(*s=@!MYgexv{GYmB%}av+Q!|ei|EFeNE&fmEQ?W*J{a-bn@Yw11`~G!oy?Fee zZeP3lrNRHH@q_rkc;o-n%=i0t%H7@#?DOmXIb*%+n;*mfX@BOQ;s4ak=ez9IJN)_2 z%ru|!$nD=Kk!T+gwzs3Klc|XSgsW~6~pPK#ge`@A2UVPFJzh3k?7hIXr_&@EB zSH%D6@$mZx{!h*PUHqS#>x2JO^Ld5;Q{yw4|EK2p#{a2#e(`^5`9F2XW|`4%r}gvm zV|`!zpUxLwi2qaL)A4_5JSXe_#+&tj)qLLJ|I~c`;Qw_0tQU>{Q{!K2P3r3VH#dLx zealY%{@Sx`r|5w`9lh`F-Y@0-e{8qDDV^1+LrO;{pOn&7&N)4$TQ*GneK`H|dC-79 z!T*^t3jXi%Azg$2Q}?~h)*~?gr|x)pR#bTF9`8^FGA8WuW?mcqPy06++AR1#b*9aC!~dz}|I}^Gcj5oktPhL-i#PsHjgQ0s z#T);p#_!?()SYY|A^uN|S7iR5n)9*s1M;`MFeUu`NiTc+)4nS6?tXcb;QzFLgCUKg zDi4+V?Hk&9waow1_07IA>HpLTThAB&r|xR!ga3;+{!h*M;Q!QkM*N?;t6eYrU%c^u zYUc0Z|J1ApjQ>-2xVCwO|5FDqXZ}x(&%^(zTU^sL!vCpxe(-%sg#byJ%+hyPPIKQ#YO&Ahs!u6W0{ce43@pXW~XX5Jt3|NMN-2ikvo54gTX z@PFD)GyhMG-@^aJ8~>;7c2jnAW}8Xg-EBSCh7Bfqpt#zu?XFVE$k0jJJa?=6bRIuUhN>#vA{qW_@J* zpSp{!*UbDsHS6=@|Kg4RQ{(&E9{Gfy4~_rRaE`<{h#08H$Mdbr(SLQy=(&iDOk{GZN;`F;4mc;o+c z{%ptpsqu9`A3W8&$h!KEC#UpfKc3``XM6I;6Hj$Fu#fa)BUqvF8)s~|EHG! z^EN+-|5LMmH2zPG_rw3Gc|GF))CIO)?;l@%y<-QKMKyJ-9_Z#?S-Pi#wR{GXm5t{?ON)W!CC#{a3;+4mv@g8x&0Xnqg>r=D=g|HT{sr+#;3(*MQV{EKgYeMKprCQsX+nZL}|H~!rF zUi-e2`G1#ne=T^yXAb#4^}A)Oga1=cEh!EDPyMEOA^e~EJzL)m|EHc|o{#x|>JQEP zvHowv!q3DCvH^ur0?}5Vx+n=YRutqEX zF*5&R+na0u?4p(2-uv;=jlutE`)lUynE$6{eLei2dbxQR{GXcnk@!C~9@UQTU25~C z@PFD~V)NYae`>r1{!hKmJcZ38^k%-FJwGXJ^BcX3%ma3M@28Zu^Uv1tR&3wLdZyla zn|Is!oN>5U?+yM>*LULk1w0?w>PPO+j~**m)4ONxlXkuh{Px{iza5>rzL|I5PSd$Q z-h+F+9t}UKv-ij=r`hA_<$c$!v^uH_nY_L8vLIg&!fXG3;s_%b$DCz zU}LlO`u_0duI9fU@LqP$(BS{H|G{~$n3sLrw=XDIXrAjS@AW%31plY~S^p60rQ>h3 z=bQglFSq%7_&@bB^MTC&JKTGM|5GpDz1QaZzMrl4kLBi<@PF|(f1R!OBjyF#`?ELR z%HF@d@qd4Mak<}K{!hn~|BE;NPd$Iz*5Lot@0P3z{!jhP+*$Z^zrU8lh6Mko^NafC z2LGo%_pZ^w|EV7zH$M139q+>rW(WVLo-}V^@PE2KADH)J{-64N^MK6%Q?oue{!h*O z6Z8Mn@06AW|EFf29{x`~&DMKdTK<@X?*E0Qw*F(qe@!F@Pu_QF2Zj$a!H&3MgViP!uC5Dw07ZBPt?UkR&-So5(qXV8EO) z>z%y4!+U+t@H=~Yo~p-s>ixqiztufGJw40p?9OMe<9q#%g#Xk23)d(7pL)jPrOyAU z?|))|^MC5-fxgcFsms`U&Gh0#^@PBGNHU2N`ozJGly2#*0zPH-z z>pjmm@x9%=8}t8k`<>>u@PA?B|J3`;8`^yGG`;_0o+18E&HQ5f`6f+2f6(|pHR}!I z|H9t7tW(-^g- z{!e|-ydeHBZ2X^E{!h*KAN-%rcds@6FKqmun)Ap1g^mAHvwklAPtAI~_&+tC5C0eT z(XXHK=g0TQIbRQob^ouQ^^Nbt|LOeMAOEMu1LFU}X8xa=^?UJudcJAq|M@=gQFP&N zBmMsPd;Fhnf6#m%{!e|#d|~ddV|?TP7X12xZ~Wia-Crs=zRlYl-(#%r1NQok|I_{N zvhDc4uw#_#lkokYwf9s(m&i|=5+x%zzU)aSic*B4F=bHZ;e%=hZa|>MZfl1m!@XEAO0_F{GYnDt;ad}s|{)TeKn2$ zQ!~E{{}(p?PmS-v|EV*~o8kZdC^^^pzZT}X@PF!-=Dn62&hw4my43uiwzK{({!h(% zy!bzL$DZ|_|5M*~dxL07@$G*5tv%{Tf2p*?cSrMn%>UE=H1q$|J~cB|q1pPI*u|5M}f@PA?B|J3+B=KqC_|5Gzx z5dRl8{!h((Jp5nS_&+uC`|y8y{%Gd^6?9_$U)bG-oGQ3|*P71%>3E&G*LD6+-Px|+ z;AJ2C{aH^L|EJ^O{h0r!#slL2)Lid#zWdzYp2q*__*`H7pPK87|5LL+{!g7@>jC5c z)a^P~bN)}=-n=FLPmTA(|Eb$|GVf&mPmS-x|Ao!`KXr3kZy5ilZejP2|5I!JU)Zew ztJeHKwdVh+HUBSc{GU1_Gco@!Z2X^^`GEMp(ktgU|Ht~m_&+ti5dYWhx;f7OwY7PK z_&;?gn_r0kQ)gyYiSU1Fd@%k`-J(sx|EU|dEb088I<;wW=l|4cjmy|i+XcQQy-C?v zH*OIBJTtvse7&>ed1?4F{GU7vo(KOY?}D$w|EckH_&+uC+VFpBd>H;OZ2Vu?_&+u0 zgZ~Q~|EK2ja_0Z#9=+K4Kkgs@r^bun|I~cmjQBTJB9b3?B$Zzx9wa#?*F=bsf{k2kXUdExyhcd`fkzxJQqKkEbI z|JJ5l?))E(|MP905dWt>|GcxKIT_>gPZz$zdA|!TI@kF>^@SIo=ltJW?_A;h-(?q_ z=lq|#aG{Hw|2wtxO6UKIU6SyB>JnF6>HMGinrjmNPkr5W*E#>EE^&QP=l|5q?_>R6 z-5-75FE9AU-{JqR99}p!|4)s-!~dzP-&oYm|5I1J;kpR_cd*%23IA8@8aMwhZ07%k zjsFW9|EK1BdK@3+?+*`%|I__dys4=3f9mRGN;v|Hj|4+^Oy{!MMu4K*pKXrw2 zC7l0LS1VQ8`9F2#n@UEHPao#@ztrX_HY`=ph0Bz3{!jaJeEgsK7F%DK^?%i@H;n&N zSFTzx2d1v{GV>$qINy!|I~Oe=Krag--iEF*S6P_|33SOZ#*CC|7tt0_hsIA*f+1g z%>UEZ2lD|lHudw{xgPjG-M&rO>;I}7)~n_GpPK7|{|g)cr><}7 zMT`#UD{!d*ay^)*$r~T_RZRY%+9$(Y6bm#xncuM@AZ@WMIpPKcI z@qg+RTkjbEr*2@+7yeJp^N;^iv%WF&|J3d5_V_=YU#q$eoc~kf2l0Pl7|Ruy1jkh6{e?2-r{l4CP zo&Wpei?^KrYuTrl^MC5<9a}s9r{?E#{GXbi&+&h1`9E9pH0J-*ct8AK*!Vx+Hjj<@ ze_`YQ)bf97d>j7Hx6OCM|AmeJQ@69@Kic|GUXSAooY%wmwXc6L*7!f|j|aTu`u%>p z^MM!c^POS$hyT;@ZnNX#|J0rDO!z+?uhQK$o&Qr;y{}Gm?&CZC{V^Z#v%7Zq#v5+w zu-!L)aZcJc-^?={QhBRy);qrQhAqB3*nGm&OEwp@`L`SXndck-_QyB5zM1!j|I_nH zXYI`P+wpIL&N6MU{SE?z@XM^Z&HHlkJcHQ>WPD!~cbi z|5G#H5dWu6H@}GgQ&+Nn_KUat^Iy&8DcaY9Z|1|{|FnNA^JMrxHS+PhJ1v#?Jq# z8`%6t{GYnT!%dz4Q{w^eynCqM&iucB&U!x9^`CvtH~#af+n(`_uUudAY2Wz2zg#}h zxBQ>(kNJ%FKXtpuZN8)VKQ$f@|EI2ZN9Cwe&wjoub*t?BpZ(3f^MB7T8RF*usmJDL zJO8I%_`yl%|Mvd;hVy@K+2VM2i+#R?|5ILWG}aKVq&eIK=XfG2;f8f)hNX@9me|4)6`*6+pt&FMYE`NKos{p|don)!YBzp(Lt zVdMYQ%=g3pshRKh(_StFY|8zb)KK!40lieQwr`~8^pA}Aj?0c{I zzj3EO@Qv5Q|LOQgtnq(p=J(@uhr~6-P^ZoFD>Q(Q&>*oLI_F4A% zCjL*oAb*?lf9jE|)|z+e?zdOHqnGo49XiZ(9s<8%uT8W0TaA5Bo&8oc zWNdxk%dH)hx9o~+{chh=x9qUL2fRMkw!WnAndVbEm%hmNEW17a z50ivPoM`g}@qg-}E7mywryjdDvHmY>nBwJT+59Qi|5d+bZ9dKS0{gs``G49@#Cs zdae0U{GWQg&3nWDsq@XZ;Q!S4R{Wou^?>nzYP^b_kH7zI_WknUgrmN9eDJy5-{*e+ zeDenQKixjhyaE1Cz5e*e&i|=b9eUsSKXs1zzaE)I{r+>7ZR7dyJ!Z_dXzhesd}n5k zbN)}a&rF-^{Ga-cHp{p^e*e2~o9X%m3;1BFA2@@PA?B|MdE^ z*XIA>|J1w9Gvoi%_-A{4_r1=%h`s*%#{b#(2j97e-@%XjUUB#s-(P&sW?tycM|{s* zwaWQF-Cvi!eVzaFeb=4N|EUKKAL{&{di1yn&j0E0EnK$3`9JmeH5;R5fBfJd|I|(S z&j0CpO*RjW|5LwWuP2um`KRB1+KxTZ;^P1D&Ff{!tIkT(@n6l`7Cn6JIld>X&vyP# z+o!F|b^b4Gdp-60zmm1p`9E!cEqlB3f9kQ@c1IuXyev(Rchc^J|5G!ckokY=Y4&(n z|5v@p)^o@I>HE`LwjKYcUcSX%-|s8xd;W$T-oN>NW9cg1-}!#%x#7GhAD z-Fx_O=l|3rr_FZ$Pn~t(xbuJN#rE~X{6F;y`+8&kpPH{n{GS>xhyPRWu=#)Zzp(Lt zYS#0`|LO7K0r7w8ooD=?n)PJye`>rS{!h*E?EQb5-jDJ6dd&}weeeGCo9K)0oBG~k z9&pw7&0{_E`<4Z5ejER%<1wGmett>wKX2Ik6Z~J;_&+uCjelF2nP#TRc|RKer)FLu z{!h*OBmAHGusyzN^Si}*NAuhL@lV?IxVl+S-zV&P-P5F(??cwB8r>c1DE(gF%pYu@ z+B??xKb`+RyZ^;6_4W6U-+XG!gTCeev_E~#u>O8K&&QX8AB{EsFWevhr^W~3|NQkf z--rJT8~+zJ{x59&pPKo6_&+u4_2U23%=c^X+i>5^_bc_=2;cZU{Gaxx@qg;WCqH!l zFKqmun&adD)LQ>njR$1?U-iBdA3Fc1ujg%cfA~K&^Az!a+MjuV%>Ps4_wavVMe(k zJO8K7IdshVKlMiY`w{!v_g^phdlLRn{~l=kpL(OM2aNwyuiUaN`s{^SX-%h0Pi=GQ z@bql!mqyR_y}{=F)f_p;_nN%?=>1`Hed7U#51HqCz<^$sY z)ObAR|EV*3)OP+)-NClw|J3Y{{|g)cr^ct@|J3+2{GXch!T*Jg|5LZ>QPcUqu$liC zHuL|~_(%Mon)!Ltn;cGi`}BP0ujrJHM|`t>FaA&a)A&EN*8f#&{a>}#{|y`e=ljh3 zKRtiU|C@T(`?2kRd*p*ye`@?A{!iWh_FB&WsoUOG%lSWb3-fFEKXo%(kC*v>>Xvps53W4zuYX1t z`})lP&Uah$Zumd#-=TA5=l|60J5_S)|EimIs_guq8V`v7Q{($?-}-B;@qgNmr(^zK z*v$V^%m0Oq|5I~&=KrZXbg1ms|5f7y>&^Z>?bG)2o$up#@4x*|-|~Oj-rDxZ|EarX zR(1YQ-6^Az^M7hQG5$~8vTYf+{;#@4%Tmt&h5h$&XQiuCT9t`*U3Iqa`px5?f3{31 z7yCT3O?rI(UyJ(jd1Fm#S9bnSpRY1+4F4zpg8wV_N1yb646^s!w*D@j>hu?VedELM zf7&0PHhSZOemi~ZyneC9|7m|b7yeJ}yr20$HJ%Rtr~9Yze_`YQ)U1z-{|g)c=i59X z{!fiR#Q&+8hll@Dv;HjpPmPzu|AmeJ3mgBZ=6vygYS#DLd1O#}!wrSf_6+po`o+WJjL)gjd>n6_+O!j`so$LdX*AGrUU*;`^_s{bccCx2SUhg)! z8`*lD;qCvg-NZakc>CmegvoxdW3Bjl#LROFZ_oOUVRy6nUSZ!_C%ztd^8U&543p0< z*-xHx?pd+pC(q|g?*FmB&DRUhk9m7x|CtA5eco{Yk=Zj3+PEjL^n{VS!QZ@%%mXy^9Pemgy>T|t*9 zQNsB@9gp>j@qcRepHp(AKmRHfZjOpB8Q~l6H|)0&e*X#;OFRFk+t;p~@PF#6<%&E1 zr!HTznDc*O1bN`y?(0mf9hs+Q=I=(H>usg`9C$j z@tt3~`QzjN9yqI@+crpz@P9hL*7X`X|EF%=u%7dOYQF#A|I|ER%>PsKeBuAp?2rFb z^Zfz;r*2fUqVs?129?V=|EKO$v!3&RdVPK7_Pd<_Q$KOf{m%cXi<}!@-#1E{2V3l> zVzKWBwaeZR>*jUh?^l{NZQ=aim!H4w{NEFg4{-kP`ASQj|GWLM-p>E2>$Pv<{GYmA z51TJ({!iVZXRT=3?ho?JNICDv`nAme3!C|WYCIeMPmSlp|EXDT7ylPF{!cCcr3| zVc&Vt9N&04{Ga}P()d5M=KrZR|4-f8d?5ZWZ2X^^^@LgfH*Dtr`8I!u{|g)cr^XlJ z|I{20|EI>Q;s4Yv&-gzz^Z)RFVdMYQ8Fsz!f9f`U)1CiQv%WR{PtEgz|5K;+O>y)8 z!e;)Ty3U#Pf7Q(M!~dx{Km1?V%>Ps42buq;PB+ho|5Nk$ng16y{!iV^*6YRpshivW z_&>G$U)cCRwfvu2{!cCcrJ-n|5M}t{xhdXp8buy`#h>bk1Bk=}!0bkG0asE%e>g4gr*00J_uRV0a`9Jk0TdxTJr_Mcg%K1O_Hd|j2|EJEi&u8#| z>aDgu)i;}4`19Fj9_za8&3xnkTJLJ&dymaKduDGV-_HB>O!voQ-WvYz{-0+%uZU;E z|AmeJQ|~tqi2qYFe~#O?}z_0GZpiH>cciK z5dRnUIX~a*Z;vOe{d37!qpm$GY=xXZhyyUDp5A{qcY5-FAPqzxgd!$7B2SZ+`Nf^U1f) z|7m;v=ifX3r_MGXi2n;4|EI>U;{Viq{r+N&}Go_+pq^H5@K>#O<3)8PMfJl6lk|EbrVc+dGi^_t@+ z&38WPx39I&D{p?SukZObAL@t6cljQ(Y_;=$x_));xZ8Y8M}Iw|KK-2k`{uT}&I4AM zn(%+>A@i3y|EHdM#{a2jWGDQedhX`k&i|?3*t*^Mzp(Lt>ILRq@PF#JY+j)G7vFE# z=b0a#^J|W_PguFi);Ipt_X{?E%Y0c5W(hC&+E(Y`d{4K}Pp`OTweQ(Bf5rCo&3c^X zrF<{8_1J9wnr}R#d9GOF|IENSZ#d89Y2p9WZ`ph-^J~6W?{FS5TichK=dt5w>wIUf z+lbfm-E+Xx_VZMPv2(|d?(56(8me!a{0ctL_d_eQod47DCfItw_&@c!qsKYF6y1K) z$@iT9Q}gwO|5LM`H2zPWYhDKb7qLEHQ{{GYbxnU}!->He7yhyPQv9slR|H-CWt z3mgBZUU%#x=l{ZH{-1j5zJ&i%&s~z|{GWRC*d5OQsWUny{GYmYTEhRSJGWZu{Ga-c zTND0I-S?iw&i|>Od3>_-f9j!6zvld(9`CFX&pH369{cD6&i|>GKh@RwKlSP}{!g7X zs;~2Z>aSM6;{2aF=ZybTAA9$Z^M7jjKlPpyC!POOuRr;|^MC3r^M3q)*!Vwn_L=#A z`uE8Gw!V6*USBrZ>lgk{z1_Ck>vO7Jzi4~?_Kh#Z|7rhq_WFkZQ{y%8f9kv=C!GIN zZ?xAx{GXcnc=$i{jFl^$|5M-j_~Xw1sY~|0+xb6r(=j8Q|5J~g_-d4q{-rHgo^wAJ}P?LT`>w#|z@*KZ%OY)!N{`+VOouF10XB|!SPu=&~A&5 zr`~1$8ULrotK$FEJI#yX|H8)qshRJG|I_)?_&+rskokXVJQ@B^&362sTK-S(xA^-a z{GXb?FT($+_n242|Ec$V^jU=eQ|~pOXFs2$>E{y~|EI?9;s4aUe<{7TeVTs0VxAxV zFKql@*!Vv+-Vy(&W*#5@Pt80({GaacsQE?wpZbXHkN;ES`|y8Zcl@7vi~T&v`oHQu=G|ET zH*D7bRWsl3-{l9#x?Q;;L4O<_oHEq+KKp+B*U7_tBLz zZ+zaA38Q=;w!atHG=8-2WA^uMpNt#hn|Xp4j(frPZu5Yw|EsUBtu|i}|EFf&Z;xNc z`rcvZ*XY-AvEDysygwfE|Nb(1f^W_L)A4qh-)lN*Qo(k6{eNKO=#aQ*X9;)%ZVkj;#-j|Fi#`|J%HMhx32xP3HaZf9kdQo1Ont z%m1l!Hg0hKPo1|Z%lSY3J|%zoeCPkv{d;z1{gX6x(-zg7|I_dP8m5(Z{!fknYrk_{ zntuP>-sS`1|I~GCJ{R-^;s4ak2gLuW@qWzz3mgBZ=JxnMHMhtAsqumM zzp(LtYWBzfg^mAHw>EFa{694w5dWv<_V~ZB|55W$TFo+xQ%7!oDIK4O{|g)cr^Y{i z)a$5k_8;2+SV5cDWB#9xkKbedpKsfr`F~;K|I{69J=&Tb-}8+>#Q$kK$HV`rSq~Wh zr`GzvVdMYQ+#dg@=JxnM-{$M^f9m!&PZ0m7mj6>Tj}QN+Zr9a(k@-J$rhWZj6J|!5?W;3oS~$`GXhJ>7G~r%Xf$N6`cRm{xtLd)bfAoR_)40zug?A>v+xEl(Wwp z3%XhBveAiZXZh_-Tb7GjZ7Ap_E#mY4(o;*=PvZsi0h=~19qZ2ZEZv>JYM`?*!aJ&@qcQLw z6n6eEZ2Vu-($^=}|Gnla=l|4~U01}-|5M}rSpQdj{q>3Uf7K<67IXej&HOz4pZcbf zMVYH!A z+4;Y)ng16y{!d-8bQ$OWbpDmgmUI43U8YKT=l`^SxoWpK|EK2lpZS04`nI0$M=uTc z&3eDA|Euk+$BX~-U9FPye`>ri{!d-GYGVCgb(Lxro&Qs_o%w%ZGyhLr-RA4!|I~On z{GYmxegDP(squpNKRtdL{}(p?Pu;L;b?5)oDYhOu{!d-YUJvkpVdMYQm1@>7Px6Gn z|0=a>x%q$oe9RBx|H8)qsVme?%>Ps0V*VKar^W-~|I~Hu^#=c^#>3(N)c8aEpPJVj z*8dHg^?%jOBgOxz@yqwE@9iHS^XYEeb)Rp%bDMYX_02rLv~TZ;HU3Z6r@|Tkr!H;t z7@7a4#z)q(^?!B$cz67tx}43!!~dzdUiiN%M~gcDSFc8$X!M#p{Py}a>qbSl-R_(3 z56h1B@Xh-~ z`NaRJ@uv7cb!HXwa5n!>eQT`-&i|>KW@JVe4sGYJXD6Hg@yDdLzN2oPV&4yYUaz~ z|J3q-YR(t`=i83Q{6BSDd%UCH-Q}Cdd*AMzzBwP}|LOeN+x_GJ)R{K#4*#cSy-4{|g)c=li}?=l{aS|EW1&{GXb~ga7kw z-jVr#VdMYQcu)MF8qc|Kz)F8T@sFc>uZXqn>-XpWnl@inu-&{L{!h;r9_+!lm*h=+ zf0^@pwEZmYoAr?wj$ah(=Fczm&Hnhm@b>sWHU6wb=KNUW|8)QLA4re>`sO^}4f{2Y zY;6SJc)&Fy=ENHRr|ZG`xhemc<(vI)_Hfp^zWBu{+~L{{2u;Kood@(oA-L` z_5&wRi*?tbula6kKC#v#uljCh{_v_hU-6AM!~f~{c(fx8UoO~go^9nVQ+&5F@5cN; z?T>%M|EZhwYvAVpshPKj|5LX(`9C%D0hs@%-g5js=l|5(ZN35X|J1D4G-^|uJl!9k zpKZu(<$IUSAH)A?JAMiO7dHM+ebBrX{!h(3wL#|pbbt7=TY9DX#f9g|b=KrbRGe3v_Q{(OMe_`YQ)bf8eL(TiYSwEGF zZ9n`|nONihboG(AMPy6Hj@PA?B|J3q-YS#C~|EZa8 zhyU}}+x!>)PmLeL|AmeJQ{&a}f9fqZ{|*1A-fN$CPML6Ctnq)kf7UO<|EUw}fBiRC zz16n&|N4(uAN~68zIWL1@qgNXr}T|H&X>NY$;ZBV zd^?(d5NrIOZqIx_{GWP@UEhu09rB%T^ZD?9dj4qqpE}R{9{%s`FXub|mt*tx@PBH& zB=i5&_)7erZjZ0U|EW1&=Krbjm-s*RHuHY?KQ+G3&fT9cZJ#~H+Gdyd{kPgY8Rq}# z_RR0W|AmeJQ?vdr{!g7{pC9A@)XZDM|EXE;7yqYT@lL}3sh1yr*ZDtn_L1Yx|EcjW z_&@b4Z?AIxPuDNCOLyo0)aC8(fv&l(wZFa@Lr2;5Z|uAK^w~DAtG;i$^!Nzh6SMN& z{J-IMEpUEt(x%PM|EXWe%5nZrJ#}Mtg#S~&x+%~3KlRj&InMv7XRcc9{Ga;eg^Qg3 zQ%_sG%=tfz68>-gI_KeX)T1|Ua{e!DvrK;bE9D^hT8w>d5fI?Q_tRWh~uTGreZRBw_r2KG+q1{#d#TL_ zwB!56!<&!vonxQp+x7FEZN9*KrEfeu{!jOx{Xt^>U)Z*Ov)|6VKb!9uYdil`?Z5hX z!vE><)A&F2wlnkp)N|g-asE&J^o!e_|5G>WnDBq<<_%`M`G4xn=85%x)$)Jp2ku?s z{Ga-nCtr5{Pd$3*Z0G-U{%?#L?EIg4{8NuO|EJDR>g++ca{c||Uo+%x=l`_* z^A(ew|5LBuyur=?Qy)Cz|J2O;WBp(CzIWeq{!g7{-jmsMVPpN&%m?KE)f>$BvHq|A z{o()Y^)*$mH?+O}`p&iWgz-K{!cw^#d7EW)V-g3mie{*{(3z5DC^t%esJVad;R>x_mByb zq8Fxq;d|`#8P5OdcmrRb6Af?kgTKFLX3n?ytiKfWta;J;u7CACY{BBF!|lKOo;ZK8 z^M5+tgf|yC|EC^3@2%+a^=GH4pPM$r`9JkTug`S;PyN*VMb7`JUtF-n`9Jj}`+k7` zQ%_xPudn9+)Nk195&lp8vdve;|LOVS^%4K49<^ev^MC4*%hx#nr=GNIt@D5Cmsf6Z z^Z(SZE>HMBb+4zMVg9o}etlan+vY?2PU+Lrynbol!zWJS?@N4dvh|Z$|5xX~!sc<| z|J2zhKXCp}z3tt^{6F!rQ_Pt*Icjn+0F+;_Ik%d`36zVUH3Up&_MKOIm0Psii^3jR-x z_rw3GcYOMl^MCqzWS_mC#Q&-JdkOrXn)kQ(KlN_&d-y-~F7t!-q=i&dt#{a4Lc@zJq=6Lu&HS=@ve_`YQ z)Voi9;{2a_*NKmv|5G0|e~;Hz0|MPwLov6s= zulnaV-@G6GPtUjfpE_^vA?N?pTWsDl{!hKxwln{)pbxn9f7Q7*UmE|X#{V@OJ2P$g zka^Dg<=T4bX7vhsTf+ZodshCI=+wn?(w3b&FZExGho!I2+Z=7bV6N{~S=o_o^Sx=~ z#^{x^-i-C&{}lA9m2W%$r{AxP82-HTf9j{YH*@|^zwhf|^RQU|SKY8xN$3Cc`@}{W zWu5<1SF`^2eH+sB`^Xx$-fyobH~Pl^Z5ff}n|XiuKkYC7rZ7dHM+ji1B+g^m9U8~+zJ{!fj^!~d!AdiXzeM_aEK{}(p?Pc8o!HvTW{!WZsO z%kH(zc|P`Ed(DAZ-gosaxq*!Vv+eh&Yq#?RsZ)U1EY{J*gAf9kefDm(udHvUhYVm=Z7r%tu& zf&WwE3z`3?=6q*&`@%mSx^bT`eX~FQPuGXW|AmeJQ{(UOe_`YQ)Z8Bb7dHMcJRkgD z*sTAn=K8VzZ`jQL^KIS`|EFd>V*H<)^JD&B*tt#q>d%Mmy*mEQH(v0pyZ-K*d4F&A z|A%kp0pkDkc-nWU=;r_Zmi=~O{+~7T|I}?eRB-<9#>Q_u|Hpd1_&;?9MZDDt*7x!55fBknCasDsUyaE1C&Ac`IU)cCRHQoyU7dG?%)c7>!|H<3n zweWxHMpbJ>TYB~P`=?e)%>UEv(<y%M z5dWvfui^iEoB#NW`9C#}7yqZmzx4ion7`gM{!iE6JwN9E)I2`?pE}vkB{%aT!>=zq zVc7VT|E=*V;r8TC_ISyi?Dzh!oqYbu^97T)CwKCC#>qYsFBCq$YBiFsPm)JWK3?+U zN%n}zoxJ~_t&g1SCzG#l^7Ebi_>z6z`RB)d-zDds7km84ea;0*-Y=>D$2`EK?S(Fk z`@zdEj^BT=LKjBOS5C;kynHd|`-<8;zsnjF^re?x>inO!)A+xgzZY}l zg+G4LcV$~I7yqaIndis+zp$DAS9Vu%=l}46_&>GQ|5aDIv4rz~YSzca|Ebv@|EK17 z_&+ti5dWtxUAnaMf9jGqm5%U#>YGcJb@Tt!%-duBpU%I0`SQ;Hsmqls=lq}cuVC{~ zS^rmEyFx|h|I~GC{d4@ETK-R6-PSw*%c-IM{_uVe_bzDWo#Owrzvlmi&HBG;`9C%P z-tm9x8kG|3|Egc6 zPmM>z|AmeJQ`fNhzxY4hKR&Tp#^b&<|4-ZN*GjDatJeCzYR&&svp@bXZ2X^^`GxpD zby|&D&i{pt{|g)cr{?_de`>rM{!fpO`G5F7HS_=Qe`?mZ#s8`6*!v^=pSq&?LDv6O zm#JCZ`9F0n`+EuepY9*8iU0F$9uEJf#>?UVKAd)=^MCk9{GYbtAMt-`<~`#7!p8rp z@sapHbz}31%>Pp}PZ9qYHvUh|dcF9+uGVM>72N?0@H-&j0Cpc5d3#`9F1Gn|B<3|BTL!zusQ~FAv`D)~-}0)>SLT-~YC0 znHk&OrT4&C-`00fRQ$P5^V;0IHg(Dmg#S}F?^enAKXsd) z)t&z{qviZx3!4Xs|5G==qo(tJ>iRa%4gaTZXuc2sr^d(O|4zTM+Rx|1|Ecj`_`k66 ze`@(Z9k1OzDbD|?)69oezVxuazZ9D%cj+Goeb>FWUc~yp+P}VeHT<8B-^o1TXVK?Z-@U=cd+$)@qcR8@5TSAS# z7dHOSx6S**|AmeJQ@85V(9Qo-v%W9>PmSMW{ok#%Inwq=JuDqwI~~+jIe+}0wzogy|J3q- zMXp;N^M7itKmJe6_5bODg?UY;uX4W+!Utyjz9824KkeVTPs0C&jsMgAr}as5{!iW5 zJQ)5@-Rgm+&i{oy`H9&D+iidRpRPBa4F4DQKi`?*8z1=I_BVXDFkhFoW_qmgf4Y6^ zhZ;oqzp(LtYUUH-|J1Dii~m#O&3{_opuV}0{{~J?$2;V6WGEq`0 z`t-N;f6p|>d-$gc{&+P0PscxE^ZD?9YUT&x|I`Og|LW%dsrP*Kqw|02{a^eLP5Zfc z!Tw+V==`6y?=x?P|5GzR5&x&=`Z516?2W^1{oga^&-$?VKQ*6M;{VimKK!40vu(%! zsdMe~Q2bxm_&+tDuj2pIc+sYl&hgFXkN7{GAARxH|IJlr+vkz^KlLX2yc7SY&Oh~q z^MC5iAAaflpE~=)uc8L^zRT79(=!{|`oCu$|AtS#asDrC{GVF>FYNNIPZn&q^?S#* zJLVg|iT~66Gmr3w@At(T|7Qlzc~RCM#{aeaZjtkUH2zP$%|4ID|AmeJ)9rbF@PBIg zKQ;f}@PA?3|NG|n_F1DpzwKxIpU$7QwZ{B*KL4-s%WJ-w_cP^}mt&3p)BWYz>jnN# z&HBFhKXtBsK8pWS=h^46_&+u4VY2?OdX4!l=KrZTobi9^CEIs7|EHe*_S@!Ny7~Q^ z-*%hxf4ZJg+qTaCsjqtQLFfO}?IzE1{!jhL+AYrisb5~R5pUt2pVw{P73=?Ego^hV znf^*vuJeCk58ZQw{Zq96 z!u`jb|5GnLe3J9`+gID?-}pamUt^!I+wpy`KlXw1f7+g9^M3Gu>J9e&5&x&=>l^>4 zUT2<$`F~;K|J0joULpQZopby{&OcSX;qWOp|8MPtCC)!)9ZmQ@^_JbI-1@)jxr-A1 zPyO7P^?%jPZT;UXZmHpq-?Yx0s8Q1fzB@E|o9pAdW0x7xtO0F&_q=P7J)Ta!2R$(* z`uD;fzDEt2<@}${f91%8|5ML-@?q!y)EftNcm7Ykc0gCIzdzpU=kBoeUPq;20W z6V1!M=zCrMdRxzRyzc`i5AuBZ+spsy`0{^h<~`#7)Xam#|EV|F>ksx%y~(^3=c4mr zeRBMtUT^S$_&;^-`|msdr`~k(r1O934R(L{KlNJke?$&GCOtncY7mO1~Y{rf!kjPrlGzsvyxo&Qt!96rMNKlPJi6aG&Ow|TS7|5Hyg56JqzYP>Y-|Ej0i{`U7BzVCQ!p!0v)9^KX1 z`9Jkp{qJ`EPyNh`W1as~XPKvY?BVkMc&p7r+k9%@dFG7@JzB~4PWyYG9*HUWDf#(18ert=( zBgFryx7pth;Q!S7?foSFFYGn9w)B1G?~~H>^95}`zxdAi_)C7i@ttSyr)O&5-9{x|g&*tah|9sngLHwUu{!hKlZjb*9 z8~>-?`OZhq|EcBw)Q4;yApTE%#2yd+Prb+fJ_Y}$X1(mHV_)>W?ZgMsZ7PsGHt)y$KQ;dEsUlPS^`}3+>Sf>C zty>hH8tY|OyyAPC%@4%?>G|D!=!o-w>ih%8-26Xv&fde$|Ecr#B>bN`cXz`7sk8SS zbp9{wm&eaYD>=|iy{+$?w{ws4f9f22|BnAt=brI@YWcs6e=KnRkH-J0Ssxhxr_SA& z<@}#IFKbhT|5LA7x6=7P{XXWUabxWBsx@i){manD`Z)imZd{{0zdudW?*r>Mzrp!G zb@PtpqZwV-r|I{N4b1!C|H8)qg^m9U8~>-Sm08Kn|5MlQSlP}0Q?tG*^Z(RZ|5vT` zf7SRo{9oAkzp(Lt>h?YAxcPtT4!75J>;L+;c?9^sup!nVdMYQ93TIuW_}?4Pmh=Re9Zp~8~+#f569p4x5u+h{QQGh*ZB2Rtnq)kJ^M5N zFKqmun)QpbDt+p2&-%r;H~h>u>j(e4_2;q1|LO7Y`0;;g_Q(H)jsFW9|5wln{}(p? zPu<1lSK|M|UVh+v-}u1HQ$P5|BmR2&N8ijZocjAuzL{TG`@&y*GjH(ZHNX09-?c_G zsLXG^yV&iE)%uI?&USnJpU$U~{rkfIg^mAH%m0Oq|5In!zhBn>eePHLnIQG0bo%vw z{+_nz$(7FgwX@d;=KqC_|5M`w@qc0C|J2O?!~cbi|5LYUTi*FUb<1`Y-26Xv+qM;= zUmKp4{@MN&saJM;F}-!`a?uxC3c5|x_ab$VpV@gXFlA4y9fDhXY--(f7%~k z_QcrdeB-gseR8mGd>8&tkEe}YFZ`dno zqHv+8)MFF#pIdp8^L)iGzc_09&k4R+zxT-z@y7pY{~|VTiur%)>#x4d&Hq!&|EckQ zO{4}pBgWS|I_)>tpBUNsY1DEYK?-vp={}> zQ1)=Yz3R};~AgmG{~P%Me|PhKb;Tzl4lfKy>|EKez@qcQ39`pagX8xZV-^cpDVKe_vjqk_*shRJK|5LLa{}(p% z|I{2G|EI>I;s4Zlx?;kJo{P2Hz{51YAZ2X_PZv9%$|EXDD82_i{`NaQ)&HBH( zf9CJu|I{sN*NeVfc31xRUZtGxORZ<~+j4sOPH)iA`9Ez>tKY!+Ki!_j|AmeJQ{x-) ze`>A={x59&pBkTu|5J0l@PBIN1LFVG%m>8(squ-o7VYF8Ki#@wN8inACf5Je{#+0I zpSnkr7E!4?+xz{Wv-P6zf4ZKJoBzw~+}6LIHMRGLZ}x8EyHJVZvDfqH!nh~zob>%* zP?D#wW6wwU{h?)x*0DaX=iSkoyFbsH*dr@-{-fj5FS)mmoBwygIUAk#t9e(Z^MC46 z9c+Ee(I4fhYjv+0ZF=uio|!J^{p#PDSpQco|EF$tdkyFR)D6rF;{ViXHt!Dqr)E7@ z{GY8^;QSwr|5LNREdDQS{GXcnfNLH&5^LuF>G<59`G49!?H==J^$!*_9?jg^mAHck5#w%>1AFw)-2o^?%iE`ldPmr{@0fe`>tjvGX_i^P_G3 z2;X=+TVKLAp3okvZ+s&DPmjN&Js5vF89s)$M&~$zPWwneQ(ElfA-Q?GyhNL)7sX9W&WSKi#;FsKQ)gB|F`$} zx`h9;^@j0(VdMX_Kc0*Ef9g#0e)vCKk96D4{J*gAf9e+Y{7o-B$KSrWJ%9DineChP zgde?kmfyeSgXvNG&NF?p{%qx@Gh%&7%{P4G1y7fn9_u}YU-ymwTXgm`-)$al7>)k* zRo|T-vaj#YUh&=4{2BgFUqARW{GVF$|J3q-VNbk%vfm${*#E*wv2OSG3BH>@)WrEe z-M)#HP44_&;^`htr+^Q>S+>6ZP5npx<7- zXFcct`t)C#nD>`I-T6QD^uq@u=KrY|fBd2If9j34eir_3>JLkt|6?8({!h((5d5E- z`5E^4nQ!KmG5=57x0p9${-1j9ne~6w_%i&T`k2i#WB#A|-EVAt-vepB515C-|LJ^b z{GXcnclbXw-Y@;Wy1wyuKliTf8-F*qPfgz^?Edh7y8XL0FA)EyK5jk_|EE4?J`n%s z`;7l<_|sD74e^3|A1mj#pE8g5>=R{tzyHk-QRM+Q`#xyv4}UbUWUQJ0r{f*`>L=&_ z)Q7(QIr{b4Vt)T^cK-7RU++8L)}!q@HJx57yqZ;Wu6cJr{4T= z!vBSh|5IUA~vv^JBgv7eg}al@aO7?e_RT)|5Q-_Yvvxf9fsv`8EDe`*Z!D z_;HOtUba1dCx2Ywd#^n{yKmon?D@3M+I{ERzeoI^&X3Q(ng6HWddB~$x0&a~|EYJ_ z^N0Ua;{k1ciSNz!dV&Ab`DWYtZTLSmpO=>UZG_){yLqaMzaHW{$L6o$|Fr+QgYP*1 zr(Sg^G5=4!(AHyQ{-5vFtDXN-cj?v3d`za_enXEgHjlBD?{d9+Isd2Yefu-Ro&Qr$ zT)y7+d6yJbIJe7Wmz@98_C;HEv44vC z)dRNWQD zj{j4yH4lUTQ|Fp5#Q%kj|5L9&^nuO0yC~M3cUkQ?D8| z#LfRx&we7||I}Ls^>F@Aoj33{zCKd*^|EouJuvrY>;LNY zV56-!&HO*T{;ak0Vf|k<>zU*K!p8rpH|*Q*{GU4Oz(MB6`t7Us?sfi8+ZS%$?EIg4 zj=lcf@X~R=|8o;2IRB^ZgP(ua`9Jlu&kb_^Pu=f@7u@_m^{9FCod46~W1b)L|I}kw zta1KN{l@AI&i|=rn3rb$pL&SRD`fp&^+@v@tpBTiEj!=&KQ&&N^?%jN7B6@HPd#_$ zJm>$^ug+QE{GWP(&Ff?SpL&uVkNJPRXr|I_u`ZP%Cif7-s&t}p&iz22@T z{!hKZ_Q(IJxjp_*&HO?9pBmqX{|md*lLKRo|I_)%|Ec%d`#b!fdiSySo&QtsviW*d zYYg?r+i70!)oR0hZ@0$(X@C0u$|L-CZhxTS$XK)fulC<#-@oyH>fQGJ9sj3hejol% z&H3a1)NIH9g*~stSbu*b>T5FTZxO-=Fn@@qfDh+mF8M{9i#Q{GWQ8{e1)eFKqmudaM0C1oQvYtT)g4zv?Vo zPn`9C)$)I8{9n^4)6+ITw8Z&7UVpxu_=fLI`wm6;KW&%)Q)k=y>i9o3>jA$sdbaN@ zd%b1;-w)p{cK$DKbHe|rb8S6f{GU26JJ zWyqN4oc~jou2j1`u$?_j%A(yQ`gO?R6>J?lne5A5>Y%{(CfPq**V z-R|G~pSo)g`@GHkpE}dd2mhyLJ!0nnsXJTa|I~Oj{GVF>FKqmuI=!2%muvn{-Kcvt zxBjmh&xijD`=YJK)6T1~&Ur38+R{Vs#QK88C;k3h|HT{Ljdk0d@5LJb=Z|kb5C5lb zZC(xk7xuB}Bj5PA0hfOq>uYcP#5evB|EJq`u=Swve`;=z{|g)cSJ2g?u@k=Vj}QM> zdB&GPSBnlU{>rzz9)-V7tFdUU^KG5GRE@^p^o?)4-};2Pfeu_2zPv_74KK!3L^NjyfbN~21HQo>Zr)K`*ioSo19lz7S zzxihU-`__3-8b|9UY-08-)%ZpiPrz{5C8aEXI6IpPuGX_eDQx_VH*DtrsXMeu_`m-DTI2j*yOw30|5LY2GcVZk>~wXrhH?Lg z-wQwg#OsBf?3b7ai2wWIn&Qs?;k%gsr^XlI|H5YepBk@*|5M*uqe@hI+(W***m{fj zKW)bYGXGDF_rw3G@qYNfu-qqv8M54eb6VZXb~T^aI75=c7MfIxyB%UVf^e&FA6&w0~OlI?n&8J6Esk z{GX1`dU^OiHS7K1|I~cGj{no+;rT1ke2CxP)*j!x*9`T|d_U&@z5YXS=PzmepKj0f z!T+hbKKMU%vPVnqTGiuUPq&o2IrjBcyL5?I*DYHr)~!p${aO2R@#7`m-=BHFWH0xB z^?%8}kNHU9zZcd^4Et8|DPea?@_@-6FS(QF?4C3$h+>czze#yuPq6z3ie`Uv+8R`(1PS6|wC!{;ztU zo1On-{a*Z^8ZU_dQ(t!3Wzn3B@%e+tmU8m~uP$_1^x(;HzKdRUbyVZ-g2w;->-1Q^ zUH(tU!}pE<&r5zgecKBKeMQl0qY{M+`sy1K^Z#^vd>`}w)FrMj>inO&Sg~Tx|9#l4 zwDW((izob_x^(dyqfht0kgsNb-|bxsn)!amKOEz?)9vps=yIiQh<5!r+HWs?)Ai2( zg~!AHsaa1L{}(p%|6XiU#`!~z&-%Y=_Q(He|MDeEIsd0Fb8~s;|J0>Rm2>`2U8O`R z=l|3-O5688^MC3}Wy(7L7dHM+UAcS(=l|4I?DY`;r}JYT;GyaTU88DZ{a;Gzh zd>{T#&FdHQ|J1zxF#k`@`oQ=^;s4Zlvo9}w#NVFzZ|@fG?;9_O|I_|- zUiw3^?W;2T`DT9K{JS5F^|Z$y@XdO-V@LFjHU3Y>Z&0hA^M86gH2zOr&F1~#|I{_= zHE{F))G757^Z(Sf?fnY=PhFu#CFlRtmFrY<^Z(S$7sUVRd}!wXsaw=fbMybyEgPgq zzrEShZ*SBf&G|oVPp_Zq{GS>>i2qY_{qcY5Mzs?DPtEnl|EYQY@PBIj9{x|=ynaLH z|I|F6_gvK3KYqL*{!fpW`H=WO-}Zi_VM?a&rcIhhRWdsG?$y3yw6scw|9b6vTaW19 zjoKA-kFL)D>GiB`h0@Odsn507v+(slDpDlY>BUROx^wlo_v85wZ{N6O-2av7)GBJ8 z^J(5oZE~FVE8VfB^MC5pF7=)NQ>WkB(D^@gJ^T3_|7RvF;s5Ta>*oKdJKE3R%>Pq& zuzCEf|Eq3zXHDn-)QxQ39{x|wd_Mf&->%7a{x9A97XDAoygdA$nt6cuKQ;af|EJEl zr=FYtr{lAJFaA&4Y5ZT<_&+u4`{Mu9U3(?`pSrVo7yO@^`Gw5?Q**xfKXp4>-xmL; z&M>ct|5MBVsquejP21+T%m3-|$p5M3|J3+0{GYmOpY*7E%RGNPx?bH}-}t0!%jLw{ z&c%1fzV)2{)A?ogsq6foy0OjE!~dz9*nBnn-IQ;AQhlkDk@%#rltubA59>{GV=5j5x&riDfH~gQP=O6#4#;4)`)T}>?|5G>Zm+t(Zy4^!5&i|>I z2iWxJRKGuduhiC;edEod)l+=q|302OIo5fTC;4t|+h+`$7;F5WzP{Vo{dd26e8Kj9 z4WoJ;$N6?&-;KxmW*#8^Pq$|tApS3G{GXcJM-wNmd-q{AZ{VBtZPQNH^S#eJ9R5$& z%-#z z)Z1;oBK|LI{GS>hcKNke`p1J0YgF`d-^}}aym%qs`Sy9{yb_oA-eRA3;{S9!8vmze z-U|LNZ2X^kvwi-F|5LMmCjQS1oAZ>bKlsAth5V7L?Q2ebY4b(??mNe}KUw{^Sf8x* zQ>>pFb2?XFPq}vc_s4(bJNskvaZ^9@o%6}J_WA2azVUzmne)DH<{jR(@PzMG_Vthd z)A_A6?}z_W^Y}V;-sgL(?Z4*MUB1`b{$G5*%|G4^_WYUu$Yq8U9+3HdOMl4r+qwRi z|G1%`ZGB_>pRN~P)9%|JfBQ#Yn^#@xdz;Na#Q$mkjpp<4f9g&4?;HQ8-fQz~nE$8V zW83k6YUY9B|H8)qsrmf6$FF03v%X*MuVZ}6|7m~LAIJZxv+VQHqhCMed+nhUHsA4) zg0}TB@BX%r?-hFvL={f=@;!IM8t4CXJu~mW$N4{X)$YBV{|mdw;70!X-#Fk|JcI9U zE7sv7e7|DrIpY5?KX}dAn-cy{jbFk4squdJKlSTb`Og2T@qze1^;FxxSmrM|>X*%r ztf~L0?@_iMCH~KhpYwskSFCpaPd#CM!vCpX%TM?}^)&M=_`k66f9j>?U+{nG#dbdU zKlPjD1Mz?A`I~Z`|5Lwdz6SrNp1E?Z^MC5+7cRl;Wt*XM{;$K+&)UyZ5vI=dxp&{g z_J-=H=biXG-{~XAI{&Bb&u!Vw{weC&I}SPjr+#x!!vCq4>^kK9pL+G7lN{gQe(mAo z&i`rqMq7Ux|EJz$pTFDx$J!omiXPu8o9AQCk8ivn{!h2hH$Q;?Q!}3n|EFGe(B|=) z{|g)cr_SB^f%AXrxl5SuSkiAFJa(teQoO}?TDvjM|7rhb4dyxjr*2w*uJeEDR!v@W z{!iVl(?aL})OX$cg7bgsCkDRZ{GWQsi07RDQ%`^5Avga|y<$KY=l|3z2X=M-PuDMJ zcwguL)TdXz>inO2efApX|I~+$?|1%B$ICx_)UE%k-f13h#7D3D>#^E=2L4amY5bph zi~aor{!h(3Wc;7*Z^emso&Qs>w)K7ax2k`y8;+fH{!gzjd_Cd+)Eke!O95c@OKXvb?2Rr|#t~F+q z^MC3t3l}*5r^h$`t+$>3Q@^oxlk<=%Ripiw{Exj zuTh%rZ-sf~m0iw`^?$ma>w95#PSp0c^L@X$VWabZI{r(xUU}0k7pJKw+3QuU+b{L| zzml^(8h*!RzF*DV;ryTOe}3+E=l|4;x9)NNPd#_XZs-5P#{a2T*!t)AKlPjTdW`>5 zzq~lH{;xXo{{GJYsY~29K*%bIsd1|+c5u6oo`=%%>Ps4 zd+>kiUG{z-|EJD7I;_dRKP zzvMii`Mjj5BtVf&fon=tbg0~m~Z@F)BGoV?=k<5|I_jJ z+TZh(eC%o8Z2#rqXMFE7uebTZ=X~P zaNl^nYP(0oy7n!j{PFR7Gs=&S^||H7#QLE!FT@)Er>{@EApTFyJU{%O9{&OR{{P6j zvHt$|+xvxU){OJL>*#yV|7m~xU+?7;{Pw-pm%TkP*6S8e^3CmgE}ZNe&wJj2DZVxT zPshji;s4azj~sLJ|H8)qsabEh?dz}k<83zo_m@|v`NsdvnEHCGA1XdQZT!c}oX^YI zdnoEs^o>}jTsy-z>j9U(dZzD9HvjL^D`)x6GynIOLbH7{4-o(7kDr(4=KqC_|MQ)b z6a9D8ytM4wm!&RmIV^pntp{9w_?x~rtlt=AK0n|0g86T`^?&vI_gNE$JO8KOw=}O^ z!TCS^zO8b@OPv4nzYpwK()mAiz4n!z|5Mj7&x8L{*UPBj{9oAi|9*RQTig^mAHGw%=or)C}?{!iV}<_Y5e!p8rpGj0B0mzMj|CiKd3-j4nM z-etdU{NL;M9Ef$pM-TeWwE2J^4L%g>p<@sG#s`*q{Yb2Lymd6z_pdz`>)cz8r{#RG z(fKxf-JH7b#5&`{6MldE;LoQ|`pz(KHsv4h`flIVKA$=N{aBy8>I2`+ZmSs$DtRi_ z_&;4A&L965HvTVc{9oAfdw=SWhnH;m#AmVocIfA^#{c>2Z~No_e0Q_?e&>DVAAja; z<{{1h>H2gr|A_xnceU&FXr*rp+OAKh`lo&4@oKgB&UYuf{dJwckM%!${otGHkN?y8 z&?8F!>>Gbsw#F~M*}gmdSKs);ei^^{Zg1YN(CvTmE&r$E)0ge~tG|Ex=VO11^|4R> z?i+uI|I_2Ang6HO`oCf0|J3a>$~*t3W<6m1pPG4o_`k66f9h84%DDM|VdMYQ9om#~ z>;Hz${J-BTZgd_nwMkj$|J1eW7mwa(bB@1#gBlfLpMR#-j?eQ-Uhg!y@qGBd8}mvy z56Jv4{GXcjY4LwyK)v$R%Hvdn@Z(Oyu^M7hQ7XB~nDR(^Yo5zp;)An{Y zFAD#sX1?FnhQs{z*sJPM-Id?Emn3;rY?5|64n?tn++@FS*pM|EtCqp4>LxZ@=t{OPv4H_QF>ea{f4rd|EHG! zQ{Qym_0fI5yx_NM{@;~F%KLeM_&+tb$N#CXzy5mX|J2M2#Q&+wmn`P|pSoO$qR#*M zHXn%pQAi#!2VIE*a_!vrtp9pl?|PrL&U*Z=yUt`%$b7PY znE%Jddc*L4?9LrqtN&wn4Q=O~`e31Lj}Wg8|Hu19WBwl-z7PJ7jn7Z`KQ`uv!vFF7 z@a*t^Y^*;F|Hp>#U?uNf9#&( z@!qZ886k+he1;ssCeRybgr;;NQVx4xUKl9gKU8vr#V|sV>f9$X-|HqCP zm8Aa9-I)K!#^2|`|A{G6|Cb^DZT+zitjFFV{zLp9x8EUuKL`KEP9GDc{*T>%T#WiZ zHs}A%A70>@|Hr2Pb2t1S8|%r!|FJV=ec$Isp0)0OXQcYS>g`eL|Jd+=@PF(ynePYx z$L=qU`G4+)|6|9?_2B>5cs#QHfM0$G5}0o%-cQyi@HG4%_lN(&{6BZY|FJPo@8cE4 z)|gL+`G0)==>Oa;|83hb-w*ze=Yt=F|6{|4!T+&S#Cyr_maO3gG5?R-F~1M<|JV@| zqt*Yhqo>5-_fPhC;q&1C_1;k{2#mDv^eK>@qg^Jsj<$lVNY0NzTd?bk9&H5 zot4&jex7qySi|q#^W!pWcu36uQBv?5;Ae5dM!HCeJ7Q9~(Xp z{?Fa;e{9SLg#Tk>J|O%byZ6kV>i^sg|Hn?B*-PjDu`_1%R{zHyFr%0HKX#Y&HhBNY zf9{k0>iZ(bCSksW^{c0MtN-Kn!x!FG|Hm%4{E_-UYkB`@XT5>`KSu6X?}zzf@PF(A zY4|^OVU_>m@s;Ak;Q!nW|HsDsIru+zrT9JgKQ_D{{2%*W@q+MwZ0ryJ=Wh5vHvAj> zpSx$hAMNQ^K8&5C31fFKX$Rae+mD`#{13if4tx0;^pA~*zkSuf9wMB zc<_I0tfveA$A-s)|6^lb4E!IjhxL2m|JXPl{?Fa;e{7r&{!a{_dPj8M?+UEp1ux&3 zYx|><@6NU^m-naTT-JEMSl)}YhR1~e4x+!vjA1&@0xb<$Ume zyg#ge2mi+|mi^)X+ztQdZumcU!~e1I{wwDHv5U^VqyCQ#Uj_fi#ymFoKX#tXGlKtP z?=P!V|HpozFxUC%%5d90<+&$iedYnyYbTDCd5nFmSB)Mb&wsM@#M$>@J#p&|ukMif zie0T&?m7f-k&hW)@S4vZ^22XfuR2+NFxAA7y{6tPLxFCIIg^Z&SgtE|8FM&+~B=acJe!2Ka>jLqqGC$E8>-EX=YmNCk@P9mi_PK!nW9P{F zz7K!;sckP3?;!IXt&7Do!2j`n51#)}{U3YJ$#=xJ)wS*ZiopCoZr}Q5q541e+?A#3 z|JY%@7OVebbNyd-x^IX2KlbR17uElNy^P+j`|JZBp zo2CAby|2puvG-T`KR#c1i|VAFm{K-rH|G&3tRE{j&Zp z{GVM<*58Hyb2t1S8{Y4+J72To3uIm?{2$Mcd4ZUP#@F|LS^pO{ik&0#{qVJcUmvhu zIs6|x=j=K4f9%|I=XL#GcA0oTtpCd{sXU?nkNy0yV>g&BkGXG-`akxnt((>V@$s$Nu~+>cd;Ot2na}#8-7h@zubcjE z{YpWZ%ya$SdZWy9g8$?B(eQt4`akw=@yhUj>~#gj>i^s=Ur%j2=JkCw@=_sxC${xxpeL?`OUmew1#y&_(}wRPTW+nuvNw6*?BUN4(| zXm6c!>YVyNp1)M)Stk6@$+j2BdZsu05NeI}cIEqb#A!bZ=TG*>~VjjHT+-q z@1tygw0ys`#`>%>pWDZuKd>IH%?TdHKw>~Mpuin=S?EEFtueW&AHzs4B`YrT=nv1OA z|F&Jf*t$f%pT05qF+09YdiC8)JpE4DQoCM>d_P`Tvdp^d(#KBwqUF{&{~7-ZYn=Z= z>&NZ+hyROj^@KJ2UwQTuwm;_kT}WSL*N5-R?faysU+wjjH9Q~uAD>S&{2v>>Z*=0b zwtunwywM}>IZwm?asQ(8GVgEe^VaacLpQInE|&Fv|MT)%>yoqQooz3!v-Y39sQ!=V z%R71Ad9n3+yB_@C(iR&$4gbg23;iEE=h!JHQT!j9{?FYt#s9JMLRma89oJKfZqUAI?_)$EN>d@7}dX{U3k-zGnL?>i_urm(Y}0^?&?* zR)^^8)&KGLeaRWk)c>&)#qVJKUw6a*xf|>Mx?60Xb#!Kk`af=u9oSLl|FJp$kKK28 zH%ERK>f`T2Q)Io|1tSWqQ%6TQ%_bLG!_&e4aep-Y9~8U) zyN}HK>u^oE@Ah^10k0>X@MN6|PtR(0%o_9l>U6I3^ntkJ)>wZS{*UMDKQc=F9~<)l z;s4w{`@>Vd-Z$r~&%?aHtShHI9r2Gd)+1#e;%(QSvmPN{@}G6iTf^6V(DZ_*;s1Dk z_&)eQHui`Av-^>Gb?|>|cr*AvHhdcV9~(Xm{*N6oB2@h!J8D!{r*YR0Z9DxRpMQAA zas58F?N~4Q>JguK8vc*x!*=*Tcf|HmFG&ky{c zyW#)Xm?sGT=Wh5vcBXhj_&@dlxgYpHYk9se&-mWc@PE8ttnUo}$4--v$I|D2vimfRY3;DmONbh>V!SlX?*ZahJ zxjYvCAAS!0Z{)-_>H*;w;Q!e05%7O(%=3f)W5Ykd|FJRO2>y?a^$g+v*ok4`>i@Pc zZLR(fUJ(9|jr)iHb2t1S8-4=*kB#|D@PF){?K`Xgb2sMyvEk9+|JX6@IyhMWm))yf zCufKAkf*W!FSo=0m7jaq(?fISSx1Bh*8k=HkzK;o|FNV5t7mgmR4y;q2L{$KF=!+8Ae{ozmlU%Fd__k3M~*2|6W;`MHL{kg9f>=A=I zc>myz?CL##a0fr1!5!@Jg0COE9iG*F{~hJ^;%=-z>TdW^cVm8}yMyQV{aIgkop=4l z8a2H0{cgCyJKwL)4L5qO7wr46p0E3Ug8SB+Z&LsF?e`r5{;$>z>i^i7CkX$?t|RLO zWBwnzUcGwi|Ja!KhxvbOct7|*cf*K^Z(dQn%%DckKMdwBVGTu*SSvW|JsVzga2c@e}_Mc+PZ*T?$1@PFT(>a3m-4gbf+=P&#p8(%-*|9C!p{eu5vV}03rMe}U`uH8DT z|KszE@2Bv8Y|LAQ|6|kt@qB3bKQ`w5!T+)0`QiWAVd4Sd|JdQ-;p+c*|L|b&e{9T? z!}`DMRGF`a`F}hfo)7+yofIRUL+1an`*iQ6{?A(0V}<`?C&VW?@PF)n2?77dPK%FK z|HqC?h*tl{#`?XO|HtkiUK0L~-7PL!{U19$F<$*2J0mGU=l`+0`vU%t-Lrd=`agDG zUxNBScJIVE=f6o~?RxZoe7^dKmxKRfi^L2f9xUh_jmArZ2bKm{2v?Z17rPPcAv3<^?%tBcgE`cKQV9W|02f+ z*8gSq8y8srmz{oRqO;=5bN;Z}CF<)2h~H~>>8y38%( zc>c^u3F`mY{l$ODf7^EYKW<0+A1tcgF7xnSnq25<`Q4B;)~kj8>e3JZr$Qpi7et%>Q&nCZLvW9nq|KsDu{5$wRcQ4OA;FsU=sNci&zu2+g z)2SQxd3y7zw>%C1=RO|(kKIF_PxwDJo^SX+HoPDF9~<)`;s4wX|HsCBO87r_!~eM( z{?Fa;e|)^~d+>kmhX1pcd6$^~=Wh5v>ni`}ZumcIIUfGc-SB^G%qxWdW5Wl+|FQA> z!~eM({*R6Mg7AOthW}&Z^#cFLhL3~)V`DzxUq(G|jroAv`mMHx2kepXoOSP+J)BQF zJ!_5Q7dCmu)9`k8^J5A>QjsAX>?VmL*-udT8Pk0*skNabOAN-%Y;s4lp{lovU z;c4Oj*zl2=pDeZ3d5dS4Si}F-EPTwTepAKQN};Q!bavc50o|5;-`g!sQr0}reJ!}?k9e{6Uo z_&;`u%s<2YKOSE$?^nV9xf}kEjrnu%f9&!v1OAVF{_}6u|FJK85t#qSuJ}UM`xXD^ zZumd;slNs0|G69fk6k7{5dM!{QRV;G@O1Eh?9<=;qW+Kl?sozI$A0_D4?6#keMZ(7 zF8eXWj>r1Lzx~qA8s4wnKiXKs2g3h};ZiSnO4b*K|6}9v!vC>P$nyjL=Wh5vcByQ~ z{6BYN{vVtEkM~>l*%kGF>a{^0-Ec>fjtkB#>);s4mB@_L5<X3=*jP^&{*Mjs zSASHAHRdfoJf^@J?^oBlm}B>YmV2{?|C9HEt>OP3*L7qNj&0e8C#)=^c6Oc~8swW!CV4@P9J1P<)c-nJXw!mht1yAXcEdad}EE0f`k*?Mz!zWP6yAo#&8 zvOoMEd-Kr(c$z%+CfOhUZ|_w{)dQ}T^>yL@7Opy~{_oY2WAJvi{qvvl3kjDf6$L%lgKA`@O z_xsFi0sqGy|KK9|_m?9x>2lQnMb3Rt{U5vQtU2oc*u5TIr2dcnX!cR{f9w^94`DuG zBG13!ScUpO_L~(a)c>*HlGhLXAKNeQcf z{22TnyHI=p{GYqULng8P;uA3ckB=u;JR$raJEsEc**3I(QP%&({6B7=yP`<_A3G{- ziTXcw@0iUx|BpQ&WvBW-_8t9SQvb)M|FfR`jQT(JoCjY}|Ht0B@L~0T>`hhvkGeA2XD=M5{*TYcHwT{A`G0KsKQ{dzyZF*O>i^g!@4V|A?!CdzfB5Zp zodE-0w$2t0C?8+zeDR*UzTB3?*RNmJW9;+I4(mg*Kl~rJAFW#dmz`6!{x3g&51kMA zKlZ+}7u5f;_lpn2{6BWSctH3+cJ7(8>i^g~D+B(I{d#$s`akyJ{5`kw2Q~$?) zV(l~P|JdWE-L3wQ-DvtO^?&UCo3=QuU-;VYXNh<=|Aud^SBv+B|KtAK#Vf=AvERrq zQvb(ZUp4=ajrDWk|JbidWBwm|o6LWL|6^l*DdzvNF)tPVkG=j#zWP7*mZEa?f9#j! ze3<{|Zu$D`Kh?8-y|Bc&^QYUa-;nuL^7Y<&+fl#zKc4@w z7hY2T$Btd~xcWbK<5@G*|MB{F&z`ORkG);ibB6z8@0G7_@PF*GlP4VbKQ>-3nE%J~ z|pGkH_}8-$&SX%yX0Z+CKigfbZurf7?3y;$`)J+@2#I z5dM!19|-@)pSMci{Y3pAyHL&#|Hm$pd2;Z7>|F6^@PF()`S}n2kN;kQe}n&XH~gQq z{Co-j$A-^?|6|ktv9TTgkBz@Sf&XKd%Fj#if4m=fNBBQB{vHMXk9|^(hyQao{2#ka z<{P&Eew>{j$3O75@zyvV{*Tu`E{_-fj}0#e|Hp>Mga2cf%KgFrxqEfPnZDEIhXUSD zJ|6IYY&;(LKlVxacwAj$uBXpC_giDV;aC6lfOUmjf9~HOvOXan-yYx3v&MS7@P9l% z=J&z>{WtND`ad-M9~*ui{?Fa;e>@((5B`r`eBrV)Z~Rj0Qfc@v4)~DtA&2k>MJ|*AJ;s3Zl{2u%tuTTHS#=JxLKQ?^ds??{gk4eu-e#X=A zf83w`&)x8UygvS(2L6v-AU{9D|FKKXTy#F~ytev$r!P1sI;^uU6#sXi-3!(Qr!F`> z-g?2F??RdHH)Gd&Pp{dr!MdRGw3D}OqqV=v|M7nFDo^PAKXy(oxqJwXFABT4RfKjz8f4xczWWVE!LpANytAALjqD56OIL%>QE_Jap7~?LXUmT@D;f z8vo^@Wc7di{Znj2BPXQ%ppU_Q28c&gPRvKKY;eJ7^?7SO^uBfXQQ^)HOFyuN--Q3;b+{?Fa;e{6V8_&+x0 z2g3icGlmA%|8@7bHUDX^mjQ#r)&KGJlrgZY`ad?-2ZsM+V;&&*`*v3U#}2KU|HqCEYwy%Nca0q%Jg*HN&+TV| zJJ@@{+ojc>p4{{25ShNu@DF1~F-w;9Qww`*^n z@8^ayt>OJ1yLy&2<`rT7ANR-ltnhzq_(J$Ucf=^NOP1EKjM|5weo)0}UY`!)83H%@T zhc|)$`5WJ}6(5%;y{HTf+abaXkDVJF}zAI~D)O?$<7`{x2KnbH6@t zJ$J`<^3InG-X7J-yMJ)w`Es8R&!@YCy;<<}f;+mscYaW}_N_eUi`&-+q-}Lx&i;UZF8vlKXmQ*rwiDa z?+5?K#(Y2cKX+sOUv~Wlb=Ci|8#HL3{?Fa;e{6U^tpCf#{5|+THvApd|7FA9eLeJv zf~-|t)c-}cZtm=F`?zfnYu?zIzjviI=JoZ8t8RF_$vq!0c<8CF>i@7lF8m+6bF&ue z|JV)1+hF})Hso&UnFB|LiHhN=;ZO8TD|F}J>Lnr6#zZTp1yUM&%_&;7B4gbgP6dI!b&)x8U?w&bu zk)0p=WBwnnhx5Vzv9Uhzf&V^Y-BP~(!T)V~CQLnG8~J_#|HsC>H26OrkI!%TKkF+0 z$Nk}vvHmZ&M?{6G|Kt6l;s4l}cZd0Z+&?ZlT>T##^G4zS*!cbo|Hp>!!}`CxJ{t4? z*qs08Zumbo=JWkAf3~Nem-TNIg0<|_2N>J)&E&{_o@G5C-g{B|HsbinX2>u z*!@#{>i^hrsj{A?%>Q#Y{2x0xIa&Q5ySw-^%>QGLOzE!vk3HO%tp1Pf^Z9iC9~;MG z{vUgQ+z;mevHSZH)&H@3$oa;t8Eel+@9wGU|M>h2=-xy9AG=?oPyHV|wtIs5KQ^n}7TrzpRO?z7IVr=aO~!_(=7C+#YdP zl#_n#MZXw2^?jHZ__x2G_cZ(;x5N9v|FJX12Il|qd{N`0)&Frj=B>g1u~YAgb6#10 z(i)G)_xK5G%nyYBn{@b?qpOB>fkJ~fv_No8l{S6V1h53JM zcs=>ujx~H1=Kpa!)-Q$sW5WZ&|FJP25dM#i^Y<;vxBJ2QzuK2)jq}O+4xWbp-_(Q04#J4gbgX-5r?!$4;IYtMmWZ@PY7u?uP&4i^iorzSWroO!%@fAM$Gg)2RM@vRls zn14BE%W~^sQ&OBdtCv}0{@{*RxJNz+pt_&>I9MtAjp?BtoL z>i^hy{POQ%+aG=Wqj}cwe#`w2dAi4@2Rse`$Ma>(@~Qu0V?H4KAG@bK|L}k8_VV$C z|6|`WIK+Yf6BDHVZ}7x{>i^hzr;n=tvzGU#vHmZ+P~M-G_pkiEJ~`_BuznQ$AN!>E zDEL1%ydV6ZyXE~ePs{sj)@9|6{|e!T+%<*4u$^OWBjUQzDF z)AHW1b-A1m{*U*I=Udit%jf4S{BGflH$2_)f!D45;twBNxYfE)?*Fruo2)Cv@AX){ z(HiT)$@*Y+z5O45F0ZHOtq*?srTEcjtT8|I(Z^TW^MU!HpFFw3`m~&{$FobUkBcwJ zXur@pM;i10WDR8Xg9pV^y%RaxwwK8IWG^R7w#NEqccqTA&aSMKkJoVP9XUDb|9HMV zuWeHQ$DV%IX!U>W9^*%<|6`AtKUe)9d&aXH;Vta`p5C9Q{*T*N9xYS<$6l2u>(h$= zW50Q%NIYZ>>pi)pSpPbY+g~dv5%2he^{e7%zI*PIyocxIsTbTV>+>#Nan^dL%(oIh zWc{M}Jz0Cvdh?0XGM{j>^+9=m_RN@Pt@l@)6o0eGdPn6+x!#@DZ^-eoKC<&DtrzcgRc?bd`RW%#MvRhwUpWqY)aViF z|K1tkR}Xm4y|dK+vG00xf%-r8Lu*#!e2F}M`KB%E|Jd7PKB4%28T=m`>;1z2v2i~5KX$J8 z1o%HbzN1zCkA0v#;Q!dqzn+iBYscTeyh!HNb+C?4UoP_syIH42ZFUx}inAV^{D%5J zo{#hY*z|ww39|$9|JbwUZBYNm-o7lb{xAFG`EzvsAG>J&9nQ_S&9m$0+!t8?myiGO z;z{cN*kA2`LH!^5sQ-|z|I0pi>6Fg@W9MGFr2dbcBl7^^|JYd1`Jwk;O5*F`=-cn% z<7-X-$L(nNKlYLLF021z=X?;D|HsagpT97Bji0Y*SSt3uci&h4$HscX@PF*w3zyXY zvGc_%F8a12iC-V!1Dkw%!umjktVjFJ8SCugVrR%V7p!;7`iDPVdB=LouI=joc>a4A zJgEMUJ>sEz)c>(3uUM%5k3I6`&FcTy_Z`XA^?&*JUpZQ={*T+Y$k#W_|6@Pr53K*o zenI@4%n$YP_|?+zf84%CzMjGVvDX)rtN&v^8y= znG^DJE$f$x%klNu`gK`P9R82{qv8M9+oa+D*w4#)@bG`^8E@`U|HtchnR$=;KX#9M zW~%>V4_@?$`ad53`og8^|JWakXN3P_`}2y_|FMsYuYvz#7o0jT>pga`t`NTp|Htiz zWq#%18KFM@Jd*wH2Qojnt2O3bzV>}L+aDef{*T8W7w-rE$K%oPf9xFbXELAL$DdDf z#e>Pu@77q)7yggi(U|{dE%OB7|JYbx82*oaNPb?0|6}9t8Q}l;^UqoN`2zlreMa_& z|6`X+!~e1I^9}qT8-GuN`G0K8zr*^!ydM5O1?&I1d;N98Y=3yUubmOr@Ov@;8EJi9 zJmHFejJ7@}e(#;1$5_Mj!T<64X!t)id?WlHyFz>&{2v?7XRFSWeY0|oR(ZaUouAuI zwZ{6%#m%RC8vc*_!|%cWv2i{4KlT}E_&@e3*&qIoeM}nuk6j_J2lzjBk@!#eKek`I zDEuG0Ouj$D|Gg4=RQ(_3MZ^EG@%^@V+G5+kP<$Z#ACE71JK+D=I6wR!8=mj3vCBN2 zK6<$|JYK|z71r>4@PB-MPs{yXGw5;KenS3!<(teWtPAAlRro(%uTXv-!2CZp&i|_T zKX=3bv9Vq-{2%+ccs}?)HqM9nf9xXp{?sXYwKe=+y@=;M{qL@8tV>S6t^SY4qv8M9 zMdAe;A6#e8HyZwr&wttR)9U}+4gbf64}||?!~cD``9*8^zgjQ9WPPM8u>LQvpC|qs z{*O)n$Ih?vf9yPe!2huiR{1|(e_!@d^?&R`hmSf*S8em1+k8a5-+_bK>i^i;yWUj) z$6hw?VdsHgUbp=h4N6r1$KOAW>Do~JAG>4fZR-EnQT<79_&;`XdJFY`?B0Xg>-;}<_aR-KoLBumF?s6wdWe6zV_$(a)(8HdztFmm%)=A= zW!-mFg!(@o4-W|c$L=lb`NIFXd(;DEKKWl@eO#H}m$anZ)9`=XAM^dLdij`V`xiSa ztucSF;_z|nH1UEvOHNpi7#*wrkJlSEGFtr~yTABA_&;|))a{J#rJT}$-;?u=PC9E1 zPnVo_&N@rF<ka;oJy?7q{GYqw|Jd+{@PBOV5C6v= zCi5cU|JZ}&`G@~wV}2w29~+(%{*OI;Xu$umhl#I+|6|ktxx4MJzuD^n^8~NI>UU4W z|MB$#zliyNY}^m#|FH+id_nj>cK@tS>i^i77l`?P?uP$kV|`)xKi*$InI{VW$L={G zMCbppQ~S45|Ht;Fg{c2yhsNISRGhjxndk4@rHylR@HN(HUA;akc)nY3|Nr?v_xrb) zHwORr=%&u<0kJ+R{2zN#bb|W7GY2}U{~OySLj7OM%8nlY=Wh5vc9zUjg8ySHAUu;{i=fm~guLpP~ zcXw&y?eGxq{&+sz`}dUlb9WD!_w|2ld4Ap7eJxvhI{1F@{JQrKzW>gRZ})6Z7O&*q zzju&VjPB_5cER0QUQh1hgXisa?d*Mg!HxNv?&HHky?!xx{!#Gtg1ukxdcMK)Juy$x zeZ64s7yR|%#u{GVchmJ=-&Z5Z`vrIH8rOTSck}f(c>2%g{{^oP+2khg`oFd71^nOW zLEY5<)vaG!{U5t#gPYa=x%-LvPZk{R7p7m&Zo9pXbIo6>8~$&>v#V@-+gopU{@$p% z+uhbc*Z<}DF#qqbU7xW1;s3_vJZ{~%abxEl@p`--Jm0`GE3Gka5B`tm!#qFuKQ{dz z8@}$Tc`FNQq=u^>Y}>54lYLEfV|`$(|GO(KLVaM<#sUAwZq=f#`ad4uzF8aff9$qR z0{)NPpj8W<|Hp3Fx~2L*Htq-hkLSnwyYPSPcJleVxuv(^|F|6<5dM!HF1{81kLSnN zU-&;ZJTUwp8=p^@|L1P_KQ_FdFKeNvpPBHeHT*REAFogU$A-7vUi%T-4v)LB`2tVF z|GD>Hci@VM*Mt9K_wUh5{U5teQnLC#c3<&)KW2`x{nL}X zJ70{u!+J2mijMWuMQhsF1D zuFU`3FEi@Y(}l}C%F5}VS+|#Y%J6^3-#w`wFfOvO`akyYL2>H;*m1JHE&LxlUOXNA z9~&MH{?FZ*|Htk-E-?R(4d3_D`|sNQ(Ess%d&b>n3bEn=fK|B`x zAG@F25B#6I;s4m2|Hp<0EG<7{+u^G)|Bu_z@PBNaAO4Sx^?&8Rt#N+%KW-m*SAzOK z_7L%dnE%HfDqc&hku~P|Vg4VtW8UB2JC|8!O^R|>H!ZauaCd|wv(v0GukFnLimWk@ zZRQV!)|l^B^OFK=>@RCESi}3l|MB{RWq<79_&;m$h46pwhX1pcQF!ej5DWJ^wte{%?q^7YzT$9y&GNf&XJ;{Z{xtcDk(Z3jfE(cKAOww!{Ci zF+VM9&zpYvo6f-BlTM9u_H2H`deFoKo&U%Ev&7#`TeictV}4`BgWIj)`7r;F`=jCi z*zkSue|)_3f9{6=W7Ge!>HpaDe{6VF_&+xGhyQao{2v>~|9jGlc7OPMhX3RJ;`0su zkB#-KZ%tTl9V^Gr>HLB<<~yEky3QKDu*=PBt>HW2|9Jfj@qL*8$4(b-hxvc(o>ODg z|FPlu;Q!e8cw+vayW#)X@Q3h!Z1_XW|6^mlU(Ekw!`-{*PZT)9*=E z|Hn>~hW}&toh`mt{GYqw|J?o0{rB4Wd&vC1s5P^#yUTpQIrq=BZimm8VbiT|9@I+x zpBN$ae;G4};{7H6he>|*e1|Ui9eMxBx=`ld$b1Ux^2-7L$Ni6g_^C7QfdT&7d-C=D zp;Mp8{I3Q5tub$`@Ue7j_$&B79-k-k|KR`Fe(_ZD{+sn_@qj0~_Ow1F`!9%0wLU2x zt#e$8^=a{aA13*%;s2gWO|*vpo0Su1_j6V}-=@MC>+>>y?{s;Tb=fyRI{!TxVO=Wo z`$8{tv#yZ!cE`Ne)zeRX9BO?+eBks6o%|`y^7Z|vlV5%BG@9PQ`keT}ra!m0{c-*N zzqhr;G`2qW z**8wcjSa0UKD{FAH`TY}Pkj0}nfGw3HJFmH;_nX5``Od=7k_VkQoJ7gAJ2C}_J{vt!|%cWvCCwC_&+x0Rl@(t zOg{CQX!t)iUXR7Q&)fd!HV02vx4izB+wgzvBH17Qk6j?whyQbT&AOZN`Ssw$N1r*e zo|mU(eK6Y}A0L@FVhz6u|HtRAM10`Z7OOlB|HtRA^5f6c|FKKOC&T}-F>mOWE)QD6 zQ^EgnJLaFj|FJQT4gQZ^cIu4!KQ`V!{C>ay+n#@9zszIoW4(Owe3`$PY&}Z+pLhoA zu@lF@M_4=aR$#qv>(K27)&I#F&gvBx?=MjQ$9^I=;Q!dKiid&!W51SPuKthxYL)+E z!~1o(@^PMZeu4Twm?6v$+$r-?;Q!b!h|h!nW4|o(?co2|hpYS_`;fdp3;)N)`fc!k z?EDjF)&H?`%1@~OV;?E4RR1S4|J45-I+CaUkNw=5_3HoFS&uw`{d3vP(|gLlw;UKc z^?*+APVjIE?8GPUm0oN;>8Tai*LueDPpSXo{^MTRjQNC#JpZD?BK3dltuj9h{*S#& zydV4@JLlMG^?&RVdH)^$k9|n|Df}NB^Zn$%tuZgIU+Z(8hX3RJ6^WOD|6{`g!vC@J z&c3VuZ}uIFWQu{mcF9)&H^c3J$CPW1qcnT>T%r^xOrf=b1H0 z{P>h#c-#5t;(BZPKW?Z0vlfqcY1+0VzP|I{zbxy0@37AO@Um0uo?X^Cmp{Pgo3+2n z|MB<&@mBDE?3_yh|L1P}H@ooS+gKkyiJ$L9Z(maX$HsQ}KX&$slj{H2SU(Z|kDXmq zs{YS9=ZN}0Uhg^av*L^G`ZMRa9Gyk zmid3|Erpfp|JWO4o*vf!bvNe!vDXv^=KrzRmmXLD$9_Z3hxvc(tpQK%dz3S&1 ztoIZgQ~$^9JH-3J|FL(9Uxxo>~O41pmj*7S9L&$M275_&+wh-{7g;JiTRdgf-SjmA|j?@%w$5_%8YT8|!@W zd+>kUUMN3L!vC>L<>wRlKX!@uKKMU2)+2`hV;5fz%>QHOUjA79A3Oh}Pu2hN=b4l8 z?;H3(_Hj8M{2v?h@ZkU0od0Jn_Y42$Zp{B<7l{AE{6BZY|FLm?_&+w*zlHx}!_UG0 zu}{nX@PBOjKX=3bvEdgVi=E)(&ui#G;S;M{&JX{`?YJNKKX#F9hyQao{2v>hu;tiU zKK}a$J!jZG)+b~>U~%Rg>yzRM>-D+M8h-HZ%srI8~%@t^?Tv}*qHyfwcvTXeuZp5p1a1=zhtkq#(Y5dKR(}R_&;{}iNO3ncf&f{CG zb8`K<{x8pe@X!(G;&re3?t3~?a;uhTot1`1`u$ z_s&rN$L=BXe=z@#9h%%g{U19~)^EW4KXyV!d-Z?pI9aa~^Z(dgGD6h-;}9 z)(6J?KX!t6Az2I7Iz{HM!T<61uc<@B)c>)&4+~ZQ$L={YO#L4l9uV{Y*zkaB?|L1P_KX;#d?y@zWkAs^&w8rr-y!laekLu<;eB@*6{__6M9c7Z|M7b8dGLSkhW}$@{v!Mz8}k?8|JbADdhe%xWzWwYcZgTa{Ms7( zZyEJBPcNBt#TtHa(wuKR4gbgU!#~3Rv2j1}e{8H@4FAW*e8RVP|7hpyC-eS}9R11D z8_RyShSz-L+%MKchIVuA{P6GAm>1aNZ@*e&o*?`mUk^Ax{GYqw|Jd+;@PF=x|6}8P z@PBN~6U6*KcGlp|>i^sg|HmFUu!~bC%t>Ys7!c}Qb-23I2exy5PPodpXJiHD|MB_i zlhMJs)aPp3-YvSG`ahm8p<6@sf9#})#?Bk>U1R$P&rb`U_Z2*kEqGpAw@zKv|Ix1` zM#roFV~>r9ah6^;E%~kaq3YX4$a=RIzO8OuANb;Q+m4=_JHs0DAw8s6y|Bad6 zMg1VQ!~eM({*Mhm2LI=7_&+utFZ>@Hz6t)%-I)L9ZumcTfAJ&mf9!r8+p7O#N4IaL z{*N8mwu$;bHoP9@|MB^OSHt{2cGuR;)c>)=#M8n5UHfEb^?xz#TB-kY_q($GFVEkp zO@Mv?oXLMwZ-?i@{J$GVcU7N>#`?ePxDcj8tW7wr2In|r-t@bQVAygo5_-eK^(M0g?h<~{(}3@=KuZK z`oA~bbd%?PYS#36kl^`%!R^$psq6pNy*5hy-!*k_R{zKT%kA~l|G69f@5kRF0{-u| z+tmND>({TZ{*T?RK|S?<>^Al5Ix}B;!j5lz>uu`)xV_;m_0<2dG0zbGkKL$IBlUl5 zcs=+(-X9wNkKMFsQ=R|kZur0a-=oz3VSo5PcFRVM@%R1K@Q63ouWoF|{6FrG`GuJO z$A)Lb{6BV`Mz=e;e=IBbZe{9U- zga708;aM-ey~v&qtatv(xax+7J$rtkZAahr*GH}4XW{>NK5U2oW8-?C-T#O+ykF$X z1=jGjD>lye^!vN!S;Oy!7CdZ?&u{oYp1*0APU`>Itz;aLHPEpnz>;AI7FZ>_Rk9oWBf9{6=W5>w+-k<+H+tcuWSJ#VG z4;URC@PF>c`oBCrEGAn0A3HoQR{bA4EH=vd&-GL7{_yxR8&9#0?iQ~8kNZc3byNSx z$A|UQ;s4wX|Hp=3#QMKHzI#-R`agDZe1gvZb2t1SJ2o!h|JV_cG3x)=@Q;}P$A*9W zudM&e#(YHhKX+ejJlgJWpnSaAbs1%idB^a7+#l;P!~e0dJ}>+qJ1sd;{U5uhcs}?) zHoPb1|FJP27xVwv`22$Zi_Wh z0sqIw{LSs7Keg^Ee=oB<{S)f}BVyG5Wi~yhJ`n5g_Ut6<{Z^eXT;}byZ2X}$*28sf zx@-;4_wm2px5j$F{wwc!8vc*x!~V0w-|>sdQ{RWK-TIO>JQDmLx5GEV|G69fj}6ZR z|HtP1KQ_Fc{I_k#{=?dy_WvGnM!gyOVEt3p>9RlkACHFz6uVwc3{@cSw2beaDK z|HqHV$SJAn|JcJPrKta7V?9~;KX%{gDeC{&@MY^Ncl#6WIjz1AzU-IWUDohk@PD>l zJQ@5S8~(87^E<5vPmWdp$L#~eXTtxnGbctmZKu6%jrE0>-tn5J;s5yYfFH#CKX=3b zvGIDu{699>+iz<@$q8)-A7ifvh7K7z7G~WVU6u^vmUp`e9iUaR(krkfh(-> z`7tDQxix&?{)lDPnD1Ao?NU$As=ve<^Zwxf?EYllAN(J?hj>ExKX!LHKl~pX=da9I zV2$~JHM-2R*7cKbe#p~{e!SnhkNCm-b91fX1*5LN*Y2<9?B34LS7uqK$~?e5r)F4p zn%N-qRj~5;f{*TYc=_>!n#(Kc;e?0!8tVaz0$EN>d!=u6f@$u0Axf}kE4Sxv# zCo|&Idma;C3IE4FDf8Ok|JWzQbHV@d`18{L?s}`;4;ucD_e1~3hChS+ga30k{2%+cyguRoWQ|_+f9N~6 zU$X6ZKH&ejKh_6^|6{`!!vC@H{50uQZud|B$Hz1%zh;f=!T<4i+z)(&X!U>W+lLKS|Hr;Y{@x7#m-bqj`oF<_(%|6| z*ss2@0Y1$7xgFcp|8e`)qerlRB72LxKMeoJ^TS7C{vSKL z^AW9&$-E))lh#MXBf$Uhc+9&J3uT=z`@{cnd!G0{S-;sD$HV{ee$nuM)@Q~0wYkCi z@acENx7D>iTIK(^|4Tay)c>&`tnzPINPb}cAN$1FW9t9dC1=m8|Ksyd|Hr2PWBcF#2p``he*E`|_k;gq zAN=rR^?&Sa`S}X|k9}DDGW;LAu*(0r8*8ib^A|o8v((s_w+5TVJ}&DAQE_md}qTuY6#=bKe1ceX)M)>8G5szkP1~ z?5vqO|BsI+?9oSb{vW%~+BNF`*dyOOp#G0Nv!Fu#ANv{kdI$f5=H_O*o_&@e0e<{8` z`}p;IZGN#cb!lDerMvd2|Kt8ItbNI;vG_LIK4aRw_MZ`xGMXSVKn_XNyuwq87S z66QNwm+gK7-#@JVhjTC=+WNfA+X}tEwe@b9?>B#LTkE~zb1?sp_jj<$|FPkdC(r6+ z`yZ0mAN(I5?_t>v|HsDHFPV?+w+r($LnE!AN(J?MD8E{ zj}4Cp|Hr2PW1p1c<=;m>{`_-7=KsmRpRA8aJJSYRV_x>z2}7;n?d0EQ);PcX`^_5X z>z*~*`ncR5{2#B6{dwS!P z`PSv)OJ|IG#G3w(=Y!wF`oHWFnU{C++Q+PmWWL|8&Js^I{jaOff8g}~=Th5VDD!n^ z{kqILTfE)6pO#x6k)Jo=|M>irir0hxb2t1S8{hBY|9F3XnNJA+$HwOu{2%u}TIK)P zm^TRj=Wh5vHvJzP^RMCm*rjJKIrB(VO!$Lr_H&zJCj?uP$kV;&&i^hi^gW-rBGJkG z2g=%>)+sVy?ZALyPs9J&{xUxh{?Fa;f9zi3pWy%84gbf+{6Y9XcZ)spH2j~KKJ|a_ zi12^xe#0Wv|G69f&)x8U?uP$k_ZktY^Z(op|Hp>5dM!%|HsC5 z_&+wb!~d~I$oxk5KlU*3bMSv`_&WGMcfHpa9e7{Hk)gI3TS^pXSkI&C|d3^AH zZ1_U>KQ`8DhW}&ZeDHtnPJ8rQYxu{`Pkd*M$5(sZ_tx;FKW+KJ8m~wAKb|jMJRSTW zJ5jd7|FJWNMyUUDH~b$PuRr)dcG}Qz^?%k?^Z(fJfbf6pO!;`i|FJXVdhmbj{xWY6 z{?Fa;f9!!nBGmt}v7RveA3Jlf%(oN&$Ii&=qW+KFQ+zP|AG^n(Q0I%H>W)hf_&;v% znAk}DAG=>CQUrusj1gX#mM@MnEyw=lGZ9j z{ofA_x~c!`*|fF#KkH^KoHpYB*vSnWtN&xeqrm^MyNaKJ|JzV2T>T&Bt-=4Xu|6dH z9~(Xk{?Fa;e{6UT_&+v075pDNPUgkH|G69fkBxbR@PF)d@m`q!$A(|S`oHeR{6984 z8vGw09~%CT4c~|Pe{5`r|Lf5v%rpOwjrn$Oo_f^whu_2eKVC0h<`csIvEkMB&Ry(j z_`hCPN2mu3UavQ}|IEMrncoZE-aTlZALb{zUw?gq)(0Nk&g3)8KJJ|aL&+{D8xr^uc zfgxV67<|7`oxC59o36dib9}A8)bMn$?+fnW^?!r=&-~x5H+y|xaNl01uG9STQw1Gf zjZx3npzbZs`bpIde^>XXCv7_#{*U|Ldh4y~|Jb*Q2gLk8Hs}Ab+tjPC{*T@G*4obX z_dQ;)XlJy3J~gUW%W3h)O6yv;->UwP``2q4@PF(k^7R(}ukui=`o-qrQ{n&EZJIVy z|Hp>+ga4beH_qe#*sU5jQUB*|_&;~U|FPi<;s4l}R|x;d#&-C>dd2bT|60oYP53`{ zNXx+dKQ`w1b-J{~jzLNhe`uSI>i^sg|Htdcw(g||HqDK-$DH! zJG@1^>tW;ny(#kKIkyU&Z`Cc88dN z|Kt6&6|V;W$A;HhwPcFzkLL&T|F|9A8UBxr@89r$>zGC?Ib^bmvs-B zPwe~KU3Pvn{2%WRf6vhRrs|Fki&X!|?RY%!e{A?m_&;`HOsx7pcf)P3QIAx@5?;zXZ|9Cv+^}+wK`y?c(|6`}hJU#e7Hr9KF|6_L(k2_`0U^{>7kVfkN zc>Pi1vef_a^JC<=(dz%$k@3;$|JY4hbyEMw?$j+_{U19nHbMO#&)-d6f9~&B!Siab zzWQp<_TX;TteIzf9ht{_%{QO>#l)$fYb@S%%LkuXhlPi#|Es_8qI$qCVV%_fvBMH> zRsYA%l7H_^O!(N(rvGy{{2v?h{ow!D@PKRXeBZ7Q{}++H8cf^4c;WvZ+wzJvJm@E@H&yrD$&PR7%hstAQ=FIX zf62Pf-AU^I`26*f*DvP(v2lL*KQ??I{GYXWJ`V`Kei_&+v$AN(I1 zA8+_SHs%S!|FJP|5dM!%|Hp>+ga2d0_noZqn5W_Y`0=LyW7Ge!vHkIl^X+(ezg~|# z?CBoj|G0n8>D?XpKQ`t8KHPS$?T?24+Iy0$E5wKS4klQ`zrp|U`frQJ zga2b+l=H#=v9Ufd{2%-H*WWo~GP>F0IWEW79MaYLnD{REKR(_{xgYpHHs}AbFNz<8 z|Ks`5@PBOhK+OMRpZn`K&hBelSznOrU%s)0^?AAfnsu95!wWwDR1?3LG4-67U)N)G zBWtW@`}cJXJbj`=eLEiW7vcYSeRxXvKQ{cAbLM7yeDGgyU8-fBFWwCPkNac2Sol9S z{T~~i4*ri_D32HZ&)x8Ud^}h$8vc)s`F8MsY^=8n|Hm$s`HApi5|0gr`)JLM> z|JbKw{vrGy`;5$!g#Tk>ULX9QyW#)X`1r&B9T--j{tpfR$L;Wb@PBMP9{4{tydV6Z zyXD^P{*S7ME%vm`cCp6u3;)N*i-!MW=YRU8&i`{a{2!n10(t)&{*R6If#LtySU-68 zwOg(6`40cb?eK%}e{9SHl=Z=^kIDPZ@PE8Mdg7j^txKfg|M>We#S6m!u}kHA@PBN~ z`*~*aqtEmHr-9{lR7>i^hF zw!fwR52gqHZ;kjBtpCg2aMZ8U#5{<0J5|F}J0=4-+Ku}j74!2fao!rT(|f9z*o+oJxDJ!!#1>i^jBlkQai zSHD4}`oHk8Bh>$~|1xs8`akyV)27J3zZ{3%>EVUgp1>ZsX&a8WUbZJ2=eJ%h^Au(O zMDD+-;*9z~_AAHEs{do}mHB@1_!4=)`;MPg|HnQkJ`(0`_Qtf>i^iEytPLCA3OW#ex3ivK6NJG|JbFc z&#C|8^I0kD>0Ctbg@?>kk?Kyt+f9%6=>{9>7UiZY4>i_t7hCMJ#{U00a1CM&?M|->@pIhfdef^7_ z|NhrjzpY=C`F!&A&w8t@?+gFO>!acS*gNIx6Z{|hb@6^OPt|%~ zUWxiYZr__zB^q|VkNxttH=QGo)wBJ_Ke15# zAGaq@8KeG>-Ew4>`agEU-0AB7*fSn~T>T&W#Un@5|FI9|7ODSZm&n&A_&@f+(*gg- zK72Od|M+zRaPK zK7Rkl_Dut$tq+`kU;Q7qAAR=|^?z)5H2M1;+rL2k8T=p5pC{*s|8qC|ACEsOUytGc z*zki`|Cdew$EN>d7mCM&|6{|;Vf|k==IO!z@#i1>y%hW(8^_DPudH!A{2#Z&7sCIs z>HpYRpBVm+jrED^rjN0P4}|~Y_R9A@cHsZm74rPR|FMsYuY~_&<9^})*rhU$5&n;j z@z|Hp>^%c^*; z`hMl}8~%^?kNL&v1D>ybKIQ8J{GUC)((r%mqALH##(LuLf9#SIr`7+t8~%@7Dt~_h z|HsDszh^qWXq_iNpThs~{?PD$?A)?r>i^g|vK~DAANxpQu~S-Oi#>jLcFh0d_MCze z^?&SrhjVoPAMfXlgMsyb*{|&l%>QHWtMY&B=bl}y>;JMBJreML{QYBOw|46P*j>8c zrv8teJgA-eKmL9vRp$H2?{|Id?lRvG{*U`dR{1}7UznF`+p#_{{2#Zc4C<)i^hSKNtnQG<7sCIsyR>NK-15XM>+UT&I(OYW+d8#n!2ey^8>K!F9t8f69o@2n z1OLbF+`5DMKX$i}F6#f-nC}Gt$Hsgq_&;m$A@F}}csTe!Yw>CDf9!;iPR^=4~fAmW5GVYH*JdL|?{Qs%b#M8L92Y2xLzQO)4*y{z)pX?VjPcQiV!Snc{ z+IjsQ);o6JUvLMnAN*$>?EiwjV5H24bYCynPX^E5geP+E9~qXVOMg8Ah0}|B#MbxdM{*MhG2><79_&;}J{a<&(|FK)vspni8^F%@JzN z>TchnrTV{+NlAhAe_J%t`G4-l{6BV^<_&fJAG=-4!2CZp{2u(DyW#)Xm`@7-*ZWbQ z`ajGkh5uuBZP{Aq|FQA)8~%^ShqY>>{*N8rrk(TX*N;_imwx@;>h9LIz0UvR{#c*< zlFa{GG&xayWMs=W>i?>{sro;6WBwl-_XGdO^K}-F4*$n)(5i*{KXx(IdbKQ??X{2v>hclo*p?0#Zp9$l^l@!M4EI`aC){6F4b{SNKa|FPl!wuDZ$?eKQ+f80+0=Wh5vc2ZcB z`agE}$T;ovssCg5l=W**4jN(m_l{3g|Htd0vHmX`9uWSIJtQjLssGXt zJN}NORP}#6f5?cz>i^i`ca2g1$Ip)@cMMbi$98i^hTU8B_hv4@1m>iWMtpD!+6 z{U2NBBc^27{owWC{(f^^jjKJ~?>et9pDXjB-TT)}NmTzQrcV7|ot`P`|JX?>(dz$X z=AQb$)Lsed|JZ#qI;sC-4<9Y_tHuAZW5xd*efmQ`≤9XT-wG)|h|y+w2dl`^);c z@PFJN^TKv!zw58D^Bwhi$>RCszpc~9h&SAL$-3Vikxt2~x2@p`TRw8pn*NXHgV%%q zW5eUY|FK8jnWX-YJ$!6}1OLayd_ed=Htrw(j}4y$|Hp<;g8yUp6u$@m=k8GPe{6U_ z_&;~U|FN+?D*PWC9t-}DjrC{Y|JYc67XFWo`F`+!Y#iTA{2v?Z3B&)f;i=^BFa7;L zyre!3-b{W!V+{`|zrU$&@lW#iot}pO-6|FP-+*aIgA z*8gS0S2c6?+x0Q;Z^6%RStm~IuKthvW4%@QKR&+n$*Jo9*!?DTSN~@%9uWSIjrCsP z|Jd+|nE%Jd{lWjSv3@N4pS!XCFYhO7N?`q8ckjBg&9>wDy7BU>*7$f#IknZ(<^C<6 zhX3RF@cM%PV`s|8AO4RG4+#I~Zumbo{3z!Cxf}kEjn@nO9~=G-{*R5@HuSfVl zHeQeLe{AfJ`G0KqK+OMhH~b%ap!h=gKQ>D7u2Q4|Hm8Y2o=v7)gAyG9YE*Il;Jdsk2q0ei18exot@U+;VNb8*jnf9IF; zJO7-Mb9kSp%rno-&MxkY>u!^J!0$Kr@1d6Wd&~c6f7Y|c|HX~}Q+K&6C-^^g*D-CA zOTM_v&xaRX_3oYCyg%@N+P{;{tHl4Q3r2Se{!fhuWd5I;_b>iWow9j<_&+uC`x^iA zR`1?d;K~abUcm!Q}?m;tq(c>`iw3syw+R(Py5UNse6s<5$6A? zyV?4`%>Pq&xa5pv%-k{F`D1c||NG{y^}+vLJN3ro%#vZ{b-!7c_IrCbCWoyU;$3O; zY?iJcl+mNN5AbGw82(Sk)A&F2nyUGKYJ6VZZ+iOnmA0Pj>pyn)USZy9@_)K|Z`%J! z((3nJGWx)goxRtX$HM>V`K-3{;s4Yt%;Vwz)T_+PJ=3g%ACHggm($K05BE!6j`vpc zS@=I4zunG<|I_nf{viG@Zv3B``FkfFXk32w@O9z$S@^#mpEdMm{o(ajH}L(pe)L6h z!%g+Pci8>H|M}zF_2B=!?eXz{YP=r)Pc8qqtoDZB|7iT58h?iWQ!|ea|EJ^elK4M0 zo)Z73#=qhJ^n7XjpPKn~Bi}vT8y|@O)A4vv=KrbJ+q_5opBlf1|5LBD`!jR&ue^DE z-X5EH;}ehjglpXY=B)APgk;s3m==Kqeuc0;Q!QG|5uG) zys&Uz*}%aY-TUGH;>Q1Jf8KBSKlM8EdH6py{?D$}ub2C0zgza6V{Nluyyx5FQ1}SuYs>7dQS-&HB9fKlO(F?+5>Pa-|J2MA#Q&+wZN3lwPhD#Bw(x)IV*7nK{!hKc=BwcU z)OZG4kIx@}p8fvQe!uU%+2#S_|Fr+c4V#1iQK%^C#%r%uirZu?g*Q#bv~{rEcXGZ!snfA6a{ zZm_?9+4{dVHwP~`Yr~G<|I`a@{agH>dWro$AOEK=Gk<{pQ!g-|VAq$Y$DeES^{V~3 zllL;4AB6wYcG|Abn|VL@KW)dO;{Vi@_I|_v#cj{mdy{!U{GYC8gFQa}PtCkP{GS@1 zga1=6-S&2JUHPHj3peeu^@xx5p1IK;}8Pd&8VQ^EhK zFX-|LKGM%Wa_}=|F>U?ds@LNx^MAchxAlM3;~z;THb2w*>IsiAPtp5tx7}dt#a`z9 z{4Lko^BwP9F=ce{e>X4Q9DHNxZ5Idsr!Ky8OtNR`6yJaU?1$`r+~vJ^$?W9lRrh*t z*}8`Hn!VR<+ZOzvu6N7s-N|n+dOTmR*8=l*_&+uC{Os!^U+@1VZ|<@6R$uVO|2_Tn z%ieq*<$nEYMw_?wUSspouK8+#_d4^<_&=S0q5XV@|5Gor?acpEm+jsY{9oKyF7QyCW!T+h3%$ghgpYGSo z58e~}pZc~j7YF~R?l68_@P9hK(+$@L|EC^%)8yd))OY>m>EQp=_dNA-@PFz@UY-~H zpL*h}^Mn6WPoA?l_&@bi&(8?{PyOIurU(D0&(jzF^ylFJ)K5;hF8Dw7B@-?W{!cyl zf)T<0sgsLG1pntf>dfH()K`ri8~mSo_G_;N|EGScxGeZTHS3Qv|4)s_X8xag)yD0? z|EU+4&td&vJ-@}~g_!@RUS{*e@PFzG`+kW3)A7t7!~dz7?}z`>_cP{E;{W2t|9RW` z<@i7S{84G&kMVzM)^lb4pBnGQ{697G;qZTP+x&0u61yJ!pB}GludTPcw$OX|?tQ`k z`SEYR7yO@kh50<@|EZaG$NWF_Li1_(KlNh!`2+u_US;RQ|LNx)8vmzWy(hi?ulA=| z|5q*lr~PT>|Eaf|*Tes*<^R;0|EHG!Q!}40|K1Bz`gxu6-#6vrgKhWs-J37*W_{)s z*Iw$)_orLOj`7}X`{Vy~{&n{H;{SAh8vl2&)ARq->+O2*fBO3puP^>DZv3B`*AM@v z=KX>HQ#0=m{}(s@PmhPEXZ>GYFU|VDYP=uo|Hh5~)A6fpJM;hIX8xag)6TcU`oB7U zqkVrq#r&Uojjiv?{J*&If9hp+e*B-h%>KOq{!cyMt{4BOo@?_9@qcR0kN;CMzYqWC zUFHAO%H5oUfBc`C^@#C*x}TLc?+^bMH~vq}`oYZqQZRrb@qfC$g{#*G|EFHIa!v4m>XH?!ga1=6TCpn3|5MMa z@_*_DHox`qKRoY`hxcavUp@ZZMQQ)1er5LjF#k_IXWqOp|4)7YgAWG(ryhUvRms$E z=BLbj1s`{M^V&(P84FW311@;GHl3;^$1hss-E}~{q<7aPDgF0M*4O-e;8O2yz0>|r z+dG*LWd2{=_&;^3Prc-#UzPg#y9{WYbU&)hn|WaPKV47XfocDzX8u>Ri4}hR_@$$# zR(j*t@PB%KH2zP``HN?-%xL_dw&SPpe{tjg)cC8e@2<^g{GYb7elh+}&Hng5b>BfP zg8z#f|EKP4{t^Edchje~r2ez-_2B*3j{l1r{}(s@FK+x_+CN-C$MVOc@qc=J z=DFej)bf9E51a9pZ)bhk_6y(kWQ1}S^pOQ7dQS-J;dIR%>RoU z|EFgD9sW-}aHy?sW&Te++`J|JPtE$h4<7Q3zg~Up{j=bY-)8i#>fd?u{`hB|@4eZ- zM)SXW_ZZkL_&>cLX#8K?_&;^eLCq8VpPKV;8ud?a&i~E0pS%YSY>^yy^UvOc2DMCb z?);bcx#k7Woc4?NIfKtgZhq?D-h6%H|MdL(4YGNg=Ks`v2A&c8pSo-BwEt5ND5xF$ zpSpkQwBY~Lsg8BS{6BTO)-{9w)AQ?L^StnXamT-3&0Zfk+yDHpd1N-frp>9B6O%fP>10EQZ-Hw{!g8I(rLl}shNkx{6BT0I;RK!r^Y|x|J3*|{GXcnZumbn z-V6Vy?qHtomYZ(y>+fhD691>`#Yf`*;>Q2!ey|xxDrQ-|HpdT4;I}~QGG<0Fdwc-{nLW~({>vFr{noNnKyfq zUoZWq_6Hk(jQ`XAH1q$|XEdl2{GXmL^E#RTr{?pT^?%i^YS#?&|I|D`{GZNOzgF7+ zsqtyd|5LMmDgIC0vSrKQ|I~Oe=Krag@5cPUxc@%sdcPjlv&H}Edhl%cKXt1XO_G^q z6TDkCYn0?~zs9?Mi?sjK`5U!r8vLKS%^A&t|BD;{r`H27i2qYFuMhvH{ZnmhKA`zO zHQ(>?e`?k<$N#C@wQ8OGX2<2;ZCkep{!iPPe~AB6vmP@3PtAJC%>Pq!KKx(Y_&+uC z_L%>tW<6s3pBmrC{6BT)+=Af$)LrsB2mhz%Uzpb^_&;@z{Pg@kHS6o*|I{7x+J*Ul z>JGVWga6a{JLlyG|EKO+&?)#ob(d5@@PBIdXa1kMQ+|iw|KdJ%)NtQkl$%P%T|dmb zx2;#a^6sG-jsMf}mkb>d{GYnVg+r6`{x;CxPpLDDg8$R|uSc)0!T+i8iO28n=lips zGVA|pJ6`e38vXq7x^?Ro{GT3=^>}|V|EI3sF!SG=9DQu2=k9posTrT=BiiO=bgNFb zzU#dol-o?c;QR2FpZ)25@7x~kg8$R@RBxN7W$XW{yY*|D{CU>Cax;Cw4-P)3V{*#V z?|K)U-!b?R zi2qaL1?}G=diS;Yg7`me?|(su;Q!Qv?RuI2ryh7-`{4i7ct8A~y6C)i!T+fX&d&+{ zPu<1*6aG)#&wLX8FK+yw8sCKfQ!~#E|EFd<{x5F)pBmqU|BD;{r^Zv^|I~OZTR)+E z_i=lI?_>U+t*?;L_&;rD{Zss(n)Ofde`@>^{x5F(_n+Q)IQ*X;AJ2#XiyQwJH~uef z=KrbX|J3*^{GT4bm(5?p|Eas!e89IpnB(2eJRts0+wps>{~I^+|I~Oc{9oMoKeg8X zRS&(aWAJ}!<^$sY)XWED{-2ulg_-{sH~vr0kNb=NQ!|ea|EI?1;s4ZlKK!4W*B}3< z#^2%p)Z8EZpPKXG|J3+R{9oMoKQ(?1|EC^k9vJ_p=6L*H-1t8=^AGWVYUUr}|J3+d z{9oMoKQ;3)clCMD?;qX~|EK%O^Tq$g{dJxD4z_ty{GZOpJik|eKh?K$e-8WUZg1`n z{!i!YKDu-8e{t8@eurbrv0B9 zpNIcb_qN9W#f|?{%m2lV|5MBV#m)RbwfvvD@Ul+9|EXJ!Y8L#Ty5m*tg8zH)=FP$X zT{rFS;Q!X_-xT~`eaTsEB;Tt%DfQ%Prcga0W$wj9ek7d zKQ+hW|Ki5~sn^E2t+ z3*!Iu`t7#)fcQW4PMep9|5I~3^Z(8|aZAShKQ;5{rk{SI?@#0Zbo?gsl=#26@qcRW z_t|+zXEgp#*T3e2PlNx9`>2l&^X>SziZ6ff&Hcvz>HMqB1LFVGYwY>q|J2M|#Q&-B ze)vE2I@|x6zyD80*E<+t9@m>`NBIlO!8i1>-TMc`On_0=Qpk7T5mkykj-Pg zOYQf~)%K6_F1FvV+WL9k6>sbf{!jO-)aDW4|I{0Hynz?+Ub}UN`OB1d<%V^^|7rhu z%Zh{lQ_r6_EBHUXUmpF-LrHN`%ik{--+p88e_!?A8a!#y*b9RHQ`a3i#QuB9@5|IJ zFF!viYVe;@b>GXb3H~o`{GYn;mZ`!2vF0a!u=gDg2mhzOWZDzK|EWhk^my=p>ObFm zfAD|m^RF5o{GU4K!jZxM*^I&9|5~4aZt#EVlLmJQ{!d+fVCUff)X6311^=gR{o<3s z|EV8ZSQ7l7n%{r(KXv8K-E7ZQuQe}aKF_6B3h;V|FduOUUKWj_)hQQyDkgCA zKlSF_Zv_9R`?>hd-NFB-Fw`X z!T;&_0oP3k{!iV_JRtM`;%5GzI`8gj!T+f{-S=qlf9er`eIfWi^|{Z?2>ws~=jqP| z|EC^)?M=b|>HeHGVSMm^>LFKN9{iuW=DB&n|EX)7lNI_Ycw-qP0pRUdQNpycKw zs;Bh*;KI8fN{aq)lJ~UY<;f|(KgD~dt*8FkuWNeGUz_%SI^V3d+k*d7FSPle%>Ppt zZ+|=ZKRv&twq7{?PhD!Cr}#fLUOD&cCK-LvXHEU_@qze1UH?k+PxwDIUJC!G=6v`+ zeLq}L<^R;>wjKYc=JOi=r(R*-ukn9zkmV`SJ-?*=KtyEpEA3C z=Krag7l{8;Z?0PZSG~!+BlG{%_`m7X&r9j&Z~i{_#lz=&ueQg>|7rUg^NILBHP?gx zQ{(OMf9h3s|M7q7HFmw*MqS}8|EKM1?e)a}so6gH(eWw$eTc^Ysn^^7_`kUEe`?N$ z|BD;{r{?{J|BE|+*hKI3ww?8Vbv-oe|EkxR=V$%jxbc5#`MW&WQUk5}>K zo!-p<`}otlGWw{G?)EO(@X|7D0jYnZ${7Eb)Prh@68?ed$XQz zvh{(CZnW`1@0Ip=_&=S$%=X9ssqujLKiyB}`{DoM#{a4Df%rdl#pa#C|EX7O*%|zw zx^mO@;Q!Ri*Qfno-1t9r#ilLEkM*APX1!nL|LJ;*tNfo@^Z(+WbKkSR|HAU+$*+!j z&d(?Rr^lOb>j6)^`}tJsS2pG!H~H3r1;xvfhErbfp0j94vi+79y%#K;m)v;c-@K6FVBA8fd5mo{^zBm%lvxra=ou9_h$WH{GYC$ z`G5F7HS_!Mf9hW5r|^GjJRANmZv3BG^Z(+;|EcBw)P?4~@PBHq5C5meC*uFq__`H; z+L)U9$G3v#!%uy5$0l!l<6+Y_XEgp#`!gRA|EDhM-!#nsQ+My*Jk0-7_ZZM3!T+hd z4``C$|I|Hg{ZzA1etldI{!iB{|EK2uF#j)Z`?ELR5C5m_@_%vT|J3q-YUTyv|I~Ox z{GXb6f%rc)^91pKYJ494FK+ywx2;!;|BD;{=WWNoZT?T)*IqyTpBlf1|BJh<{8PW5 zLu~tj^`B)l{?GRx)-w3Nxbc5#{2=~M%{)B(pI$HCKls16@qcQ*Uhscv*3ZTNshOXb zfA`;0%g4Q$f9=C}74ZIf_TeAAyY+9J{O0L@c=LY2|LJ(VApTE{55)hed4J;n)XeY1 z|EY)B`y2nK9%}DD{GS>>`0R}Tcn>izc;L*WK->EdY7_jQ?oVO22FY(m9pc;b3u`5h zewNt{#{J5-cg}B+6#sCr^V-)*sz39qfRX^5&WOJbRNw1yx+c8uk&uz@bskl!`FK=j}HIm*H^zm@PBIN)8YT(#{cR0%m1mF zKZyVHuJV6syc_;c=fel$|J3*{=KtyWu)Z$-PmO2$$Hxa7UlYIn*`4kG^0VGAMK(_{ zKE7AI|GVeQ_I=s!x9raLeqFM>VD|pp&-i+>ub=sh8QZfu`}pkng8!|vJ>vgg|M%b4 z3+~<|^Z8_Z!0h#bvpc6*=K9}lvpydVKl;#&`}N0TGW}k*2h8?=+4K9V9i8a`4?Q+> zo?mw3@#5DDkC)N5-Y)C^zW#Dydi`H(*8f%i?&u?e|5I~*{Ga-SqmB;#ujMnHga70F z_&@bY$EN51spbFF@_%aiKlRBqs)hA`^?3Avt#|q3*RF9w@PFD)7p53h>Q2Q`ya7vQpWl3 z?2_5ZrrUfwUmrIOIoPaU{`Yro_3f-TJ9gB;ZjjSD*}P|>Z?E5`Rq%g$eAcVQ|Eb&9 zdZWz$Q{&O_e`?m>#s8_h=d@4oe|mm+HT<8N^Wp#0?OV4A{x5F)pSpRwGs65oou6j@ zpE{>qtKk3QKK|nIzP(+$cFE}L#(8(_*fE*e{YpQ7UWc3{@2s)j?Q_mZwv4^PyCA1k z@P9f#^YZY2aZj0XneUIEt6qAk_n94XlUKHm_8!)@eei!ezEhjF!T-gL|5J1Q-_^X> zk8j_;eKO^Yi@cdPH+=2I{(3TxuJ@Z4c^7odO&*$lfuE25VAlEGol_l?wv{8j@pyOd zIM18sv*&|zGn)B-x<2OfG5=4^d_Ly?sX2fB=4WLz{x9Cn{6BSJL2iQoQ}=G4_J48X z|I|Z!^$GL;)R&xfPVj%~Kb$)x_&>d$l2lIcf9gTzFDGy6@Aq@y8Lfi<)Ar_V?e8n* z|J1E>)ARpy{>G^e!T+gGY}z3BKQ;56%G~2<*Dnu@qL?)UYpU4e!a$;Jp;PZFw>2ule;?)k*SqD; zjP5f24sYg9;{S9!y?4Q&|gng6F=XTAvkr^fr?|J3WvC*l9%#{a2VKN$a~t~7sz|5KNl zPs9JkjsH_KzYYHvH~vqJ55)henfHhPQ{(0Ee`-7+{!fkHV*cN=t+oaK$9lo|KQ-(9 z;{UWi>-pmU)ObJqpL**jU)lOZwY}N@j)!V_Z{vE*|LOJOdh@E+@aFkkQS)SPt`GmG z{kMGnUGRVE?RJ0hf9h>j^Z(R%N&H{j_&;4Q^97mzr^e^u|I~Ot{GS>Ri2u|1xWD*6 zHS-AZf9g_e{GS?shyPP^JpND3{K6f{58h>;ex0;B;#=>^FTS(+C0}~8{_}VBKJ~^k z4r=wG_d+}Wb)Oz6Gs72rwZGOIO<^k<@x8BSX zwAmcq%mcKwx-uI7r{~B1_&+uC0`Y%wJGw zv3-8w|I}sn`G)^fm)N`_{GXcj*6jE3{`mBRH}~~kZR@S!|9pR&pM?KYmv7t@{9oM6 z|5M`wS^w8&Kn6d$xUxL>KlO7<<_G^bwPd9=Kra41`G)PZ^-96ga2#YuV3(g>Ken&4*pMl(%=!n|EW(LeR1%A>SHfB zFZe%o;e{6j|5xLl*Mt8%`%gFF!%Ec`Jo$9+f9mVzEx_OT_B(BTHs=3n`?QUl@pazM z+4_~t|I_xFHt&r8sd>Hde`?kz#Q&*R+WLg}KQ-%5Pt$H)~KlKY${!h*PKm4D%Ywtm z>gj#)nXd%@_hG{~f>*p^Y})^+$6uZHf9mPCT_60P`spb*1^=gBcIRcm|EU+=dLj4U zA8*k;S0w))I>q~)c@NwDxXZhI$=syP+4p+CwPPc%m-mWoTaz*8KjOV=$M)d=^n716 zFSp^F>G^uU&$0P_%>Pr*wfTC?|5ML?{mtP2)JyDm{GXcjd+~qjGMgWX|5KOR=S{)I zOY-&g%lqq{^Ot!ue+~bq?VKO~7dQS-J+sRH#f=S9FWUY_!k^VM*QDqF>3XIuUmg5k z-1tBB^UGHS|EGS*yx;|&e(c*9mX!tnr|qvTTEyp-Ki-S4&P*np@xAvW)BlZfsw-|Fp@P9hrkO^ah|5KlHv(2Zx<0#*M(BzwvqpBa1(&za(_f1Lm9e14f z*yo&yfG=gd~#E9~f?{GXcr@qcR8$HxDu7ux4@(+-`y7n^@$ z{a$1f_Y4E|5&TVT!n zKQ%rO|F`Smt-=4zE-nfFPyOoRwEt5tUbry$KlR^Ucp>;do3R%B-xGhiH~2qw=lnLo z|LMPPb?kUd@PF!l{ptn(r)E9?{!iVdsB!Rr>LOb|2>++<-MdkO|5LZ@bz1O$>Nb7r zCbyqmn$q?3>f0drKXsAK2gLt*_iqyXpSr*KBmAElZ-@U=Y|~|ga1?G&+vb0 zyczTV;>Q1}SudCQe{tjg)P06D3;r)|{GXb~$N!z!VQQ1}S# zr|xIx!~eyN|BD;{r~AqJw)nrefBnYi-psdau>XsU?)CYX-uS+;|M)7S`waa$)&H;W zq`jVPpEL3sZ@lKQW4`qsFrYzl-GuMF2M%nQymia>-hJ)&d-y+{kM|G$PhDtV@A$vC zN6+}to3GCe^Z&=YPya?q^Rj<>;{zXB`;&KXd%b_y{pY^2R5Ye)Nm?fC0^u zTHpTLoB4tGKi$uQe$A6>_8sh2oofgGr|oT0Ck6kfZeLh4!T+gKo$Cevr*5BHEBL=B z*6a!XuV0J$!T+iIHqV^zmOYOw+Y@Dbq5o6k|GM6u3jVKitCqq4sf%o068=w(-^2f@ z@q^6&`}n?s;0akDk@bJo%nQW-sqt<2zp0OQ3jPoOhW}GD?`%MWt9}1rww~&;Gn-zoU7}`1!PNkoo+wJNx+T{(tp;+5V6BPkcSu zojs2)`*_|j@$uOnF#CAEUgG_;w`Vu=y5jv?G;NsC+5Ydpb+!-8_I@Xt&x;=~+xz|T zgiIfD{PD+U?4LdV@3?A5Cf(-VU-8n-J%Wcj{)D5FBRd{!&bNEzeZKvO>c)CeZ|LOVGHt&r8Q`f0mGx$Gs!_#X9|JU=Lp27do zt)IE0LXB_6|EXEOn)!cf-jDdd1M_ra|Eim` zZW;Wax|w-5{GXcnbof7Y$DFpo|EasSZX5hx-1t8|zxJ)t{!iVZb-UpI)CH|`g8x&e zTD1xD|J1E>S|(dRxZ2N0U+_QUz43qFAAYdI{5JD{x*mKV{!g9CZ5RBX&flwJ`{4i7 zJv+1u{!h*E%>UEz`5n{#PmKq}|7rii_Bp}-sRx+f!~d!Kn}^JO{}ONR=azqr%IJ}Q zIN10}{GX1O|5J1Q%>UE%^l0BU%>Pq!{rEpM&maG%W*#5@PmLeM|HX~}Q{xA#Z8_Vo zC(r!bj00zR=NEKLI{t8`cNbf~cJrYJ8((-{jS;>*FE20orp0jY{Cx93=Ku6~J##xH z)rJrC?E|~^N@k21;(g}efx-W2{~`T~g8x(J+3%y4RSxp=)i*!+&C&sWJnujJpYA8k z{6BTe4r%|VZj;|G%>VQA+x2fexybjgXFm^|+q{o=QoTm=?JIv~#0Tkle&=;e zb|&w7ce_{!fi3!~eyN|BD;{7dQS-J>Zf~$&9v(z5Cfb!rwMprN^Z(SWzsmeSbx-qt_&;?I^IpvV zQ)~WT+^qkr9%S?WnE$69Z1Vu|f9gJ$cMS9Y;>Q2!{fk$`|Ealt{GXb6jQGE}@qg+8 zquU1m7dQS-jpxJvspbFFoFD(E?qpsK|EK2q@PBHq5C5lTejffWZv0=|_&+uC3-Nzy zUf)wjPxJdl-*Dzb8IAwb{p0l?{^tGVwfDUjd>$Tf!p8f&nTLq~)Bc^z8{+@s-u&V{ zzCZ8(&mOzmTmDby?{H~u@PF!#=0EX&YVP0p7vJt(a9Mux=iyVl@qg2MPxkJ5MW^8Z zbUg)Ec1(V}_cp)2&g1fuAro))?rQV@E`I+O?{4M+YpuK4yWf>5e%|u#f0fOXN-5B)@bmDla_k_2AuD zud`{t-rj4>7vcZ3|GM`+O71?tyKkq9FYD^P!RC>De08BW9`J;lJ9#fRUxokE`Dpx~ zy42VM2m2JoWsad}k|EJ#c!I#1RsW-frp8uy_ecRi2qZw9x?t;jsI)=L``qz72^N4UGzrq zo;3bXjgQ0s#r^$~YJU7i^JC9f9Ou2s{2BBAv_Jlj^?&vFH2zPm^?&2W|EV?qFK+yw z&d>GY|I~Ov{GYnauK#WGe`@(ZHS-_we`ZN3TX|Ed?;dT01Q_3}-dliJtS_bywvK6&r1Q@xk2 zs0{wEVXxi6|Gm0sLGXX-hhCi#{Ga;T2ks62Pd)yQslorL&%5S^;Q!RW8GC;4f8Tz# zJNUn3)QI5!yw5!|_&@b;E*cs9pE|MiDS!C(fl~GFuDv$+KlNd^Otg7mBYpc(Q*OtH zl`gsW&ENsYJ~uD;KlSa!>+yHK{mGRZ@Nmnt{e=zN@m=2YZ9a|d@6CF+{7?Irn!mE` zxoXz4x8uE6nAfuNdoxec_RrJ)tY6LiKlN%`uND8NUT)tX?fK>D`IehM`NPK(y;oS< z{qbI7?>F;d-levFAO270qwRVQw#}Qg*;@zqw>DqpU1IaPY+hPM+x6$`e0Uz_|EU+- z{4eJJsY_SC75tz2h1V*1zP?@lPusf}O$q)_-KS-G{-65HRC@lOdQku8g8x&Wd)8~_ z83*|J@qbJ19pOE0{G)hE@5gSt+UCVw>izhnYs@>2^RBr2^5ntiZtz}m+eN&--o;a| z3jR-z|MqJS2LGpCwq#E5f9f4u)&&2juGqRYnfC3&`Fed3 z>L*vN5B^U*&$?s#&;9XdEUUEj*}uv^|K(l5L%+JTBw2XVcizv=nq%v^|HJ!%mtGA1 zPuF+p#6JiBr>-|~a`1oZmiOEr{GWQn{nLW~Q=j?3!@>Wl+dlGe@PF#&_f8G|Pu*wA z9l`&phnpAdbn;OtUH|z{{5AML^~lGc2>wrf+sp;Q|Ecd^QW^Z8`l;m`g8x&$w84Ch z`9Jjn^ELQCb%}W-{GVF>PrcB5(}GE(S1Aqc=b08y;r`zH+kgC z#@@_B#sBI2%+s^)Zz+9$!)M|D)c7d;pBgWX|BD;{r(S0BE%AS9KEJOl>5$U*U*7Mj zg}E7h3ACdr(SNyo zU2nPFf7bt1;{)yAS7kK*Putla|EI1nKWBe`OX=rj=HLA^^DJ+!ulEb*cyF?wSMYz@ zpT_^GS??bIr)FLv^Z(SE|EK19uUs`crN6(dv@Te7nKz#C==qmtH2zQfvmO7ZUT^ag zng6F=YtNVYf9j3q`S5@04fcM*|EcBw)cC)5X55sz>6V?rXR*Ec(>G`I#D{P3UTdGH zcf53~pO60fx!b%~+xJ`ipPoOB|5M}j@PBdR|J19i{GS@XhyOd+yMzBz^Y2OUf9h2` z)ARr0#{a3e*nDIBpBfK{|5Ib3THKI4K1{Q0fg_C|8_xesRajUyiNUT(e^ z|EK%QygvM&TK+F?{GYnqyfX9u)D?C<{GXcb_&+t<@qgYn-w*$%F01l?>cwl<2mhzW z|D9j^Dc^sYdGqx(p7v(`-=3$R_Sb)5MP)MOiDxpp*(1+-FDa`?-njp{jBa$q^Qn37 z?8skz+N}limM%?>`~3^va~3a7{*}DwE&r$YVko3|EEq3XcXrEsk`=X80P=QjsMg2cInq3_&;?wJD&A_)v10> zg8z#f|EFeN9R5$ud_nx5n)PGxe`@@iSvqfCKm4Dz)93Zy=g$v+Iq9tZ-n?G+T)cbP z{K0kO-t%TYpsj!9&FgpMogaAP{mz*7q4$6x&66QdeU#DH&-mDz3%Y= z5C0c8{!fj6!~dz7*N6X8b3Z=m{Z;CnmHXZM;s4a^kN=As|EKQXzgh5q>V9}#^M7j1 z|5Nv|*AxGzF0grk_&;@iUz?9+{!h*O2mhz${ek~e<5NG}_0LqpFZQK9oxNXs@Bb<4 z=E4j% zHBNF)zuud9fZY$f!5cp|^y`D&&b%M~Pv^&@;s4^s|HX~}iyQx^>t$XS{x9x&{ciQ< zdNwaV*xgRAn@q^L&9~>&JuTz)&2HBFj9>q3518%gIyTDmfV`gZ@!6g2;j+D5_Wu8` z&3woB@v}So`m;NG9%7EIryZZ~zg^G&TJPBAsl~@cRi1Yg9WS_&+uC z{#gH4-Qc9-ga1=Eu95bCYJ4C5FK*`l>G9?N)b(qh68xVU&xiku`@Wm*s`#Z-k$XPY z|5da8F6;lQ>oqtn_&;^s`n7`pQ?oz*Pu;XZ?co2^_)z>`wX6CD|JT&MzVUzRT21N% z|EE6Py!j_}C;RKcJjzjD+~(JhH-GoKgWaNWlVtcInZ0f5t-e3+$6hBKZ2aGp&J%q* z-*2uPc8fP(57*YZ)t?XR_u~Kbd{_?`|EFd>U)KLsvpz2VPtANj{GYl*oAmrYHS_D3 z|EI=J;s5l0WPj%Wsqt>i|5M}VSpQee{9NY$sq5u55B^VGw@tI)|I~O!{GU3veVc^& zf4Uy#{o()Acr)hzY5!rlxxxRbhji!={GYlYuYK@;Ivzjw{Uc-ic=NYk%5dWvn?c61q++~<| z_rXJh|I_xN7hW9vpSo!H@T9{ngMI(jsZ_G@p+VmLZT(!<|JDAzb2|k8r{@0S|J1qm ze!%~!b5iZY{6BSv!o1-BbiX)1{!iPR*Qy!(pE^1IxZwZPCp63a{?*uC&-nAaL!Ukw zJ+MdDjOO*l|9#%>)8PO5cDJA3Z2q5mSpT&DQ|Fx1KKQ@-4}X%L?{`6d@PFz;o2SS8 zKQ$hX`G0EpKehayx>J?^Q*(UZy}QcCFZnnrC} zZ}m$%yg48KPv^tu;s4a~e{tjg)bf9E+pX%Uyo6_3I0#r+2#l0|I}T~+u{Gz_&)rfn(M*;spbFF@_%aP z%i;gx#{a3gfA~K&_YeQ4Zf4u@f9jTYefU2$^V;x#>JBzfZbXBb8PET^lV9=1zv2J1 zKRyos7dQS-J;*#E>;I}*j~M@_uLt=*HP09Sr#{2HC;m^}=JNFVziQSaX8xZVuZaIs z%m1n6|J1GRdYZldSHHd-^N{zfdBPjN_Q}%6GrIe$k9p@^o(ld?=gYNuiTFQtd%Iuw zKXqGse)vCiUweJB$( zMdLdq9{5OODTQK9f;Q!Pg zzMWqGSG~o4Uxxov@7$YS|5sgX>s{gh)bf8H9`R=Ie|RGNpBjI3_VAwGctHH0wy!h4 zg#S~ow|Q;&KlK`$ABg``ue9}P@qc=JdcysAzI~bX^N)4(#shADw!Js&2PZSzW_0rf zZM?VI_H#>HW%RwPTY58(4*#d?!PDXY)Wzn%@PF!MRsK)Sd_Mf2uAgT9U)=b=xbc4n z`}5%c)c833U)=b=al_vV{*UeWKQ-PF|EK2u;s5;j1D^)}r`}@w4_teUZ^!rH|FoUg z7ylPG^Z(TBkN;ES1)2Y+=Jm$^>3X#Hzz25vC^Z(TNOZ;El_&;@p zZO8w`&HO+0nh(DW^Z(+;|HX~}i<|j>X8wZz-+P1m{!fk9!~dz7--rKG%m1k>Y`tFmpBlf1|5LBE^@Z_&YWcso z@qg;dy=niaF1PjT@PBH2-*5jm&F>FAYWDr!mDX#P+~d7s|Az_wPxq7Utp6J~{!gv> ze{nPaPhDZYkNJOb5*aqxev;mP{HcPyA2{Ga;%`HO@9Q$Mg^N$`K_dlxSY{x5Fx zZ>8$n%?siG)DM||?D=JZ_wCn z3;s{dd@1~&8c%}%QT524F!(?9jaB|n{phXZga3;g|EFFv<&xn4)XOJc5d5Ed$(>_t zz1PY9e0IHbx809By_YPSm7Mk6RPT-Jm-BjgmuyMKPmTZk?oZS6_4PzQ zc*8T^i_K#+yY>a|r8fU>!}ymodi0gAdY712{mtcbyz!*?Kb@cXXZSxg>to{o)OZv8 zpSr^4k@i}pF#k{YZ>D{|;s12}i}v}3|I_0y-mo$FKlP&Z8-o8+FElUx z?bx4u|GBGHCl8GNxA$zDPxxrdLsHs*R^_VXl4ig5o?fvs$!Yvs@4H@`8~mTH=Yo=w z;Q!QD+UM&ncORZozp!$B@PFzTS8WLXPmeca-In10)H6413;s_%%RUd8|EI=(vi`4{ z^~{<7r=DjX6#u8@{eu5fmz$5n|EclN%>PrDRQW$O^YiNeSl74X;qZUjzS=w#{!fiJ z!~d!AX-8k$H09r~%yZ%YylsE{pPJ9dW;@SF>HBAieO~{vsdYx%_e*bl_0yH@y!m{` z|LJ)7zqs*#>gD$Q@qc=J8vm!}c>JFlPmBLkuP_gY|5LBF?+^Gtb*at!WB#AIZ14O0 zeBh6dufzZ8diePV|EFGM^Yrk4>eYMR=igtY^z-mayT50a49jTzpSEwX?_HR}Q6 z|J2ND$N#CBUx@!xFR1c=>iPEi;s4Z?Hh=HQ&7)HK`wET!Q*(Xzzqs*#2Rl9gPtE*5 z{GWQ2c|-i4n)RF?-FbED)XR1Uzqi3W>Bs9PWOV!T>%8%OQy1Kj(fB_dztXnj|Ki5~ zsd+!(|Md73_Wc$Ar{?o?#8ZMdJ$2LGqtZ1a}!f9i^@Z-n)K z)s@?Jh53Kp_VXS7FK+ywy2AcF2mVi8zJ6Qqf9jGUc7#DnE&Tp<^R-+Y`!1< zPrcN(O@B1$KYc+;|GlPLudc!Wsr$D2WAK0Ka|>%EZH`}@ zvKeW?3$ott38yXb?$+DpDVhJ%_QLMW|J0iQr|vztNpjI2m#55h1#j1PSo7qL>MOkQVKeKj%;-(cR(a#ezG=VO zTmDby??0?f@PBGN*qLXo^Zi-B_2yCQz42i9KV47%p)G>{Q}-R5p8u!rH>gSQe{tjg z)bf97`9F1Mo0rJ^zqpzIr%nw>`#*Jlf1BrK{!h`OY16_INWt?(fas@n*iG&0_QB`E~62u6M7&ErS2k^%mNC&iKE$&2o9;1Mz>_ z-qY55#{a4Db@;!y?a$u$I{cru8*k?4t)2RfBEm;-2Y+oe(>h~RZ{W~Z@xZHUG<}Pm%a^?Nt^%2yJu1T;Qw@e zz56u`{!iW4zTWYF>V9@S{!fiJy!Kzec<0%A&2os!f&^bqeZ zU1}u5?mO7sx}6&QpI)C-m-PC->JF(oNuNLcxG$pSoTBM#;Pp z<9vJT291LM({>vFr)K?E=Ksab{J*$=xaXRJRg1c%y`QZgi~m#O(eQt9&do4wXADG?D z*UZ>I%V%c49@+ly|GBgL-?7JMuJ?QF@tGblyR+y2F`qBKemo!R|K9pq-}L&wC!QGm zpZcikCkOu*H~vq}@%X<3j}!&}chX5G1^=f$`Q(#>|5LLa|EI2f@+rapsZXy_GtB=} zv)(TLPtE56{!fozx8|u~{-3(uskMUtQ=e}0Iq`pL=4;{q7W~*h_&+=!^Z(531pipy z)XuDx{oEUM-8H9m@PBdR z|8)QHf%rc)^ZoFD>Oxze82_i{`!D`ajZb9$pPK7q{-2uldhvg1=JVnIbUifwPtE$W z_&@F6H;J0pj`%+{^Y!q5>fWhN!T+hd zwCj-I|J2Mk#Q&+8Z;1a>*v>pue7fvZ_YP< zd673>^2{3j{C;&P=p6i?&UgIDHG=A>WXLO%} zHo^a0eeIXQ|MluzC-^`0IYV;7{695*kNJPIH-8cQUtjZn%>PsOzp#Dqe{tjg)I}HO zg!zB!-siUt^Z(SHF0{X2f3~~)=Py4G-mkN*7m5G#Hou4eiyQx^?r=d)@PF!#7pDE6 zTK-RsSH%CR``P-w13%kR-lqHK!N1}CuG+iV8y`4z+op`h|LJ(PGygAc=KrZR|4+?& z!1zD4{GXcjO7VYc{2lZE)SCaN#uu^vuNqH;|5M}VnEw~|;f*T%`QXX$e|rAR^TYqC z@nHBrHS49~|I{3h|I_(t{GXcr@qcmS|I~Os{GWP&%@@S~#m)RbHP46ne`+2N|EI+nZypf;r|w|B4F9LbYvTXn#{cR0;|uYBYP=)PsK`r!Z6yx#afHS^_||EIwsaJU{$j-1tAe9=v||Kehayx`TOF{9oMoKXs11pYVTi=Nxud`Q%GJ z3;+F-?Sp=~BcsQCd%HLD1MmBAiZ}BEXTCMro3D?xn1$|5LX= zr&;iS>PF|(;P*r2y*`qqiz15 zn%{Tf|Keu;-P_b1@PBdR|J3+3{GS@Xh5u9I>(-ptxV&=k zp78rDJlTZH8hW!{@O9tU_x|^rr~T+X{^3`_|HX~} zQ_KIU*M9U>nE$8VXnqj?r{?v;|Jnb8|Kt5>zZ>@EdhmbRAHRtIiyQx^*8IP?@qg+~ z=KBsDxxCEppMCvwIRi@ev^yv=iq=6SPz?y|FId9Sjs?~^Zo zC8KY+>2Kchf4UwT|EDg0H|_t_d|u%H)NE(|U)=aV-M?bvugBAP&o;ke+q|D%wLG!)K1(q>A8ngdFnxJ>@PEwk!UH~9zB2efHS@g8ua&Bw zS+Oqozqs*#>c`e>4E|63v|T^`Pd#VT>v%J7*26WwwoKcXn13=4=e^jxpPk>Ec~!Q5 ziT1Cw`A7UujgPVI9o5V1^}zqBSw9v3r!F_IV*7i~HXnfh)AqUc{m`!8oBi>B+Rpj# ze`Rd*yXyJsXXd2+pZcx`R@r*B4Sf5Ek&oE*w(u_M^lWm}SM9v}6ggOii82q35saviM^Z(QpQ$`2>r(SaN z$l(9HCyxsLPtRxXD^r92Q!iSa_J8UP8&}wT%?I-J^-yW+cQ2jvu=nb1<`pJB<~`T^ z+$q1Gp0BUB1?Jm|lV>t|#81zAvmWn1zJJNP?2R{VJ=ItJeC4(s|EI@ifBc`i)aFlK z`SxNzp7lhM_0jl0^}Nm7ga1>{-moRX|EXU#Pr+KRdVCuH zr=GiVUGRT#^Jn!;^CI{^^(^~*!~f}iFR}ZF|I>CF|EI?<-@G;WKXsYSgJS-ldj9$? z!T-gL|MNC~i2qa1Te~6nKlP#&tAhVi&s=c(^Mxwtg=KV9EnHf{<2PtD_Ry7P#X zdXdeuV*a1bw_wwb;Q!R~H*OF9Pd&^03;s{d*Ejx8J;(ew{!h*K6a1gL%o_ivWXp{`KQ$f@|EFgCUHqRKk5_p`!b01 zYVOBr5A^W;>2L1p<-N?ha#A1fGV^u#KRy0R^MUsFqm+I=qwVic-pm`czh8MXUl{+V z{VU!``#<&a-TRXdj~J2C-!Jgwi+*#K_r@y!r~NhmPrb3q|EWvO`!WA7Zv3B`d42dl zJsyq!JJ{*@e`-7+{!fh;Wd5I;`GNR9^=jK6{}(s@Pk&!x9w7ct&3r%npBmqX|BD;{ z7dQSdZv3B`@5lH*JwBh0_&;^U_BVt7i+lOwlYM)o`M*YwOv&hJ58Up}dcQy4b4Nzw z|8#%x*!Vv+=fnT0nZL^Vzj6O=!c;#W>-k=J)x8ox@cr(4wu=Krbjf5T6DHudwXZwKGE*#5mt=i{F9UQ}8d z{GYZjEGZ5CPd#_>(ggpfE?=@V_&;^Yf`wuJpC0eUzdafJpZJ&^WgA*>OLdR zNbr9LyH)Ui>Y_7SC&zYOssB0Q)8NT?zFm&nn$a)S+~(cM?#~|@ZqMkkt#)|hDOvwlk4OJ! z-|ODYcdPyR8{T+6{GVR0Jo8$Y9`dGdr>Fk$EpNOZ{!izZ|5NAos~h~EIyJCC@PFz~ z=GW%GxYw_@v-!0X=Dh3O!PZN@v3Q?%u6fRPR_^!a{uFFE;LZExg*V^x&KuM;`Q7{P zd#CLFoBi_Z#n<8gbUg#A{GYe&kN=C?{+!YHKfPYe6U6_;jsH{k9oQuJKXun3O@jYZ zcN^L?dGe~SQr+8q61*RN5&x&g^Wp#0_(l9*-1xt^@qcmS|Ki5~sac;F|EFfXVEmuD zmwi3s|I|fA^@9IX_qF!}^Z(R*e&GMqMMaH+|5Nuc?}z_W}AQ z?Dc?|-_+*R%L-l?)jN1U<~QO0)c6YgpBkTm|5M}5@PBGN7XDAo_2B>1@_*{K^%@5M zr^fd!`tGWN-}LJh{9e1d4U*Mwj`PL?zEM6tqd$D{>Ws$!>G&L59~l3qW_}y~PmSlo z|EW9L{44yQI;Vck;Q!Rk>(&bXFK*`lsZ+LoC-eW*o$8$${GXb6bj<%#=h{3j=KtyW zbHDI^apV8g_&5At-1t9rwl~Z6dD%XY`GxWOC42wu&R$}?f?E)x5}LF z+2M@L=a=6yv-4VH-rwIHkvab_yAMD7@QnMF?E{ZG<_{U$vwdIodcY?ge`Ln~+5V4t ze(~$WJU;wi@rZ%J|J6L9dhmbhqfV+G{9oMoKlQOSP7eOBM&5wn|BkD9O7MT`6YHE7 z{9oMoKXpT!*LUcIgWaU=sloqgJDzlR*Sr1k@@mxz{!fozzt(BN|EcBw)OE}g(>wd@6y?Wga4~#J{kXK<|p{S+BUBg|EK2j0sp6N)v#Xhf9j_7>IeU)ZeiXI|EKfw z`HugK8~>+f9v}WsjX%c!>3W-1&Hq#5{h0r!ZfxIA@PF!t_VtJVQ_KIwjsH{g{bt*a ziT?cXe)vCKPpf9l!~8#W>*neCf9jl;>G^-^wr8a0|Eab9ubO#)wjQ0IU+e#BJB|O- z{Vd3_pV!U*sqZb#9Ba|5N9m(K`4)HRs3wsqtR7*Ba-|Jhu~D zU*)a&f7+jUba`iu_3h02!~bbJ-tYX|F85}>ApTF=TeeHD|Eq4%Hog9@n)`?UQ!@_{ z|EKQUvUTu(>bxe+ga1>vYSAS4KXp#4=E47Y=j0?Obi2^c*RGwd$2#HyZ~S4$E6(@E zA8wvF@?e|)8~N~g-i3vQ!T;&}XBTz}{!cw5H!t`cryW4y}{GVF>Px}w; zF(CLq^;H*)3I0z#;H;6s|EbTg^?+IbSIzTb{-2uXYk&5}Q{w-$oyUJ_Qh&c5d>{T# z*N4Z$|Eb&LbqM}X-PXJ%{!j1slWhB|&HH*MS@T>w9+~-hezwiuj6c75|HR#_P3w#< z?3}qiFwOkGf6o6l_`f0c^KWs}1LZk~ej9w>#l!6Vcj|s`*3ZTNX?x*C?SubQ54U-G zH`acqd~)4yg5MizUT^ntd%W>+Ilp_`ySI6}Y5()4H{K8br{fE4{YdmRpz%l~ORjsH{QAMt;2zp`>;Mz3AG!5bfm z|I_0SG@r!$KlK1x4;cTa#xF7dPtAIz_&@I|{}=aP&ROY?hc{c$e}#9Ud7^EF%e@EN z{If4}D!m7phr<8q`LI4K{x5F)pBmqV|BD;{r^W|9{Yh~~e6R)XcB5f1m2-r?0qwzBlvh?zwHAH=b(7gt^}MztyAXWb}Jy%|6&R4=(99E2Hs$ zdVJPr&TaFmZ^vKa|MdLvYWP1j_Y420qW3VH&v&5Tiy6n` z|Md07`S5>g?mzxd&Hcdtso5X@7dQS-&GD@N8~4@&)BW+;j{np3)6D;iyI;}ce*J8} zyx=i!UXK@^derx)@qap=#{a3i*!vm(rygcsAI$$#54Eo!=Krbrdcpt2jsMf@A^)eA z|5MBV#r?0-?kPX=(XZV1omlPejK=?Idvm*9{9oMoKehayTK-SX*9ZPjjc3LGsq<_- z>O&Uan$dYfCVJ!luFw0kH~w#4-9KgY7k|7lqwD=}op-@i-IDY7PVnwDu6y#=)mMA> zx~fz1#;kGPtoM85qgQ&57?<{cx_`NY>j(d*ZaK0QzaJ`Z^y$9f@&2;vF@AsKJ$v1% z;QzjOcz^JLEBC$?{GVF>PrcdZH9XsDfFEDH=YwQRZoiDi|LO56_kI}spL)f+XZQhCbe{nPaPrc5(8vaj>cRR09 zoAQfO`-0b_k7(1%8}Enz)BdanjQ>+_eE*B2`jDo+KlAeNe>&f0nQ{w~ie>$GV z|HVD=?mE8z`cJ;G`2?qVvpz2VPy5s7*RJXPhWWAw8lU35)2_d~^-11%yD#&qd-MEG z>0Zrytv&xf{g2D&8%G@DE&r$Y2aW$z+feQo@odX4!!{GWQQ&7;Bp#f|?{FESa~_FK*WVRWGu6grE1j$9t)H(mrS3;f?3R|7m|3|EFGR9ufbiE-@d8 z|5Go2JMI6}EA02@_&@bV^MUw3^*Zwh_&+tCg86@OVIj+%X>H@_do|K&dNUhsi5{!d+MjsH`Z+3%ap zavW@%KZyUs=-~fKw(VqonD=Wo-^F}d>FQ744<2xic{}`{n%{4mZ}Y}a;QzFp^^h+t z9O>sAx~Rd#gKe*edAAZh-b(YU z{7=n1E8E^NvnS@NxnBIA8c$*Sd(Sa%fdA8W<|E<%)V#j>HYHLo6L)i_I~l!>x2Kh>yZzFC#<;r;$+9i*ZcNG ze>#i%?_Fj-kokYQo)2GpAoxG^lBILZb4~U8v1#+F;Qw^LR&Cs9UhCm}ef@0MzTJG* zW8Nj^0r7v@UT*UN@qg;2Z|pX2^}KiSF4k9l$-CsOcY^=Z;rIUj=!xFU z2gLtrf98kc|J2Om!~d!Ap!h#EehvSpuGq6L_&@cEci#*CPmPbq|EbxI|MTlJ50C#- zFR;%;{GXcnf#<%}BBk$de7@rU)c802pBj&d|5M}r@PBdR|J3X3^AZ22UT>eD_&+tD z@AyA8kB|RTGe2+Q^e*1a)13UDt||R|v&ugIU;nXtM&tiE~zW=i&d<9MAke-{0;p^Z(*z z{-2uleg8kw?gPrI^6dNn))+NDcCjKN0@B+sz%b*2fhK6~%8&zUoW^WnPj ze{tjg)Exi48K|J3F7`GWsb zSJ=;2_&+uC`|y8pPrY%bH=ie~uer&a`FXil+??u1FTEwz_&*(w{qcWl=JDbG)OG7O z2mcrMi0^Lq=U;34|MROmQvLYncX}^byEz&3m%CE^kN58Ou3on}d1%``-c|N_T(bFI zZ$6)y|EKd;n}=rppL)s4^Ay!!9@;GUKQ*3bmq!<5Y|YZ(^+uW(YxCSf?|kz=L*_0@_1V>B z-h*uWT`SAIhnO$J|LJ)0f9ipwI|l!!#&_ZW)ObJqpBg`h|5J}J@5lTQ1}hfL@e=KrbX|Kc9~{>qHacnf}y?ejlhmFh#jTkSpEJll+4)}$K$ zr^gSn=ZF7O4>S*l|5MBV#f|?{Gv5vWr|VVM!)A&C% z`{V!A1BbQ_^Z(R6N3;z7Pn|cab?|>`j)(u#^|HP!{!iV*ydeHh-Se2X!T+h5pNIcb z_ch;$|5N9TIy(42b&oOa5}WPj+gX2h?LR;99%1*Z+s>aw-8s2;&+XnL&D)s`YiyhE zhyT;@<^STw|EZY=Xn*z|X5Ntbf7(vt|27~0W$=Hzzwv)@Q1}nMa8K ziyQwJH~vp8|EC^q>r3PR)Whuc!T+g8*!?@@s2?-?y!O|k182`H9yYvPvU`Vrd-M76 zQuqI)dQ{<0-tvDsp8TJBoO$BMc1w!YV+OTOM%~)j%p=`tzny%0>ENRi{GaY;>5vY= z|Ec>7Xp`Xo)FXPe3jR;sxBbDX->)(cD*pXzZu|87we0mv`Uga6ZZ`M)EkO$h!EABX?5HA92{qw#<0E-hOJ|EKPJRIA|s)U8{# z4gOEvrgi&d>Ce~u<2$u#pWHUHvAedhdAj>GHtPc)`KRlAf7S=a|LJ-UGk?hZKlS1E zd5iy3Gw%=or%{)Nn|EckRCx3dSUyuBs?pJOX`+33U|EcBw)bf97 zycz5N#*P0|YP==>PtEg@PBIN|Kb1C%%5Za zpL#@}e!>5#2Nx6t|EI>s^?u|yfB(_=KfNFEllVXNz|ua+K5virK6Av_WT&skd0#qd zN@DwZAAjuRKb)L;@?7iD?KVP%L;xPYD$4~a&FZKDn|No@@c%hv?{`}_s`oHzy zzUldY1B-hmlL|hnuIl%F!#qFxc^LnvKK|GS|EDfGsYmdC>f)1oB~81$TfNt$?}GO` z#^&$g|Ki5~shR(W|BD;{rye?`!T+h*AOEMu590sSgHLSme`>tn+s$6D9`y3J?)!e+ zcat}M5&!4g?fUV5>M;s4^s|EckT%>Ps4o$!A;AKUSNYPRG5)U20^|BD;{ zr)IvOt*_wEm%d?Ar8o2Ko*Y@>jW@J^zv<0-!1zBMkFI=sQL4ACTbSy9)-LeIBQ}{o z-+QdhKg@Ys@kj0Of9k=f_Xz$kZv3B`>&O48S^pRRr^ff;|KdKP?@QkJ zG5nvl(|6zSygz?@*X%z$=Z){WcdzGse>~TmA`=J5yo{HQlx@q)iU;?4X%{GZOxcKl!5U5|Un zub1=V|8)KGe`@(ZJzoA#&GGSnYUTmr|J1x6fBEGuKR&P5;oscpjpytA$sMW2|LOe2 zHb0R0e{t95-RiGbzRjO}uj3z6jsMfSwJb8kO(gg1T;|EKHOWZUt7>Ww@6pL&(e zr^ElnjsH{2|Eam(_&+uC?Vg*mk2l_L%Ncul*PBnn|7ri_=J)V_YCItG|8BefFTtNO z9}oYhUSs|Z{}=a~U3T`aHy=1-&%}GVdAsp#f2z{{%;%fm>tEh@!2Ri2qYF z?-Ku~=6>P-)Ob()pPJVb|EK2b3;!2)=ehH${QjE{ymi?e@1-AnV)H9sYHag!1HX7K z)ldKQlsEG`ci!iTRQG)7Q9oa;dAxg{dnncTKQolUZ?c{Fe`?nA#s8_94~YL$vpzBY zPhIs+ga3;g|L1L<5&suA{!h*Nzs&!O8~>+f9uNLcjZeV;sps48kMV!%MK<3C|EHG! zQ_KIUE6mHZxcKO*13&mAct0Bdr(XQ_+rj^-YuW^`c30n@-uUd#mD;}0 z{N32Ke@iv~@2%TD4PKD>dH6p}4*rkE|EckR=8?Q#w%<3~`lj9s*S(IH^2R@y&-1R{ zx;6Me9k23@H|*bkXZ-xNZ*0Mkde66cRCaw) zo7cJV4(|m!=KtyZWwt-_|Khgm@%-@*U+`OQz_|J1Lp+rs+J-gDNz!S#DDShha+ zKkdJ;enaqo>N!ic+C001i`0+5TF>+KzV(sS!T;&{j+_2q@PF!KhCUhQ|EUM}dnoun z^>Ca2hyPQbF!A}||Gdw-E%-n68J9j3{Ga;iYc2`?PyN)@7n^rH*N;~{b6W6!+CFzi zga1>@|EWKleV5&jng0B$%3clrPtSkTx_X=6c1Mxke^qPO2LGpCVm=N3r^c({|I`(m zHwXWxo@3q(|EHdBz7PMWE_?eeTTk@`?}gjmOmaS(?Y-d5ZOO(DUQ0Fe|NQah12Y55 zi}dx5AAGl{+FSll+vWe%3toRc_&;^omMy{msh7O}e)8|VH~H~aZ{HsLpU%J4zMr!e zteSaa_&+uC4Y6Zt=KFE4b-&BjZwUTRji+S(pZ3SM%)9IxZ+r{$|FnIM&D+EOsTY{P z!T-gL|BD;{r^c_~|I~Ot=KrZ@FIye_pPKn#_&;^k>u(4Dr>@wzEzJK@&tKo*|J2Ou z{O!~GXLNrT*yG2|YT}JQ!vASI-(T>5>IL@sRC4!W-eu;W?z!!7?{fS8ga6a{m~V#v zQ`eeD!~d!Acg+8boB4n0<+gtM`RBLwQ6dk^!=>Nj%U8zo9_qs zKW%3{UHqSVxy>uY|EcTE`{Do8mG*wZ|HX~}Q!lmkknw+N)?3H_sqtrb9aNmr&p*MV z?cLWKADFXSi8o#k{}=C%|5M}JT75mpoB4?L_nVAq|I};k z`1n6PzZEv`kokY=dYgxc|5M{j@qckQ|NIY`(#t;zo(uo?%{!N;x^BZ2-h4fuUV61Z zp5DLs8gJ(DRrJ2rn|XcsKV2{X-U9y@H~vq}`n)H!y3rp`@7jE(H=l3#Kkd)w8~#tt z=M(-<&362s8o!7Ci~FZvZuR5i|DOKwHt$-Szl{IW{o?reKQ+h4|EcTNy^+km=q|rs zc)$nGx!arhf7hITPpZ#2`Cjj3cK$KP-{)Ox^Q!TGy52fl51sXY)p$VspSo;^|BL&M z_J8v2^H;11^Z&GcZvCp{mggVw>tDFEKI#6{quvY5``ys`F~6P#OO_|cJ^fhb>a`yR z?>Dz*Y4CsQvYOi9|J3sT$Mg#RPu;$xZSvt=^D|ox{w8=od=~ysJ-|E={!d+O>&fE(;>Q1} znFojeQ!{T4|EJD3PsIE`b+LIT=KrbjZumbn>-pmU)U4l&|BD;{=e=Y8pIY<()FW+P zAnX6ejsH^*H6Pe^aeZe0GyV}gAO7!;tCo9@8s9DXYV(Rzm6_V`HM%lOGZBYjyL`j|EKGv@qg-mHZKqV7dP|&)LcLQFK+yw zy1?GA%>PptnU}M*XESE#8s_Vb?2{4sw`wOKR29(*7EPuEA||8#w-~eE2{0XxktEr{?{K z|BD;{=WUP2|HaMxKW|%~8vhqJ{?B_G`7_&;^EAxR{_&tr z>G_MC-r>x-+%v9AG-em|4*Im z0h=DQZ}5L+Zi4^A7vlfaoNvE>-0IEx!T3LIXMW&sc5UqDhcvAJd-p99f(JaXd4vCp z8~>-q=Y87c7C&Bdo9~DJ)A3o~m-&C{qnaKb{GYnrAx(q-Q@1(j(6Iimn)Qj9|EI<$ z?o~IlCja~6g7<6H{LtY4)NNZf3;s{dd_m^_sac zyWs!S_(1%hx?`KR!T+h-wrmyrpRPA)dt~r`>fhRYN&KJsNc%j;|HaMxKXr$r+l2Lh z)mr~o-O1Jy#s9^P|I_t!v3XX-Ui_b$>%sr2@o)IQxbc5#t^cd;Ve{_r ze`?kzX8xaA{!h(3Jp7*;4_JQFxiz}}o;`bp`G49@(-3)Zf(zx`F}b-evSWJdQ=jL}_T4SjLo;db zH@u`zYWv{g!c-3}P5VC@|JVPDAA|oJH?+b3sZW{M;Q!S5Q+g#;h3{40f7ic)_oMND zYP=r)Pd$8U&oKW_&AdPSpBfK`|BIXXe{tjg;>Q1}IUe)>)Pr~Uzt=zbXYhYRY`!1< zPd)s^UcvvVM^3TzL%Xf7ZvFia!TU{^QWX53dfbUNPtW|Hy7x&vlMQ>V@#gvC|8%@! z^MUw3HQo^arpdM{GS>>$Nayzng6FAV(ZB=|1WO*pBit5|5Gzx4*#cSy=DAg-1t8=kH`PTjsMg0 z$NS;`)Wx>m?&`Cj^&Wg`ak72NGv0%yWs+UTKkbdjYdPepROA2j{^t4P|J3q-`ugm5 zMke^bxbc759}kHCQ}cZAf9irWih}=B7oAlc{GYny%;Mnx)SM6hr~4uQ7dP|&;=U>8 z{!~BH`aW;`-_k?w^=6*phyQbrH@*`8r{fixr^ElL@psdYzr*hz{_e(6w|nCQpDMl0 zo3AJQpI$HK|Kb1Q#{a4DgZRI=@qcO_&-}l*@qcmS|I~RlFBSi%&b8y?|I}PR{!cCc zr!G39U+{lwydU%b;%5Gzde|8Qg8x$wo!&qAKXt#eOT+v>b%}YvEeBsvJ+<_Q@ZWb! z%>&-K(|O+PKlra_d$XSNZ{9f5yX`T}lf`2uRlj(^XTj5*asD`dKjgjcjk4hX&RP0d z@PL)(Gw^@v>TTPC|5Gou-*4gn)H{BE++YFSdDt zJ2%Pm#{1#_v|avB&3r-pU)&X$uHJR#|E3S_oND}^_QwZa_)a^&p4#_5O`h1^#(SxG zKK!5dXT4ecpBmqX|BJhm`MMeg`&J&5 z>XOY(yt%%AytltMo)Z73*Sp*r|EI1pPlx|gFEO8n|BD;{r(SG+5C3PzF8IG%^Kp0I z@mt?c*FN~0ROA2R{qcY5rCy7ZQpuxf9F2_cW?Y8{!fp` z1KMMKJ8i#fiu%jo|Fl2%+t!-$?Rdsd_Ifkb{f^w6>RCA(yzzZMm#%4Sd;j78bbRJ3 zmQ7#k+wqqN%~+i3i*B#cnSPUMJ#{a38@9=+dpY#0< z{`h6~`|CBkT$}3gZD)Ab+B_WmpB}%&=I!AB)YbNQ{9oMoKQ;aU|EFf&AO25WZNGoU z|Ecj6_&@am^U{xv>RB~!%jd!O(Ka8+yUe^F>;G#1Mdo+*-0ui)=6^B&PmgCi^Z(SW zZ;Ss^v%W3wQ*UGV_ZD4`|zMewcTK`3n3WGrGcjK>PhT z{!h(z^HRP)>+jxi+LhjTkVhXr!5c4v|I_)F**r7+pSsSTAO26x{3p8}Z`QZO|LOdA zbn|ZI>NPgck^iZA{cL-_y2{RPk1y~x&w>9_GfxZur)E83{GS?cga1>P+x#i~pL(JF zejop*e!=b!{!cyI-XC`VyqWiB_czt}KkZ*(^ZoFD>P5C*GX76JcWs0JQ!m_zKm4z6 zU$|;>@PFF=%91s~|EZs@dOi3*^?fhb1^=hM;r^Au|NXrEufbQ2oz~$0)Fb;h%>Ppl z?fXdZf9lhRJ{0_)`pPM<1plX=biqBr|EW*9hv5Iz&t83L@PF#6nWrWD zcfO=Z*E|2J6S@E16*o*vO76VQ`?FUY{Gax(DVt-S>yJfxzrDF>W$=IMiVf?`Yu#O> zub-+-8|>@xe(!lUzpmu&hrQ>U2W0-A9{-%p*Tny+XWRQ5|EHd_?d{y6&S-g8x%5 z{rJ=5!QXE2?NuLq8vLKGXQ6%lv39EVFSGS)nFXhQb@lq-|8)P$*R4-@tR7!s9uWWM zZN3=)r^e&p|J1CHi~m#4F)xh&Q{$iUe`>rf{!hKc=BeWU)QjzS_&+t;D*yj)aPtCkG{GYnY=B45P z;x<3t*mgbLuRqcoZ-4DoM|tD_HeJ@r8{cjo-Fuxi{!hnWYuER;zqZTh`_+8=Jj4H~ z`TmCgQ&-vNH~vpuZTAoVr(U_k|HX~}Q{$`ge`>y;;Q!Rj>-&4_f{cDX;`>3LBZ|E1 z?EQ%U({}np^M7jQ+u{Gz%;UrVshPib^GO3T`gw`Af4}6-l-|~NPhhU1yE|)BRq&YQ6n^^L{^n-HLU= z|LOW^{GWP}^&Mpo`TphR1$)hV*t^WutN(EJpSCtY89 z)UR*Rl4ZgF>G{p8t_}WAT~@s$_&@c6ikjg6)C(&b=KrbZn(t%&pL*fE1;PKR%Xj!c z^@cew2LGr3p7zimE(-on|2=5(nB1iL#(5e2_n`g-hX?`963#wqIrI0ju$Z9}lna?rHPq`X5{Aop0;4K7VqRcfWDnl0DC^_AZ^! zJvr}^8gJJ3ef^rnsqT4et@jA?c@N*e#2fGT^Q^j5|M{!BjG3t5!Pvgrzm|Fru=Rq^ z+^ODs;Bh(0x;>VAbNrkpE4+F9{moW-kF)LnK6+KECwE=#&EpsMUX$upC2PI$em4zU zm+CLat@p;4jXZHfs_}oi->e^t|5M`u@qc=~@Phcixbc5#<_qHg)WtS$5C5me$F;hA zn;(DJ$d1WPH@xMI=fnT${P@9#>fiS3Wq#bx>)-JnZhmmews*bpeM>)jFV$_oeBT>? zcVyO zY5!4neEgq!w5?x^|5J1S@qcmKEIV)Rf8MEoOEvya`?J0;{!h(3KeKM$@_*V+ivu`gb>6ol+`5W(? z{In+;*g3ua=b$d>d2QJqipKvfJ!ow3e|R_iU)=aVwfvtt%)c}Lr^esm|J334`{w`D z_z3);nt4h1KlL#475G2(AoC#1|5N96wDrT!J+HXK*T)3!hbP1TsqtUcuKvAm=Xh0fE>1Q6PuIhC{GXcpiT_h`{rEpM{t*ACW_?@ypPJ+0 z|I}O${!h*Q$N#DEU-&-*n2+xumEway*V z^8~wfP9N|8_Wq2|_iNjK?fSEyPxk)V{cF!B`}t+h|KsZ;zW&mz`HR`j>l^Q%ef(eR z?DJ)>@4WBt(*7@do>R8}%l3Zz?z?a5`u<=2-y!>@y^u`4-=fzr+7&d-E2D zh53JRANk*#d^_GQ@0P~K|BXH{-Dk|2>HD+&+79Xd(}Ej)dyB)GCb>V}=+6gV$oxMu zOTh!;{h0q3H~uef{Ga;Z=0^qpr#`ertKk3C@_*`fZ8|3Z8FrnYpZR|mZoSsKgUugh z{-5r5lQyk_|5G1g9vT0q*8D#;^9}KTYWY8PSa06u|HX~}Q?nj0{!iD-{JCSVp5fc+ z!S`L>*yj20f4;vp{!cCc7x(%}fAH;iK>VM!;|KA7>UQRp@qg;Jog3EwRpXiQf9m4y zJ;MAyHGb>m%g^`gr60fZJa6W?;s3Nh>k~8oPu;mkZt#C`GyhMG&tv|dn&adD)U4Nw z|5J1S@PBGNBmPgFlamwtpPK8z|HX~}Q}^xBEBHTkpWL3o|EY%-<_G_$9@M*6@PBHa zKmJcG|EKO**x>)-#{a3Ahlu}E;{ol@-hDIq!T;&~m2X}S|EE4WuS4*E>W-Oi!T+g` zA2>SrKlS;?pBnt1`i$d_5B^VG+__uue`?m#X8xa=^E3ZXJ;>%AE-yL88~U-@)!D>;I}d+x^D>sRtJ22mhxYz`R5Af4X1z$JK`o^WH6M-fQkY zd#67CPc%;$f4>?~Qk-h$BgWf@_3xbwyzryy<|}>*es56U9?4VFKJ@12cjo`CUHEhG zfX7Yj8P@+*%m3-|g;RS6|EI>c;s4@h{-3(UybJzMU20wi|EK2h_`kUEe`@CG&Fb|= z_2ec$1>Z+kwcqT`<6Df|RQ+nJ{{+v+e8A$t8ynkv;H07r-b3y2_&@D`%#?!UcXzL? z{`$Os2k$c4<^g_s;~MXbJzxBv_NV{0(`s+l6aJqcR(f-NZNFII&GRpPZ+WWme|kQn z?0ERUxbc5#`MihG2?B9=i;{ox1dOkG%PtAO^ zOV4}F_h)_MvD04l=K10Ov_H=e|EI>g{de(fzaF~T{FlA)fBDb9l9_jw1e|_NZ{@wZsZ_WSH*N^<4n*H&AYJ4B_|J3-t?=Se1pKs8ay_5Y3Rm*`m|S9JmA+)Kl;l3-lL}XPAdL|EW1X{x9yKmtW`S%ReQPv^nou?}BN?$u85b@#g*Y;c-`c z^ZuIg=#}0BPw$uXm^mZW_&=SG*Pr=+aZfG1*!O3C;NhJw@@D;D{GUD#OU@n`{GYnt zSp$OqQ|F!5DfmD2(c_v1|2OiNFM|KO^orAi|5IX`tGX763 z{}(s@@75t-1pkK*!vCpRzjUklKlNh!eIEW#k7s@z{!bm&t2O_pW?mZe|I}4G{9oMo zKehZ{-1xu7{%i1mx}GH;ei8hin)QD1f7+kM|EXDD7XPPSYxDK+f9loN_&@df?Oz4| zr{3`C=fVG}*V^yz@qcR8`^EpojsH`xu=$1fKlO6Ee*B+a?<#BjpSs588RGxccsl%_ z8gGaHQ!lgmK~rzs&6|0C^V|K_&$rkfKQ;F^souYMC+|x0cvs!?OO>vVe&@M=dvibY zs((oJ{jY!Hz2q-{v)@O4<-PRNzuWIGzwpLm+V7H5ZL=}FSAP0cVrxrP>G|LT7ms<{ zx7V5nJYxFRROA1&Ki&`j7dQS-jn|wsVMVI(f7-tMW7fl7oND}^wlhC(=O&B%{EO}D z>x6dmyqDO#Km4EWA3mV}h8L^!{#7rc=9zqsws-eu+q@qgN0 zZS$S*f0&yG&$+g^(mWylPrb-Ijm;xVwfQFR3j2LJ{!jZ?+5N!(saanS|EFeNEdEbj zXZHjDr)EAB{!h*8iT{h+j_=L zp!0G4c726vJfK~__e-`upglkD7tR0K^?5&UZTH9f1>4{5pZ6;^zYqVX^S`+Y&gR-NCbNY^)R>VtN@UA#w^K9Llk(#v~T@gw+1?}>x&5B~4r?SBt`@S>@6 zg8x%byZFA~|J0{ma)0oD>c_6SIQT#HtZOc{*Y;dLe#I?k2LGq)d-dum!T+htZk%S` z>pFivpU%D8eAi6xiiNX-|I_o|ykWWBpWFTZ)NEKA{GaY$?WXm?|EcBw)XdZS=%&Z~ z@e5vm!@Sj#-WBHiT3q~$_d=U@$^1W^pLu`G|5ML1f5QAf^#b#{kBwU3k6&P4|M)+h zA0LeWQ&+w9PVj%~YFjTD|L1L=H?04w=JOc;r(XX4N5TK8Ywh^>KQ;3#d;PS{o6l4H zpSCYCAA|o>FI>JhVYZx}Pv!D;!T+fjuWnfXSG~~Y`{Do8HFiJne`-FT@PF!s=J)LV zAN89_-ufh?^YisTbJfn?YwUh(UABw&YP(!IWS)RpGr@PBHaAO26h(!PJ;|J3~Z z9sHkK{!cCcr^dTA`=(7s-;ZegpBn#n=F|=ueZO63-#;rRb@Jx>+n!^)c=P>j^002+ zoPTm++6Q!^O_@i^z!|gC-``$-rjuPTNgzFz0 zp6V_4jPzb*_v`)bqcZw=i|c>&onyS0+4sxqH;nbJvw3+FmX7ykz2|m|j`il>H`u@b z^5b)V4j4Sy8=rSd=0tDS+g;FoinsiqUJv{r{!hKieEf?CoaXz>|LOk7|EZa$hyPRa z{TBbH=JEJHHIK*tsTXY67W|*OeDk}(|EZVR_2B>1ctHH0?kA1^Q{w~if9fjp`S&lq zD%H8~Tp=SP2b+g+JGKHgq5X3>?!>_6(pyHj0uH~hK6yPwVb`~0O!Z`QvZzM#q*?>DEW+MD@!O;*;V z`qE8{8{2%{J8#!|iozd`^P@)AiB#KlO-l-Gl#&8~>-~c=*4#@qg;kwjKYc zW?mrvPc8o!H~vq}{5Skx-1tBB@Uh*3|BD;{r~A+2@qg+O=ELxRdcBz+i2sWl|EI>M z;s4aEw~PN%;|cM9I{u&?{!cCcrosqO|BD;{7dQSdZv3BG{!fiR!~dyy|Kb1C z14ecV^Z&ffBi{S_zhr6-{a5gQtUrzaQ_KIwef1rmrM9cCAy$j8=p7s0} z-o^HM*jl;X+<*L^Uyn8ZPmLeM|HX~}^R}-S=KragANbiP|M26F8IzOT`qeky#~jlw zF3~e9$pYDhJpSs_mw!#0Y2b8oA{!d+$ zpI+~GaM!e_%5FSb{QFq>zg=FL5d0th3IC_YGvWW#_#@W;jhp#@>cS44ga1?W`)}s| zsq@WC;Q!*r|Ec?Q$qD{1Zv3CRcgJqQ|DAo^_~8F&{GXb6ari$q^Xc$^>LIq?E&fkE zxLwQO|I}>9|EY(X*TVm)2iUxw+wZ%?dvNE@!T;&{Mt1BP{GWPwds{Ek{GXcpi~oxo z|EK2l!2iXK|5G!c5&x%Vz7qaVoxL7xcK6Lm`@ih?cuV$ zTy|&gkAKjy`2RUw((4mv&-?qe`GVQ!E9#haz4m^L&sWes{r>OWHhunVzxQjM?e%`G zv*+<;cedZlKL4-z%k24|+4BQ`&Ho*+=U%D%b|eF%7H`%M#{X&ieoYSz{!h)kzuhmo z*|#5Y#1RSpPuuZ%_&;^)Bbo>Q7dQSdZv3CRL-WHD{9oMj`ZjjABMwVmzV1eUe%+5e zJUM#r#%6uu#~-}Gx3fO+AuSubrOgk$^X2P(d#hFr{?BHp1y9(q_0eJepSp|9KgIv) zellMa{}(s@Pu`oC({r)T|NH6C!o zrmJfF`mFJP>dy9gi~rO9%>TpxsquICKkZNB|Keu;pSrMXPJ;havp@b%jW@^tshin) z^7y~Fng6He`yKvIJ*0PG@PF#wy?Y1$r|V@tAO25`2gCnqe|$9lPu<48zcc?&-LXfP zu>P-F{!cCcr!MZ%F#k{8r>C9I{GXcngZRI=ng6He@%TSAkH`P13-WS<|5G!+kokY= zfwtZ*^Z(QX@(Y9iQ?uSK{!iV*yqf*Fu?q{r{6B5aEyxe+|Ehat3WEPr=k+NH{!cxm zpm$jRS6z~u6a1gun zdrt6w+Ri*a{GWPUUQzIW>e0Eqga1?GA@P54v;MC-KR-YCKQ$f_|EHdi$prtWKE~dU zQ@0HD?MLLMzyBxur@i0c!{UtT{GwZm`}fZa z{!cy9{=T#Gu^&{ck2|hca^jHpz4L5-7W4nKoo4=@n)zDzKQ+D!|EFet7XB}8{GXcn zaQHtp{_DEZE!E$)OfoIszPXs=-q590r3 zJo-!Ue>@)lr^fd!xqP)Z$HV{W@$8TPQ*-_Jzqs*#apV7V{o~Ao;s4ZQ?D^vV)U5AY zHoMLrPj7j0i8t#92YFq!ooBi>B+F$-pjb9wS`+UE?{&xRt{Rwa8qv8LwKl9P>e`p!ndj9l^yqEp)_^PKmy_D)}k9yI2lx;uZ;1|5{k@!EIpZkOVi~IZUpGozm zFP`@1{I9(Kls6s`|EKGt@qc>#@p1S+HS6=@|Mc~Of5iW(hfXgJ>;J~h{697O>yQ6a^ZvsBsd<0l|MYr{G*5^BQ!_6U|EFesUi_b$`F!|49S`5f{6BS(c|iQ1 zn$H9LpBit7|5NjL{GXb~Ifu#7k3+|I_|OXEyl1xbc7Lg0mau|EYV}@tOap&Y9Yt-|tkLVG7=F)HQ>G z|5KM=eNpg#>i@p6lKBz7Kl7(-zJzzV&11Uk$}!&j{;ciIqrF$y?5C5m$ zVDtTUxxBacCi7}JGkbY6-|nP)dU)gcZhySHceVMe$``w(8vm#3Vg4HP|Ki5~sTZ4{ zWB#A6r`CKN^Z(THf7)OEPrbqX8vakc-mVw_r`Gzv>J6WN9sHkqjjcb+{6F;yTaOq2 zr^f#kjz7q+hd$%vCaK2%X@Ac5_~-k2bN@zsx3@Rf|I;sfdcVHI|JjVa;7wV782_hc zz2IG&@8TuW|5Goq^W*>G#{b1_fA+33uV=p-^Opb9 z{>#n#;s4b5##1uydvkyAf7)L0*;m2;sjKYu!T;&`udw@p|5LNxGX763|EJdcKQ*rx z{x5F)pPKc2@qar1GMfj8|5I!JpSs$9e~kb0_ouB-hyRNk|EK+{%;Vwz)ObVupZYa> z{HN6qde61}n+~|ouaEV9@qe}kbAt!8>&5@6S??GBr>?Z);s4ak_r(9HnNNxTQ!jew z6I<{3qEv5~c9u8SXY1X0&#~XfGe>ZRhjdEJvlThk1hdKQ&$m|A(=`|IzqAHNFJ@r>?N`xpM(EXPagha@PF#F$32?N9Y3&0 zebs5N*gV6L-e+I@K+<;bgjCx+Mem2Nz0~H#o#y?Jtp|+%)A1I~Jl#Cl#YMVa{GZ)_ z@3NU^nD@HYpWmnR9pe&HV8c*uk1?&-bQUN7^t-hBQ{D%>}t z_Yd>WI`rJ%`z8Cl`%jl9-m~rd&$kN?%;@{qJo9@ca}G}RSL=G)o# z4{zq7zO%=X-m7f?mv=eJo5x@AOUqPWdRc2fAKO=6(8hb2eZM^H%y!=8c6|Jwu9wFD zsri0~|BD;{r{?v*|LNzIW%hjWe`@BB(}D{)Of%L4jr7)&qwt1y@p2pe(-_oLo=Uen7n=Ux7{;PaN5&)aS9E4<6h^Wp!r zf4ObP|EckQ_`kUEe`@BD;{SAf8vm!RFh7j{QutUt{!i!E{6AeUjsKgo^vmG? zX#8K?_&@cEwHt%~Q!ih$A^1Nv>;2;Ybo?q?f4$cm4|vb5U!9z^?m_PbE7v8rEPu#* z-#nSN(Himn~Qn{GYZjdiAy7|J2VsJ}X)N@7FSwpZ*+t--9<@p0xk%Jnz!n zHo^aCd(Wc1lg?+(&+Pl{Pr>gE8GTf8_eBf5`;F+3{BXs>R8O3_$a~PR4#EHF@${$z z$}?twg12HG*mq4UyocL*uMf7W^u{OQ|MYmg8~)GR=Huc2)ObMrpPKbg@qcmS|I`!4 z;|kIzk>x^8)@2i>|N)nDGb(tG5wJ(D{hUFAJ= zLT-}#%xZ7eGu}FTjrSPycQY2Q^&V?J4F9L=XTBTr|J0-G`tg5y{n#J>r{;M0KmGT; zL1P>IU)=aVHTQq=sayT=_^{gZ-t;cD`GEL89UmXa{697G`+8Kp<<~dpn9gDTpI@)d z&%^)4jsH`RG;fCgQ!~#3|EHG!Q_KIU@rU?7HU5zKe`ZM|dspE_?$hv5Iz+^>1%U;1|L=dpEv^Je=`tH1JQyRDt;&FfS8 z?$_STgT(*o_~XZP5B^U*c65XPQ_KIU<^STw|HWjUHe)I-e+;{VhGhPDm-gjp&*7PNQrdP?H}{E$%;XQt*DmZN3ll|I|g@x(ENK#zWx$)U4l! z|5M}1@PF!IU2=o}QxEFUHTXX@J`n#G_k)YiE}nhR#NhexS<|0BC)K@gIoF$cP|W|+ z{yDZ@EdEbD-n<6>Pd(1&1LFVGTK_k0*8f%G&G3J5dZp+}R#6yGLhTf3^qA_I}yEFnj&nY!8Poim!+DN8`@+ zc+888w`cpj?9TRo+4J|Zw`X^@_sgF5mwi97ePs6j+4Bzf+CM%2FT1nn`(<~w_sj04 zO%6=muk1ejz=KlTS)Vt)zpUSj|Lb@4$-)0MJLurx|I`N`cvx~_w_APtAqO=L{!iQG z|J3q-YP=u*Prd))hXwzqX1*W(PmS-x|EZ5|eq``}YWY7k9uNN)_mT^4ta*9Jl+4PD zzbbBP>-k>(%MIRbjygQS|7m|3|F?Di)ZiOiA9+~tf9m$O9xwh+jpxJvdE5HE_&+rs zkM)1eUapV8g_+9*8+?VHF+jxANA6T;F8gJ%(?lr8j z@rC$5JwCU6o8bS{csKl?u9rUb%qx6<`9I&^K5y`UYSxd%|LO6}x5NLb`Mkpa#f|?{ zYyDp}pQrdgHC`G2r)FN_*20VY{CMn@qc8NHJZ4l?-}O*sagLP|ECV~ z_{{&Q2jRJd>{T#jaS6~squrK%sR!dpY8VCyi0ob4E|61_si=M{GYlgufhMR z`xF!g|EJC^>J|K-x_e>I;Q!Qp3mfMDsd+r}|J336l^>sK=Ktybj~_HT_&@apr<@)9 zpZfBt4gOC(qGx{ae`>y8;{Vi{+=lsoYP=`&|I~O;{GWQ19gq2c>JhmO^Z(Q(y?O`# zr!LLQ5A*-j9FO^b>cYap;Q!Rj`(yoIHQz7se`@@2{CSLrj=T7%^m_J_%oE1jNAykm zzad2hsqI|`AcpN_}#!T+i8fcU?-r);YCX8zw*^~+NINcmFl0n^N*n*Y<|Y5boW z?}YzTQ2QjsH{2|Eaki{9oMozqoUoEb!}- z|I_v28}WZ?<_rGu>({*do@PGzFRyx!KD9^if7+kM|Ecj(UzE)D^RqrL{!iCKT%{Bng16z^Z(S$H)Q@_-1t9lyTAB9HQo>Zr{?Po{}(s@ zPxqIvKm4B>?~DIa^ZA7Ti@RC%&E9>IE5 z=JNypr}O2V(mVJ+b#I$@i2w7p=ZF7O7ufp~|EK2t#{9py@qg-GHct}&r^Zv_|J1zy zng6HmV;&U$=e@)Ksk__fCH_x+^yDtd+Q*Nt-g4+S!NZ+!-)YHzUYzLt#M86*{gC$? z+cq;l!kgc}+3%OU`F*PW{>hu)U)p>M?b2(iSpPR} z{GS@{_f5C{jmNh>GE?Hc*m}f}zNyCl>G>{sZ+q~6apV8gb?<%}{GYo1gU^HiQ_KIU z<^R;ox5NL%{rSQ!-mDLd|I_oK`)}yr+iT5(;s5k_8vm!}{LKH;<7wvqshPir|5L9t zKe+QgEvjt|+u-Ts|FnIbc{A4kZR`gBr)FLt{!d+R=fnT`^_ZW+|Eckm_`i66{GVF> zFK+ywn(KSvcmLy!S39oB@4V&zv_Jmu&AMIu{9*mz4Lheg_npKWA6U2H=PF$E$1Jud;spp7*?2U-&;SzU9sO z#S@lpN%gDmY-((qf4SwJ^?tp0((cc%_U8WFQN29XU%p=FjprQvc}=RH{-wfO{!jNq z{!h(%*v$V^SHAsm@PE3W)z`;Hr`^!~4X`!B55=G*Cap1aJuYTL)Q-t&dNf90DW z+4|0BRUI(!yWkDWcKAQ_BKv$B^5^4yJM)Cl4|y+X@JQbH7V}Ns{C?l&rFnCF{GX18_rw3Gcg#ohX5JD0 zPurOXWPYbYjX$*O@vgP|YsdFyo|WxiuKhVb|5M}lY|1)^Xi6`D0{Ga-`(gy#h zo;>K;;Q!QTjhhwxpL)i$Il=#_&%f~g;Q!PY{{BJMQ!Y|Ja?NGI|EV9m;$rh*=M*sm zE_l@&PO;be_kO+et~rU<*L%?|=LY|$=l9XPhl2l8msidY{!hJb!%AK+e|-6xHNpSs z>#2G}ga1=kZERToSC6lK;|*S4e|*&&ZwCLT?UkFihWUSL=GEc<)XbB^|EXDT9RH^- zv#&S&pL(G+^Z(+;|EcHM*DLG)s^^T2{~OyLkN?wlK9BK#YCcc#f9hp+Kk$EQ=FQ>%)XXcz|EX)mwv%}3$?w14#u|EI39?>F~8cc^dY^W>9R zO}+WN>G@DIZ$4jdysNo4pRZeQZsE;(?QO4ZnQHu>&c}RR{GXb6toT1~`}aclzqmi& z+A*W=&v>eeb)CKW`^2rwx_aZ=@PFEWv3Y9zpSSt4&N2%)JyFBg8x(F1@V7sJR$y1KMyfq&i;Oq(a%5lz@@DRdgB4{f7;IX2mGI! z`F{mF4fkffVEmu9^L&~A7dQS-&Hng5HOIsMsri12|5Nk#G5hWgZ~@PtEhk|HX~}Q?Io9iT_jM1zG=BjR(a4shM|}lXH%rpXam7(dT*N zC$}7Wfj93D{GXm5T~Ye`%t0spqrvl;|J%FQCEobIDeeB?E&u2H@9=+W<`Yg#uJZlq z@qf75n|XUzUvP~#9`N}yul1Jy)A8j0)O=pz|I}6Hnel(>c^ft-mkgfi{hE2|C;Hvw zU1h!w|EK#$F_?Z8vW zD{MY1{%^uFUkCrkyjJ{Q-1t8=-jDfzYUTkl|4+?&z(1UJzjuxKKK!4~S7tsC|EFG1 zzb5!U^^#>Pga1?4E?tqlTlOd4pLu}0&V3}+_&@Expsr#4U-i7&y0HGQy4F14L5I(3 zygr)`cukWhyvuE#AM^k8e9FxG;s4b0cKAQ_Ydid(dj8zG!T+gezw}b@f30@kDf9b# zZYqB5z8i!8Q%}ltNmfspm$5ZAGgJ4yskmG5KEeN~OOI*re`>rG{x9y`cV3h+qmyC% z)WO3$CNJ$#<}LrH?W_-s|5Fbd(=qrz^+20%R@kY^w=@6mgC5o1c)#m2HQpm_z23G1 z7dN)e-&-@X)|+{I=N-Gmn|XiuKb>!^tv8JSQ{(aQe`>rQ{!fh$#Q(*O|5M`w@qg+O z6M6*yrQZ|={;#n+2mcp0{!h(%#LWLw zvtBXt|J0nH`G0DBCiDN)JRbk2=JEJHHNFr37dQS-&FhE%i`%T8H@*`8r|mTUPtE$l z_&+sX*#2A`H}n7E#{a2@4sDm<|I|ZDPj@w4~O?(Fm7 zN#n==ns3YYe%YNp?=HK4ZGK+1|I6;)ZI4b}Z$Z|2z1g1c*L>iwdB5z}EBpF+f5rDN z`*_*+dygjjrS{M6J)5NG^JO>d@5blLZszsH+p`@~-#od>&l8;7)FUTh{-3%_uiW7O)T}>S@WN%jo%MI| ze`eT%f6VLAE%-k*UJd`JW_?@c|Hb|N{ulf4@PnVW`Mo!vFZe&5pY>Vsf9mO{Obh-` zeUbSw*8f!>KXhd9f9k?a@8JK`1x0zub>-*y{`rNyk_*?L?cJ+)ZZhpJXL;kpCj5A2 zst51g*mywJ|JC!OJLOIH{h5!~eE8|!@_*W2{x5F)pBnFn|I_u$|Ec@+%nSZc`}2BT z-)*WtzOYwbnE$8kT%XPA^X(n;^Me1=cGkCL{afXZ&ga1?av%k;&VbS}(|B%VOlLuaW&l~?Y@3D8i``Y@r_&+^9@8rVZ z|KcA1+_vf$w*4k}JmyxxA z@qcQ3&dBH1R}a1XH^KMO9Uooijn~2dX*-SoQ|Fx2Bltgc_bEMt|5J0k8Pit!{&>aX zCa&;iK3~s~%e_m?BjNvaeZ$QE;Q!*r|Ecjx_&+sX5&x&|H8n5zKXtx&D*T@sAB6wY z_0sr1^`L2);Q!RDAB_J~^<@oZ}~r+pT_^G@lg0bHC_t;r|w}M5C0c8{!cCcr{@0R z|J3q-apV8u#{a41|MdLA`OW{SxnBIAzFsDnufzYvjsH{Q^YDLad>;NUZv0=|?cRUb z&&U1)Uw_D(*OsagN`fIaW>`$K=7-06+? zUHkp*-b3u`5&x(A$=3`1Pd(^_UcvvV`<&c8_&;^usksUMPtDgm{!g8Ia<63TvopQ% zzw;isG1d4#?ay}nU)=aVb(g8Vg8x%@JtZ&rKQ*79_`kUEe`-7={!g7b+3t_|KXpg@ ze8K;zyO?Li|EYPu;{Vhf5C5m;{dVV0=XrOSWIs=u|I_vs$8||&{xGS!qV)Ul`;c>< znUVC^Wuo`XFTRj`wBNDbTiuNwWL<`QFU`TJU9_cbR#>ssHZjU2W_A?z?*rZ~R{Mf!)0;%)g!4 zvRkV0f4aUUA8k(#UfLmToG{!h*IeZMZ%)Aw5KjR(a4#rN;XOr39M9^j1eHL2cuPK9@!t+&nmKRup# zf6V_=*P1`X|HaMxKV4s)eSPEq;>Q1}@wxavHU1a>r)E3;PtAP1GfuwOoAtYG-iSBz zg^s%C*2Xq}i2u{|Ej52QzugVqb+$ep{!iQa{X70oU2fa)fB(AdpTW!0`@VK&W83ee zng2Jx*S~@XWPTC;PhDom``wbU-aH=vcj0&c3LcRC@qcRO6Yf2`DC!TBp9_2V<7@1G z+I%E$=KYzsNVWM5Z~TUNkW|mvvX?hL=bZ0<>&<$K_&;6Gns+}8{!hKu*7wB!so5X@ zhoQm$aXkEA+~$!|jsMg3Rd)UOKQ-qwf8~wW!~bbJ9+mlj>PS{ZmJ-$G_(!7KnKh?Is_fqqN_&@EB53$#` zQ1=gyVDlnVeZck^-gpZ9pB|65!2hZ7Dfqv*?Rvafe;EI#?W{kH|5I1(@PBdJ_51e9 z9rORRy?l9t|5HCxy*cY1m!8vLL7f{PmbpZdbzKfpXiKmNn!|K7UoRPXzD_&;4w z)eX~v|I_u>%sh?P*RQ|q_Va`P)Asjw%>Pr*shk`9pL*HG73Q~YFVgEPr@m^|)BU^9%6W>0^{MaQkzwp=h*-dW*|EJe?p{?JE|5Gzh z6nm%V`+|La@@MsI^G^2u_kP(vKk`!#(+yIgNPH2zQf^ZgzFr+f{a5^-8qbFR z^S1NZd~rV?_tXCVkufvzPrbps8vaj>N5%iejsH_~|Nk*{SVn(8NGahcQzmI%{*HB`(3K-?|yEyqCOQGu8K}Tfa8Vd$qkjmp*lx_bU7TwEF((-pp4#A#;`=Z>638 zyvxt_?OadY+2?xm`X6-C`QCiLJ^h#qz4?BO|I__kVZIRmr(SLz5dWvf|6Mxqvdk|t zzYAWC9x`->cdf0@i~rO9H2zP`{`fyN=fnT0EA8`|`G0XU|4&_Q^Lp`r>ZB>e{tjg)cAhBu#f|?{^Ya7i|LXlpfB8Rm`uUkB zIOD!M{eIE-Ki$u2Yy4l__&;^+s)qT0apV8gRjW4!|EI3N`2%#tLs-L=jA_=>bG(p^`5tEd078f=YM7Kk}&^Iy=aI3iyQx^ zF0X8u|EFHCs4VzD_3T9zVg8@`g?S6Z{6F>F*X9NPr=I=tE6Hz0zLq)o@tuS3d-BDn zlhcl!>pf`n(BS{HeQ3d+$>H1QWo%|v@O;M)YnCkjdcHTF@01@Gc;o%>f7)OEPc8qa z?mOJp|1|%n9yrGQip~F1^ZN_@U)=aVHC_(?7dQS-jrYU<#f|?{vwkoBPtE@LKXu8m zU4s8p_n&A!!~CCmsCh&DpBkTt|5J||+dcTdxS9W_=K7ic7dP|&)PrrFAO250$mSm& zxpe|r7;P3Ro_pPJ{>ecVHq#;*AHy|7m}E zk0-YJ@#X(?eEC21aGOuZ{697G3h{sHiKDv)|EE4~RF~lY)bf97{2Bf)Zv0=|tpBUV zw=w@u&3r!mpYCVg@OHufsS9m?{GXcnfz1DloB4lg`MRoU|EFf2-%XisGRJ+iQ)c;4^SHKN@7V*s^=AEE{Gaw8Wv>tZ zPd)Y+^IYct)W_`be`@(Z^+MnzIYm=~|6`sQ{x5Fk|7m}=PtEn<|Ki5~shNL;|5G#niur%KUu|uDP5hs_eaF_p|Eab9 zubRi>|J2$34=)tI-g#}(zt7L^oVMxhJv+8ZJwAJ$9?vH}KJ&2R&R*{~+p}eNwpYvc zZ2zyFef(@+I3&wUX8XPWPiOhR{C4U4Q`#==FS9%Qc)#|1viJZ0+rKu?FWd8FcatVf zQm=3J_U!q7%l5B{&k0ec7kr*3{&lQ92J-SUWr^?&1L z{a-b{kM)1Ok7yp||Eb#@)iU@$b#9AhN!vv?)f|1t>A~yuIO>Sx!;;2kz90Ti`_uS8 zHNFr3r)EAM{!hoFng6F|{ayT@_V3=NUGRTqwo?92&DS^nPmQm`|EZam$NWEa*G}z% z|MTAA|J3+t{GS>RjsH{kZ)=~2Hvdn}`I-Nx#$)6EyxVmO{!iV#Q@7y%)cKuqg8x(J zF(20apPJ``|5Nk*3je3>YW^Jmr_MFM&ip?${t5r5W_zcaKX~K&nEz)p@ftj!HU3YH z$NJ4L7yJG+{!hm%&M}W;{!d-hwMX!O-uWfL|EZ^(a9Z$x>dU8`5d5Ed+R#D4|EWt0 zy9fWL9+2q~{GXcndHBD$@qg+uHeU|^7q|V{8(&w@@{CmD|Fl2z1Mz=qp1;{JZ|)!S z|Kj_F|BD;{r^j-(D*#Q&)^|4%Ldr_QtWb?-RhL_b~+^K#d8Kf$|w zkHX;pbpFiXQNjPI&mTK6_&@bU6D9}$r#^q&gy8?w<9Zha|EC_-y;Jai>d|>Q!T+i8 zlFa{$oArOyc+&$XjPvKq{6+kqwvR0+2>wq!Cf~f3`9C%D4e@_*Uv>Hj|NJN}?4P`H z<#6x*{e}krr_YxG!^Z^wr*3|9$Kd~TycW&U-@iJv>7M%h?pu`heS`atPHjJVom zUw&L&a{jKt`wi>eH~2qwPT#i4E&utT`n-SqHh8?^5j~P;{{Fsqq5XXp|EK*+PiXLe z>e1$9ep&sF?@u>f{I++odBD7RZ+Z7IFNpus`S5G_KQ;5X?znTScYpIPFI~UIyVN`k z{!jbk>F|GQ=6&J+)cCvmsy9~Ob=Pl$@5Aq1Fn5DD{s#XSZ^!?6oA1H@sr#Dm!T+i8 zMa=(G4?3~I|Ecjs_&+tz7yqYbz90TiJ<{fX?O$4->aX*bd9(kTPD{PHUoRY0m+Bi2 zUgC|{nYw4KHy*9ePK&*n@ArR5yYC>W%Jl#H$A|&5VkC&<9EUX1Llh+^0l|Qx0!CDH z1#!(eXT_WY2J#FO3B!<)3?hno*RWAHnfAHf_sr*-`}DW!w|_iawN9$^Pz2Cp?&HBN`SHI>x)Q&%9 z%B$X|n>YN&Ij?x*|E8>d*^l4jqOM85vX{Iwwtnu6CNKHxf22L%PoD6i_XvBu3l4q3 zyWixzWb@w7r}{7deAXMkSNpqXyzzecKmB~k|HX~}i~H*#Px|?>|FS+$cr%~y#jcNg zb3JCZe$1QeJFelQsm?j}5pU)%;{SBLdsq8Eb>@O9|EFeNB>qo5=={#X|EUK|=otK; z8t=#aKXva5ItTx!&aw9c{GXb6efU2$J{kX~?uC~%|EI>c;{VjFZ;k&`%m1nIe~k{f z*3jsMf}d41#m)VvCXTkrOu?l_=-(&MF%GCHC`~J(D?<4K|F>m~aeShYSPkLikUq3##AN6K$ z?|Ie!Pv^hj)31a7QQHPw$_mXm7ypKf1f^8xXH z>QeJn_&+u40Uy`Ct+)K29zTu$Q&*VRWB#9d#g~5y^Z(TNyAOVB?AvMlpSI)e@PBHy z-|~EYzklZWwR@+o_d4@&A1^-98xM&8)9vws_&+uC{P1@EUC z|EJqCpAY{RH~vp8{}(s@PtEP|e{tjg)Rnd#F#a!Y{GS>RXzQVQSJ-?${GVQ5%)i0^ zshP)y|BKt!lk;YO{NJp}KL-y;uiHK`)p!0p-W%W7yTPbbSAIIEbab;{f)^~d^SSlE zeZBF2J?rH~UFH9@KYkkj=WTuh|EFfY68=xk{5Fd?&_sgKCy?o z+BW`{Yd?B|LOjjH+27=cYS-Y%@;Di zYLA*7yO@k`ju7wPd#(m z)4~7g_%Gg6<^R;PW=sq7|I`IHPYnJ~=Ua5!MfUh_@W)s3(6zz;Y5S)OX4&<)!?({b zo*Vq1wy)Y)8T_A~zp@P*!u&t=(oLJf`oHSMA8ZWk|LXQ7o3{l2r!L&GCCvX*FW$N} z%>PqYRQo^ma`PniddSo93(fzv-ZIy_z~)hHs9fm%o^8LpXtDQvJdF82-G0uF4}<@U z8~>-q3*!Ic#{a4DF!;Z?@qg-4^D+28HS_22f9eYRd1C&bdbNH2;Q!Pc_IwfipPtXM z4{Y9)&Hq!sX;rvs@@CD-{Svtd;IrdUmuv!`|Aqpb3ZxQoB4D0{_M?sxHr!`EThjG zdivNSyqU*0aOhFq%tyoj`To}UKQ;6E$~qqJjgP|r>3sP88vm!}`N03FS#KTxr!Lz3 zQSg82lC2-}dF0#if%re&KaKxWb3FW?n)}25sqt_4KQ;cXIMXhp&u2Uz{!h*I!T+gQ zA07Xv+p``27dP|&;(qP79)9~$^VR?QAkH%m;>Q1}<^R-pJ^Y`VZSJnjQ>+JPmuY4>V@`xkN;CIFb|0T zQ?tJBMX%lMuP5gJ4SnIBsJA9vpT0NM_WQH2mXd z%>UEvY5bqMVAZ;>Q1}ng56XQ?nj0{!d+G-M8iQ-UUl5g8$QY z`MR_VnE$8!Y3BdMjsH{Q)Ak+tso$P{ zbNpxC_`^XLeC|ESJRJT{*Ngdj%>RoU|EI>s;s4^s|Eab9uUhN>s_|?1KXrfeefU2$ z^9%8RYCIhNPtCkS=KsZw|BHJ`o4@+&mHl7K`I|TAhyT;-o5ugeJ$%TI-kSfXbpNVl}V8km#zT)A!2UMbT){e3U<`tX1I z9ez>pf6N!{njn~5e#f|?{7k<>-*yW;>Q1}@qPF|b(bd1ga1?G zWAK0KPR&{b|EI=B;s4^s|EZbBcFdS-{QU4&%>UDN<_F^c)Tf)D!~dzdKm4Cs{!h*Q z|8ei@^1pa!qJ6*pO+G#S>zc;f;s3OMmnIE^|I_tq*W~2j|I~Oq=KrbjcFg}%TDmDJ%29S`(=0b?X&&d|MF_t-Y>hekDooiFMGaSuO{i&bN2kb?C#n)?Gd}#>nHYS z_{_L@y~X{1_RqR~_VM#=USoXw?DcqgJ;mFzuV;2=KmKe#nC&gIJ!bax&F*afm)+Ux z`DSGrJ0i~m#ObMb%Lzhm=8!T;IJx8VQy`Dgy0y1DsM{GYmoy+7ms z)GciuB>pdM=KraAzheGh-1t8=o)7;QH~vq}dcpWVwfvuVwf~Eo`G4y6HeZ$bf9iHE z?Dt{wf8OR3@qcmS|I{toRrx=4s}5E3|I}@(=l{ix|5JDF+&QVg^}19a@y+kN<^Qxl zehvSpX1!JXpPG4g%>Pq!|IGhWx3lf6|EuoWEjRc-b!VI3_QFF`eLKfv{aKlPXn-4nB2zMaR1|I>CF|EFf2BK}X^&erF}|9N*Y-}bwU zQvJid7kV>~5C5nAJM_#Xw)SrM?e(VyZ+Tj#NAQ2@em%Md|EK2h)aiG=@2~ZLwLQ}{ zH~2ptzgx#D|EE4`=&0cT)a@?4GWb9BjI$>O|EC_8*C+Tt^@!Xa!T+g;_vjw{pL&F? zuUofrj6c5NUArddoHW+Ym&b$u)Bb(CcM0?V)Tego9Q>ai&oEmr7yqa2<9hZD{!cwN z(>wS-b)URm!T-g5?vTO$e!}Z>(}jb)Pwk$Y^uA%BcXRWF^Bx=Eeb7lKrQUzL9g}`P z9@H#7pSM+)Olto&-Fl{)`&%{j^RgXp)C&HM^Lh2c&%As0xA~*vKJ^|ts#|i-&^_K= z#&u4*_x;4X+gV+bVDoS`U*3C=t+#3O=e;@pM_ade{T#&HOO@pZbh*y9fUlH|zhZhuHc2dF!gO>8I8T{%e@|o_p7<^d4g#r`eK9@6qNF zD;BQs#`~Q&yTW_8d7@umT<$&Cyc7P<@6YD@;s3nN>)`+5#{YTS{`kMR@qcQL&-%aW zA+|sMPd(b^gE9Y4J<`14N!=Fv`QiTx+Z1}^pU!Ah;C+Vqw7(s{$eY_gaM(g`ULP&? zTafCNKh5*z`JedLx!!olsrjnBjX#f|^d z^~S&9|KdKy=KZOM+Iq+TedC2x?|$}qZ~4E@2ObdoFa5+F&!)Ctb^SBmc)+1kXL86^~=@%PyK4O|5F#5U&8;Xi_Ame|8zY{ z%=6*@;>Q1}nRmBzW~WsD`Q8rRcs2Z=j?X+d{GS@%wj$HooBgjI)Y2Qj*I-<8Z~Wf+ zNlm?3e;5C!>p|oH)XaC=`q0U~Ki&)fr~6-P_lN&eueR%h|5L9rKX%W`kI!EH~vqJpSAJCet&qr1NIboud;cW_&@E>ygmG%8gGmLiyQx^W*#U0FK+yw zy3CHp{J*&If9j?7{WShBZv3Ab--rK;8~>-~_V_jUpxew#NwtkdqBQeFR>>E3ui z{NIg_{uVqc^9gNzI`8Gy_`kf-{|z3n!rrg&e`;=z|5M`yf9*TSTmElm?IiPF|C{q^ z{GXcjgl#=T-=8)g;mz^!f7+kphR#^$hWUYSyPT>rIzqz`;OUx(Oyh!gd^F#PQ?LW^N{}*@dBcAuh{}qpa*Kd#i z>shbVoB2VNpRP-_`6|EtQuBZ2JH40K_wjcA-etD_uX(0C-9P@%=978L|LJ-?J+G4I zBTxP0vun(&HSs=w(&P4eXyZLO^I~%OuAICl+U;fkz2lbrOMAbX%wC`IzOMhX$sd=T z>V4n%s`Y>W@$g=muQ%S3f8Er_!}`DK8CN|S*8f$%{QGOd`oHSuXIvTlpYCtrjpqgb zr}JHW>xIGpsf!<+7W|+3vxQauPhDX1|Gpb?k6(|~8&(AWr|VU|u4?|Dx?VM& z$h-*tPrbnA3*!IO%U z;s4aEXO90zdGUMy58Kr z!*TV!m)i07KI~*~=A~`j@03)(_Ddsg=Fj2(bbmDdPmS-x|Ecj__`kTPoZcp*&)?ty z&Ht&nKKMU1@3;6rHQsPey_{6-tvt*lluR@)w{yBS+FakqE5dA%Py z-Q&%Czq)PiO?CgK_jy;^Jin<8?oT!TPp?<}-|{0L^zE#-d(?9e`uWeZ^?UJux?T%x zePaBdn)QM4e{tjg9=Pl0;Q#Q4_&@bB^Mv?6HQsN}5087Zp77n@J>gxlYJKp3I(|{* z+Tj1xCD!;qb(!st|5F#OteXF)F0^@n_&@K8)xrO%7c5y3{GVF>Pd&f5EUf>lF0y9* zUv+`a`(yoI_2TOJf9kn&<_G_$ex=&~sb88qH)*$FZsxR!`v>p$`nzug|EIp-k_&_X zQ=fHO-@)xyax_#p7ejV*!$FBEt6KSmUy3L^VAM|r_`Hyb3e{6^FGby`Ryz&_ddgXTj}y8 z-lJ^)7uPQJ#=qhJbiVR`YStGX{6&Rtr}2M!yfpqVZv3COt-s6qzv@9FtNfpud3g9g zHC_$>r)Ire{GWRG8EwP-KQ;6F@PBH~2mhxYYWw5=;=ca+Etxke_7DDZv|W!qw{7)4 z!#p4UPusaY{!cx`{(B()Pc8qa*8D#;p0QQ^U4H*~K>VN1XP6xi{};D?KjqE!!T;%a z^tl7}`1UhKbO`=Ww;wgUeei#3`MFzTqct9v}Ws zkB9Tc|EXE;cg*9z`u_O8+~g2#{a2%4Qv(W z|EYWQYm(HvckldrU)(P<{hK@Thj(v~%sF(QRLA~^`89D5?2uj`c3?aE`8NM&<}dg^ z*0aU`squdJKQ(>{{}(s@PmLGD|Je+|;Qwg+pBkTp|5M}D@PF#gO&TRDc24!+1@PMqy7KwY+sn|7yD#+!0gWUjM?3`af8(BA8#4|JY?^m-Mvmu`@#V&((50O zvU!&A@rIkXiaY!9W&6kM`G?s)@PA$Z|F!+lLk~@z&yhzS`Ty+04m&Kh{eOAE?0JCM z{_nWs((C_bd%)%=)(QTvP2DSl|6?8?>;I}b9_#(#55Jn-v1JLLrbr_Pu^#Q&-B zi1)%QPEPfSKTq;zedR$%)O4Gij=}%M=Y#)K<0J8Z>YjPsg8x(J z=bDeS`G4wDbGs$0*PQQ-mn+_Lo;QAM_Ky?1@sQ6QSko@cbiDk*1H=43_4#AR z2mhy@boPYc|I`i#+1ga1?G^SV8IrXPP$Ue)|RZRdRPe`@A2vi@(}_&;^N zT~Fr!sd+wG|5uG~#Q&)Wb?+JcpL%eQUdc(h!~FTlGjj~JTj-kk=OA9>H^nG@Uo zDWCPDe;72-oAsmde|o=Z+@(wKf9fRb^I)HSYo*@r+qLhMYUUfppJ%Lh9Cv<~Ho^bZ zEjuvyzdk)W1plYboZc+>KlQ-TorC{V_ZnN}|I~fPRrx>l@UuDx|EC^xZk7L2GhYw? z7dQS-jo-rm#f|?{%m2lV|5MBV#f|?{Gw%=o7dQS-J^0)z{}(s@PmL$U|HX~}Q;)Ry zhRpwq8~>-qui^iCjz2K?KN|n19%1tk@qcmS|J1B+i~oxo|EI>I&3a;4s&npJ>dibg z{GXqXc_aLv8gGREiyQx^##i+lTjIx~zZhKXJ;LVE-Potd8?T7})A=!95C5meFX8{x zct-qR-1t8=&oBN@jqk(%saanb{}(s@FK+ywn)QeAe`Gg|EUK~$q)1Y^!(uU@PBGN7XDAo z`QiW6oFD#A-S6VA$>N8fOEvya+wpq%KehZ{-1xt^@qcmS|J3q->fskx`9JlrDK;Hc{=;s4aU-td2F*3-uSsaX#j z|EFeu{GVF>Pp=30zqs*#YOW9dFK+ywn(Kl8Q}g=5|EZbJi2qabeuDo~cbn2P_&=Rr zGg}|TzP~A(UMI68pL$klQSg82!jE?H{gLm##MY0q@0Yys zfcU@B)051fXWp1!VBZ(v|J3*vn_uCLx3KTGQf=RVdE;pY-FRB6f4c8fZ`Sw4|M~H) z@qg+$wqEbTlY9F4(Vw@=co*975AB)jU1a_V|EI^x`oPC;>{8Zw(tpGE5lhUQt+0Qf zu3l!1|I_}<%>&~9)T_*|o%l>U@3rQ;jx+zK^TUtf|I~Ou{GWHV|BD;{r!Fx+HshMc zscw4fDc<-p{Gaw;X+97Cr`}+V|5LBG^Tq$E*Vygxe{tjg)GO@#@PBdR|IFBBRy4RN zf7xeM^Z(RZ|5wfJ@qcmS|J2Jq`!@JL^%9%Mi2qYpd{X8A)T?b?BK}Y3v&Os}{!fjs zvp;*|{p`E4Qf;Sgc7-?VCEHqB-pg$MVx0+pt7$tv{!h1O9v}Ws&Hds3;>Q1}%WXUU zPtAJ1_&@aqn?Lwa{q3p#w)+feLVc%k@a3! zW_>*T-(OzZD|6mg_Ifv8xMbvb-_HBpjNgw;HU3ZgFEanOcuLg=K10O*6q7@@Q8D_?F{};U0~bs zf9mDd=6y;qG5EL@c0BV#-mCX~jz{vYG_PZR&3l18e)DbK1@?L||K?q2{s8}X=bF8P zFXZvy|J2MU#Q&+~|J2N5!vCr9qWC}cN_)QWe`F|8zaioBUAlf9i3$&nC|g%gIxp+v_EsU+>}hPb4R`Jk|S(vlk?d77WR|sP#U< z3(heAH{p%Z-q+haK-T}&_7~0nvHq|6S@VCR)?enwdw1se;Qw_0@7-`#@PF#!`>qcD zPyNM$XY6|1;g7GdbV2Zcx*qa>>SgB5TIM|B`>)zmHUCfBwf?V;Uu@ow^?%iDe|O)P z{q|+%{|5j2HSdZo+k*eo@s@4c68xWf;ihfD|EU*kuJV8CIa_xI|EHe6qiX$M^#Yq` z#rnVMMfQ5c|Ecjg_&+uCDe-@5=5gWw)U02P|5LO6H~uef{GWQQ{k-G<)c9KbpZBia z!T;%cEm*od_&@czMGJ%fQ(v}fdGLSgXO^!D{!hnyeM9iCethP?Vf(b5`EmSNy~MmV z{!h*OG5$|KZ~Xp?|5Gov_apqD8eg^lw1YEx|E2MNYP=KvFK+ywda-TC|EWuCy?gwh znt7%8KQ(?C|EFgDD*i8S{GWQcyQ1}@nHDBxbc5#{2Bf)Zv0Tyg{r$xo|7U-{Nj3gY`>(X^Z&eP==USW?1|EFd>Z2X_P%s#K)UNAPJzu&C1*Y|I)jPqt*B>qqP^Ye`V zi@UV`dEPvq_&;r@@qcRGFYteA-cRsPJU*_Pd5{$JeqKQ;49>*oGG)zjust2;g7d_7j4*pPn-YK`7c_#G5NCbL;m_%Z11o4*L~QV^@6(` z^N2Sd5dWvwAKnlD7dQS-UAC^u|HX~}Qn{@c%NpC#g?p;sSwE4d~Hb3oMymDRA zZp|!j<^%3p`iwX8|886SY^vMLea^d}d|9&N&F8%rmsKQnPI|HCdK51W{?D&Zae456 z>V-vR!T+h}7c5Si-}s6jZ|=f^Wb3uBdcSS!|K4!NFHz)YNho&76{NEezz7_nR z`r@gVCXLUYpP6^W0m1K07(X;Q@WKV&nQpCn)o9)9vN| z)XeL`|EY%zZWjEXdZ?}MiT_i}|EULg=KtaU;>Q1}S^pRR zr)HiX^Z(StZ9D!?jSp=9-3o8^uk%A?s(<=vWlfv^`(*Fc-tvFC-uOQJU)=aVHS_oI ze`>rR^Z(R%Km1?Z_&>G$U)=b=%Xb_Q{NEV6p7_7G@qcP=|LiZ@QpfAL-wtoQ-dQYhEALM<4qqZ}$Ipy+5ZK z|EJd@$H)Jv+5fyd|C-tMUajEQ=-VIoTdLoF{O{h}9{;D?)A&DizWKl7X8*(Y?`78~ zcium}2bwR$|7m~L`^NvN@qPF|^&s#6|Mlkj z-#R+U*LLO?;{VimL+1a*jsH^*9@I4WKXw08PY(W1*Kb6(`oaIHhj*=)`hGUs`weKH z_DRhDi@(ps|HUo;cU#ZPe0^a2pBm4E|BD;{Xa5iW?^N?4_&+s14gaUcN8$hCX8m6^ z^W>QSr)GUi*8f%G3GsjGF6RC4e`@Ay;s4Z~TQ&*v|I~Om{GXb~kN;CM-wpp4H~#OE zcP|e9kH>@mQ}cN7e`;=z|I_X9b@)GBFT5B2PtEnf|HX~}iyQwJcl>;1d$a6$aM|1Y zHA%l7`Zi9_ugms$T;KTqvb|h(XRj~J^^b3#eSX>Zmp$(HV|k|K+vF^0Zm={+J(`Iv?{>aWjuC?(D~({rqJ6N_=a4`|RtT-P!){ zfBC*_@0aZbv*!b5&jUR4xMNc1mpvcw*kk|i`oO(UyuW-(#kAo6PB^N{|EUi>u1@fO z>Z9tO82sPvYpxFd@3@8yl5f`BT|TVoRl&p1y~fmZ<9b#8Py4fe@87Pt%lB{GxN&m& zFL$Q;<-2OSiTP9fpKjmO{O*XC?(qHD{&wq{W;^r$w7>kH8ZU_d)8nD>e{p{`rlz_5 zubZf@s;|5KmX_>^Q>kDLAe z8`%5pN0m2uH)-7}`Ehuv}_vY|EYO>b&+Hga1?K+B`x0pLd70NtgGo@$=2=*e!kgnW|4;jO zY26}O_t&d@d)+oIlVA3)>4tWDvz@*j|8;K1sou=rWB#9xC;z9G|5M}l@PB%JbZ*x^ z_&+tD-}pcEX{}oa|EFd>W&B^<_&;^iHm!sIQ@8BUKKMV~Klg|KQ+I0HF8Dt+9+LTg zYP=-=Pu+|8i01#)%!eyB|EE69*7wE#se9Ub&-g#}NvEBjbo|MRx_f%rdlcU#{V|EI_e#D0HnDky@#jTy&_Sv0ap3-`zQlZEy#Kgfy;D8P z&Ntr9dezMTo4EDh;Q#vP=LG+!9yq|}kJ|h{_2@Hlg8x%@IIDe_|EKPJZl^H+Pu>6Q zF2VoB&HO)g*Yk6eM%RB>w*S;QvK8T?Wtz|pN_}=_&+uC z^qBvr#@FHh)VX%P_&;^V*7L>xsWtyEZv3B``F}HiTj%F9&^+UDKd!B5yT66stV#9o zJ*!iV|I_2gv*G{Z#{a4DZTLSm{s;dTH~vqJ2g3iU`%KDD@PFzvtnq((JgonU|5M|K z@PBc?b$+Se9{+~_)A4$nC&K@!@of0Nxbc5#)*r?HsaanX|EFfYApS3I{Ga+%^L_Zg zxbc5#`MA|{!h*I#Q(*O|5NAN{6YMmx2>;=|5Nv#Ts8ksjW@&p#f|?{l@ozFL;^?Lpzcr_c|seZ^b;Py5pkk9yf}FaM|KPySDhpTqyDPd7h@|5LL+ z{x5F)pPKo8_&;^8DS2W3pPJj_|Ki5~#f|@qoArOyctGa=#f|@q8~>-r&;8;5)O{}Q z8T_BRm(8zx?CA%6JJ%Ecr|rzQ!~dz7KZ*ZSGkWMl>r##X)9tyw_`kUEe`=10|5LZN`Hjr~)ALn-e5>I92G-g;_`hSvR?YuY zU-ZTe!T+frEh-NFPd)F$UBUmU`Thg{r)D0EegEWLX!8~9`zdecQ`z@d-h3Zt-*2TF z|7T_^_(8l2{!fiJ!vCr9d-y+ffz7YD>&V`Iydv9<|I_&un_t5JspbFFi*5U5<=x8u z^7398)*oWN8U8PB{GWQcc|!c3Zok5O8vakc&O9LgPyK<-XY2oV8*k13)A?)upSsM} z$8BKq|J0@C;qZUzdFJQvf9i!_{VBo!spbFT#{a1|SNlKprfUDE#slL2;>Q1}@s0Su zxF7!OQQoWV_?h31NHz2S_TRX7@PR9AejWZ#z3LBtN$`K_mDT=FjrV)0_W^#qwdT`? z4BOuu&xrri`K&NMXMaw$eV66U{6GAk_NVcGYR(V;r)K^l{!h*PL;Rmw{x5F)pPK#g zf9i#{elY$|U0~}2_=dWDj&FcyOr|U=K|8zXo z^Tq$gjsH`xwe9#nHJ%Uur!KVZ_&@dH&%O@+Pxr^|ng6Gj|5NkxjQ>;f^N#;hGp~>N ze{tjg)c6SeU)=aVHS=-se`@>y{!hKoychmY&HD%bPhDp3SKE)jD%JSEiJkTd9+2&| znomqM{!iOk{}=zK#;NVy+@PBdJ+J+@+yu#u0zVpV5;Q#9Wx=-+d%;UoUVPNoo%WXYQ z{GXb6MEE~7^Zf9C>esFDf9khvfBc^s|A_zFv0~rg|9E}i|I{20|EK2pHP2V9USZD< z{!hKe-p}!W>UF^b{#vBQ8}UCi^RMuKI-jbZ*+b3zEc~CE`C0fsHS;0ye`=l|^PRbV zea#Emyh!h*_IWvL^7YDDhru{^8fY>%5t7 zg#Xj?S7!dt<~w?qn*THZS<|bx2LGq?FIlxE_&@IzTY~>nFD$F_f9gk{UlshHuIJg4 z9|`_XJtgy8@PF#d`@9_dpZbhp&jkOco^rwaHg9rBp8EPLA5WgzZ*;2d_2P~HJLc01 zz2*OO`}sGV9sHkq&Wv%v|EWvvz0$nbEqQu8U)lP<_&@cc;(5XUspbFF%h#<7{!d-8 zetnq#r(SIH{`x#J%g?WP%l6>^bpOR$w+8>G{mXXj2>wr9x@Bv^{69782ebaKn)!ar z|5GnA&&&Kj^_;C$>;J0fZU2zhvu`h~_J7*G*nBGfPp$cX>T>fpHg7Ududk)%vnFlY znCb(UZT05gi{Srsdwi0;K7IQ-^NZg<`l z{!jhFwk^T`so&lCQSg5{Ucu*I@$>8Fv)Mks@PFFA(R?q~PmTBDvFh>S!SH`-{1^T& zZv3Ab54FGfKfNE&_&+tC5dWvf8{+@e@7d=I{!cyE-XHOQYTiHbe`?-8@qg;2)&5V7 zZ^r+r@nHBrHS^(GKh_|l&mYeB#=9GOFEj6HpGV#c?fe@~Ym(||Q<{0>11ryI;mvx; z_&*&VZ;$^|SJ>}+_&+u8*Z4m*9uEJfmj6@p{NVr8@_%vT|J2L}#Q&-BHNF`Cr(R>P7yO@k zgS|eP|EFGO$HV`r@qYNfxW9hucmDX8_t*XD>8Zy5X@9ok|Ki5~spbFT#{a2{?DHD` zr^fT+|I}r6e)vCiiFrl*pPKo8_`kSUe0ZmKiTS{Go9{~X(`)Yb#sluX{2p)SpI%mc zuQ%)SZl8ajce%|A{wj07Uyow*c@O41km_!29`s&p+wp&T{S=w+>-6qJnTIob+4qe% zc&jZT~sfK2g)=`S5?be|#VQ zPrZ1>n&AJ`@_*{`m1~l|r$1A3yycZio1V{lmzP_c|I_}Zr4_;dsqufey!e7|FDO}- zw0i1A?|CIllWh;ax_As87ChUyx*<&+#UR%`u@q|g8x&Wm)j=zKXr#wk4^Ibx-e6(^uXYa zGUop-_}3!u(+0In?)t4D)%ZW%ept2tQxC89e`@>?^Z(RCM%enP=Ks_KMz#$8Pd(_2 z*1`YPberJ+)c864pBmqW|5FbiQ|15EqsO)n{x5F)pBg`i|5M`u@qcR8=f(f2S)X_L zL2JC3hxf*jYrR=-_1+WK)wDgnD;lo%9yqF1GOEP}Z~R=B4j-iYr0yGQ+UDCa|8M8* z2L|M1F>-kd-FPy2KK_&@cCA$EU@|K&Y=u-)I1e|vNLw^#lr z)f+baUeSA9|e?Qy1V|rd$e!H~y%kKX(f2>8- z{6Cw?7yMsWn|Fr)Q_KIwZPqQ{3}5hncsl%_TK-SX{o()A_$T|bH$Dpgr|mTU&)Ym2 z{!iVtY2)Dk)c6tnpSo@9D*vbEc=$gx=Y#)KGanECr^fH$|K96yd6oaOd4Tx8xPR+2 z!}lNEv~BQzy8XyTt%Cp4^EZ}VXB z@tDsRH|xK~ojE!E__Mp&DRoo(w`iQc9@*C``}$`0|9U>M_dn#2LsIvj?f(uv>fqG& z?9TRo|ErHaI=wz{winE9<^$sYUcKbH;QyHS$Nayzng6F|{b1(*9e>>Kg8!>qw{Gx% z4^~_g{NG8oz9s%ojsJW4i@Q>d|I_xS4NeaJPu;xXDGB~heab1PBtIQp(+wLoOh)|S z_VWF%oEF{>**bGy*qDeA+)-5${{_l~-HO+j(*>i68?RA?r3jR;`f3kVKo#y%U zc=&m1(C@}nKXTUZQ@!uB8@%z`GrzvUkI(J#e>&e5wq82(|I{a+a#HYr>eg+|6WaVg zH6E?U+cQ#a+q{_%$oxO;k7vXG#f|^dGmBvGzK^UeB=|pd+xD%3|5LZ?VDrmu{a;-l_Q(Il{prXH{PsQC+V#A6qIdT; z?ULR%o$t*&MEsv_-@*LfYwt|(?ab5LzU*A@{(0S#S|6U{J#yHH;Qw@flP{bU{Ga;D ziRT3Wr|#XUZSa5U?j4#3|EKPk*D3fv^{M9D@PF#wd70q<)ObDopU%IldAffrI>YzJ zb2eT-D%E4Y80p={)Gm}KPu(YzAN-#>)2(~(fARe@|4-e+*7Ln_@(}M#UeDzH z-w*cg-K%fv{haxK@#j@iD?RV;u!GY6ub0hljQ1a!NqfQpHqSEN&h^Cqz5VSW!T$|8 zH81!-by)oYP{c*!?&fnWB;w*c)v}#TT+ex)A@FrkQ4l$ zy1T6(jQ>+J-;ecw)u-G1!aWCU@Z)hl_&=Qw=ZpVSb9?+>-1t8==a2u38~>-q1LFVU z#{a1`|1WO*pBf*B|5M|M@PBH&-Q2QjsH{Q zrSO01&Nd$q{}(s@PtEc1e{tjg)bf9E;M{xR=C=J^^f zf7Ba~hX3=&Yxj@;Q{xAj{}(s@PtE<||Ki5~sd@e5|Ki5~sd;_j|I~Oq{GXcnfcU?- z@qcRhzqs*#apV8g_(1$$-1t8=-Vgs5H~uef{GVPw?2rFb_nq7`_&+tiv#97=-_H8Y z_&*(w#{a3=AOEM$u^xEF72Zw8wF&;O{=fGL{_ps4?UKTu&MdpI)jr|B$K(ILtUcEI z@rCpGeyFVXBl`pox6r;nweOF-`Mv`Gr{k5FN3idoe0za?pKRYxc^B{cIQT#9&-#n_ zKXs9P|7+iWdE*7``>|BF{jr~Sk$qn{exJVH%s;{Z>3H}H{GS>xga1?G|CYYj!_QCt zPmfprPtE$M_&@JYs@DJ2@s{uTCip+~YV&~jKlK`0PZ^|7m~Lf5rc)ncv6!KQ$f?{}(s&|Keu;pL(6mBgFs3jsH_u z+T+3h#f|?{Q&|$zd!hJZ|398I{r{^ykh^RwY@ptA3Gi7jW@*q>3FPPjQ>-w zw|R>8XK&WaweMQJ@qPF|?XUTNapV8g%xlE|skxr`KQ$f@|EIU{m;A?ny176Y5&Dv{4w}H^`nq-Pf?J+{ z!F!4A|MB8yYTABYyKH+h)erymQExoe_Xj_eYMWo;jhC=_D5?JW?AyHg{vQ9gbNRl( zqw@Vd{!h*O5B@Li`vzR>&HO<8-@@km1rJE$|J3q-apV8gthbB*Q!@{B$K^fz_{@uX z;DwIfoL|3B58@l~ ze`-ADoj-r%y~4Z*{?BH_1^Vv%Tg2 znl9ZxctD;X{GXcZkN;CI*~z@XGVc}Uwef%2&g+r+e`?MDQx}_`!2judczxRW^-x!u zpTYmBS60veQ?uRHW6s3{vA#2n|I_tky;J<3n)yZeKQ;4?e);XbT)jT4xpW|EWtVHwFKv$5Xm;bMSxO%URF1 zPM&&U@tQFIPyN7iE6uAl_U&UQJ#4Rs*52cWzhNG&v-jAcui5p?^BzC;dGludysx}` zLGXWier}lYMDTy=Yp;F~FPf)*uG;^ppS@vPnE$7qf8+VV|Eb@<{v4iPzrVt}tNfoH z&ld}x4gODESndDR>prOD_3XD_TJ8U|y>e64{6BT!mMzJpb!YkhwEcW|mzn2d{-5?= zx@~*#f9jHLRrCMUctQN18sB&Jpt*T^KJk6O<}UQ+_p=vTFHW_sAML%+)(igZ(52pZ zz+3-Y;f-Hu^w(A1_$vIL?hpU=Vuy`+di~M88*KHiw0VPH9kMgk_WJZLtM-37Ua9%N z`)~Wwk3V~5Meu)m{@z%=B=|q|14~MR|5Lxdb8E6W`G;Sh#rFFs>;LL{m3|WZuJ@`> z_5}Z@?UlQ$*8f$P+V#Nl>HJD;-WPvX7n@JQ|EWvNBXzprz>Ka3|2_u)r{?_z|EHG! ziyQx^o^Si(|I`cY{Sg1BWw*7M^LX)pYCga4f9mD-`x5?7z1lv1@PBH} z|5Nk%%lyB%@qcRGZ}+{vTSlMntXFNHzuvt6zI}e4H}AjrKi!`BbwdX9s@ZOjAOEN0 z;kEI9`u%9RJs$jDO;`Cp{eFmF$N#BU+2<+#Pt80({Ga~*fnUV`sqv8bKXs*DPyAop z_&@I*p9cS@UTL3~_&;yEKm1?Z_&@a;yB@FIa!#u8e>z{D5By);_&@bp+s^zy^=f;6 z!2hW$wtW)(pPKcC@qcPOApTFyZQ@qg;&_I`%{)8kud z>-XaS;>Q1Je|#VQFK+x_+|2)r8~>-4|BD;{r>-==kN;Dzuz7&^KQ$f?|EFHEep`b7 zQ?Ibcga1=6{a{;y|5Gosd3^Xk^%9$>_sGzD{qgeqL2m#1yygFNJqlNE3H~qc3FQxD z^xqQ-%>NBo^kAy-f7)JR^Mvt#YP=!-PtAJ8_&+uC3GsjGk~JR$|EDfqy&?EN_2O#( zr}Hba^?mVw-Zl@A`G0XU|4+^QKm4DLS6uD?)CK1Ij_dNAZ>RTe^SpOq`HJBGbi8?s z%Y*+@&nYMk{!cx(uq^mL^}M3e;Q!R`7gYH_^}KoWg8$R`%(eA@@qg;K%>&~9`n0bd z{NHVNRrx>l4OdT2{`uMb%%rsk2j7?1u~~BBHw(O5_Nf#6pSE`!-YED#b)Uh_ga3>B z-TfB(?FS8NoNTULN9f>LFt~2mj|?J^wFm{Ga-?QC0pg zZv3Ab--!QH;~VjRYP=r)FK+ywdf14T$zHuTc@H1iD)_$!Pu30|kjDSTjsH{QQ1}@qe}M-sR`R^Y`6DA9>^dHa@l68?QP4#g9|{)SI8w^r#NO|LO5E zUlISO?tMo4r0mj#f|?{pE|rna@_Pk`|BS+hyT;h7e6ofKXrFo4;TNZ z&b8MA{!h*PJp7-U`GxpD^=X5eB$t%@n0cbl!I?=H-I0&yduZ7|yqT|u|I_}g_ly5i z%m1la-xvR<#y{f!)a;M{Q*%80U)&SE`^}r%-~RXidUJdHpZ4ec@PBdR|I~x3{hzMy zz=3vu-|n5S9+uZQ_&@caZfTFi`o8h^wFBC=O*Qj^;_cb%$98GiI;{UI??U7M)IDq- zTGJyh$+ww%!TV)ew+rk4s)w{}8~mSoK+~3C{+}A}hyPRK8O+LgcWTiz_&;rDUKIXM z&Ac}JpSo9*`oaIH@n-lxHJ*(1f7M-^wg~=D-Mx9Mq|?}I^8dE_%HaD3G-;Kr=y9!g z|5KU=|EKND&%^(zPqp=eng8eA+}7hxciF`uCZBKCBPiYsU@V{md`o z|Fl1i|5I~);^!}WJy_;d#oODP=ZQPpqh))wPA8}RTDL3@nC;g(os#x#ZBMC}y1$N1 z|KFZ4+qY$VyKIm5zkFc!`o~<~`0;0ZzwFLFpX|q*Zyqc@Ubg?se*EpT)+5e7Ubf%M z-rl)UgVg=~uk$^|n|I7A( z+3N+f9`FU@?khi|Xh!gS_`bSd-|LOv+kRzDQe|SLrpSn@q zdcpt2jsH`#UNH0j)Xf{!3;s_n|EHG!JN3Zpg8w_&{3re|?tO}G_v5v!Ywt(q|8%~M z>KvDJyr-t?A9sB6-7z)I?SF3d{pr(g ztLaX*UN8Pnw`aXy{GXcnf%w0;@qg-u_I}*J*7Mc*H*RbHe#QKsn)es{pPKh){GS@% zhyPP|Y}YFIKOMhKyOznjzs&Ueqivga%T8^Q!#&huuy=z8Z*@NQ)u@WJWldUqW)Hu>*E=Xj62 z;_BqeH_!II?5uNx|I_^q%kLfhpL(FplV$#&8sE+QKlLzsJ&nF%>Qg$l3jR;GZ_&MD@PBHa zf9C(G8?|a4{GV>0WB>jF|EK2nFZ`dk&4Q1}@pJe;HS_Z>>#*4ye|J!`O{spp?#5L2IqCy%d>{T#$IG?z!~eyN|5Nw9phxh3 zaX(Raby>w>hXsF@Z|mE3IC_RoU|EI>!;s4aEH;eyM z53%`u_`kUEe`@x}|HX~}Q)~X88ZUS9tRjCrc)!wz>|dc)Ki)p)=LG+!{aZ}T3I0#r zW>WVs|4)r~!vDpM|5LLbD)ax;_{M#P&hz_YzTgY}=6W+<5dWw1>0%xY|EKP1-fUX) z_q=;t)HON0!MonwFYJ=MQ|BG;&Xc+(0}h$(oin*x^7TG%dvpDm|EKe#>;3Hw-#*s% zFaE>p-ec@|_&=S`Y3BX#f9liC590sScsu-G-1tA;AKUSNYP=i%Po0^Z8~k6~_&+tb z$N#ChJ^oM4{5&@`jsMgBctreP+$Ws&xIZ5JUqR-vRFCZZs5j^L zmzIyD`rd{Qd-M339siJbzRf4Z|LOiRlQO~o#f|?{^YerMiyQx^*80C{_Q(IJdA{*~ zYPRG5)c8~8|HX~}Q}g=8|HX~}Q)~X88qYWEzMK5<^7wY{cVnvYe|o*-PwE-`U);?9 zQ|C_U75rb^KfE!`x8pBcK7N%q&j73a&+0}UG~Y$dU|^P1#iww4t{P-*@$iXW)6I3X8x0l3X{X?k1p$e!hXRA&fT~< z_`fG_-Y8(squ6-AAPd#Uuk~s-Bap&bNgK#>ZZC@?-RZ8bsdKv@4fL4e@Z4y zIM#cGo!|Xe9FuDNpYFfXd>sByy~gJI;s4Z}AO26x`o#D@^*YuEHvbp*iVth~{W0&) zu0^WtyDV?!|JiJeRNLB0-kjfnfxndMdag9ThyT<4ZMOA)f4lQX-@eKG;+WU}>WyE- z|7m|3|EIP0W553ozzhwTOjmer_&+t?3;!24 z{!hKc`~m(iZv3Ab--iEtyI}te>s8bEKQ;ai|EIwSW1C!RL9io;3dNcO?e|KUij;2j=^V zw1271KjMFC<}c#^)U0of|5M`=@qcmK{@(aj{GVSRYy6+CA6~<}Xs)g|{$%%?GrXCP zhX2!c8vmze-WvW-jZeYcJqfndoNqH8PAlb z^Iy8MYW-h5-X+Vo1^=g>yPz`oKlNSDRQW&khzqOypL)z`uLS?6K6lvc;Q!Q9#=jW+ zpZdlt7X|;P=kMAXRrCMUS6ux-@PF#pZoV$e|5Lwt+x5Z!sTbdIY4CsQIX6t?`OVY) zExvbZnE$8#a#7X#zv_~rs`-EFt((^b|EDhh;Da##PrclH-`eI+`0*ER-W>d&w$u1O zwfvvD+~)nU{;wJj$NWEa@rKQ;2kp<-?9E$)|I_pL{&t%OY5q@LXzTyt|Khg!k$L|5 zuz7!VW-jq&o*({C`}6*Q|5M|A&71oE@_#y>{GWQ|&fUTPsqujLKXt{n55xRF9e>64 zUBUmU%XjV!{!h=}%1>=Q^W*>I*Ms%UI~?*i?_!&`i2u{|dd}9%#{b1_Kfm5@*yCmX zpSI7o_h;7b)%_RP&lmnrJ>Pr|)=xdh{0)CrFSMUe{GT4*0y`f5FK+yw8vn-pKQ-^q zFMM-&MnB)Y-~R2BBfXc}=Ye@|Z#+5vPy3hI=O_M8jnBjXsd+!e|Ecka_`kUEe`=m@ z{GWP-y&vNLyzTh-KQ;5{@PBH&8~#tt`xpLC&Ev)YshL;!O+nj?KJW1JC9~Um^Y;tp z|7rhu_V_0}+S#`+vfn2<+}Xt&pN9X_@pym5|EckN_`kSkj?VXHUM2od+qpgdPtEHc z|EJ$KmfQaLKQ$hd`G5L-kk5PkpPK81|5LM`JnR3enHR|VziRwC{!f2DS#8_#e{tjg z)NAefGyhMG=fnT0ndgW9Q!~HszCVu7=CPTZG4(b&Gf5 zrX5M|M{f0AYyR&0yKnPeV?O`Mn{W5V^Yxs5hd1*8znyw#svnztSE@4;?)F}3`~Pvw zJ>C^IKM((>$BW0q|EWvYnE&5&pFiLDy=zz9pKAP{ULT9rYzqD_Zv3BG^Z(+;|EUYi zBjW$mh3l*QpSoz(hT#9y1uNDD|EDgjT$em^*^_>I_P^tTr@S@)Pmiy#Vs$cZ#4O*w z$Qu8rZy~5ID$B8d`FDfWbmLB<1s%IbgviCcS zi<8HbSG?aYSe)GWubQ5}pdhLB^s5>D_nP5G7iK;kdPwj=U4}MHUhcQZyLZ9mQC)#3lttY3@&)Bb0g=fnT0<^ST|oLTC(XZ_rN z_FLvX)aL!2ICyzY+kC(LQ5D{JLHwVNH*8eL;Q!)&XUa<7pLukfrmpg4ejff$`{Uu5 z{}(s@Pd&uE7XD8?%+@=`|EXF37XPQl1LFVG%&WuyshMZT{J+U>9_sS|@qcmS|J2N1 zd*r-retY_wDcimAXUzZ8{>*Q~|J8Ksq~XmU`u=z`{GZN;d3^XkHP;9Kr)GX4{!h*P zMEqae%>RoU|EKP0*8~5j?qkm%{!fiR#Q(+pw;f-4-DZ_XG0r)Hks!d3tD#y9TT z@Go!H17`l8j^E#Y{_%h6)6D;#{@G8_{!Nn0|M0W-pg~psPx}uX*gV1i#f|?{4<6hy z_&@cCq3weIQx6;5Cd~g+bNu^i?VYdY`1n6v@1Ffy1plY*nr9wq#J>4@ewlwZVtcyd z?|1WBr9EJ7%k+FeJir+bT%0f8!n{BHpSqvTzr+98%)H?L2Da%K{Ga*^^9RiTQxCK6 zvswRF&GGSnYR&&s-DnrIL+R9tW2W74Q_`iH$_PoIC`G48-{IWZH{a?Ia{Q5evZk^!&%!~#9SFgeG!T+i8 zdH6qdqx#1O|EK2l%lf~y|2s4IKN|n%UB7DnpPKoASIxh({EnBd4}Op1UDC6r@vjrt z-{IREHmaM9AD3?C|LOMZkN;D1zW6`g-zg{A?N6=gh9{mB{GZOB?f5@6^ZxLEwuWx- zf13ZN*8IPX_udrzUrSpL82_j3toMum^KNGEkLLf>t<7KK|J3Zy`oB6JjsMejJR$y1 z=f`&ZpSqo`Z;t;{v%me>oArkAfARLK@15!0%06$tdii?q*7kX1R?xeJt=C(*X}Why zThF&w{tQ1qycPaW=TGDR)Of&cH~-G}XFc6oPhIQX+Wb57|MYlU+2;xVPtA7L|JCvE zf%rc)^9S*NYVIHZr^bi9d;OK(TK`wuJ9p`jJp9@fzCFi$+O0*Gdw1#7F8Dv44<2#! z%a{21wXyYo$Nc9K-@mQ-{?iYwX}ll)Pq&xP)BhVg8@Gm-$N8|5f+S=^Ff>9v|x$=$exh9ahsE@7u=1eLK$|>;LNZ-CK7E z{!g9Pu5WR0IMjsMf*XMPy|PmOomaL`I`ywD|kRi?Vuzbm|ln;*pg>HcW^pPJj_|Ki5~ z#f|?{;7XWkP3r{?v8 z|5NjN!~dyS-xdF-?qz-v|L1Mj@0Oq5^k#iz{GYZDHUEYGQ}cN7e`@CC;s4^s|HX~} zQ{(0Ee|kP>{GS@HhyPRK`I!Hw#&6;O)XW>i|HX~}Q{&(8e`;QD_&+uGf9eHK`T6m9 zJ|Fj_cdtvjCchv4M5^(BdOXZ8#Q(*O|5JCf^_KB}>h4o=6a1eV|AzllFJ=e^BNBzMWbt_`e0VULgKYU0|L7 z|EGR`%Z}jx)bs57Tl}ATfqmbD|5Gor?~7`8Ki#`{*B42_fd1Y^<~i_xX260EWc^S4 zpL)4@LHwV(!aUKG`}6(w%mc*#>He7icU9dUWqN${^KH9%FZuYZWKFLw-gv-&j_mBc z+w+Iw#_Pd5FYw%%*(_Sc@$#_xZn&7*4Asg?IC^MD`pZQ)&RjsMf* zq49s}xx4=m{GZLl3;u8ZC*PQ_I>ooIHV=sZ)Bbow{GYna{2Bf)Zv3COeV>c}Q!`Hv z|EI>A;s4^s|LJ^~SBU?M`>5v*^Zi$T_FaHRkP}UUOio?Y_LXm>;z7 zZv1+&p0UkF@MgXr{!iye9%Kydv>Xd(%s@K{4K>VMYd4TvoHS+-HRD7T6gTDBq zH}eSbf7+jB{-2uj!T-gL|5M}tR?pbxz0&6O;s10!OYHf>|7rg+J0AW|t@(f2U-SRe zJpcH=xO)sO^4phJ`#&9z#{a3AkBR?N=z-r>CF)4e&rIuou;HU4kr>;r-q zEVS>x@qcRe$N#CzZJyNJ-6Oo2e>&xmf!_E$^8(&w=3(%Ex_yE98vLIc?}z_W7nm== z|EU+7XPDpqB=04=J_-Ks%%cyiTCdoSkN;CIGT(y#Qx}>~!2hWiRQo^7%6VViluzUT z)c6JbA8T6T|L_a=zqrjKd9#1c)6aP`{|W#1-H?NV55#NY|J3+!{9oMoKXs|iFT($+ z@qXraiq%DSd-HkT#rAoD|EnxGsA@f7+iv?8X@9o!zqoCCcXgE)oY_Oo>(3r<4?W)S zdTREIH{0=l+K#WW^(Aw4eVOls|5M{f@PBI7)5QP9jsH`ZZuuzqKQ;5H@PFQ0cL)C$ zH~vr0AM*h5e`@CY;QzeWZV&!X=U;9;XZs;}YW&|11;=>f|LpO4-}Bt+F#k{2Yv}n8 zg!zB!;ip#lzqpzIr#@@gv%&wVubwpD=1mUv?K7@_G}$=u4Da7v_fYVEdVXi!Qsw{D z&)zm8_&;^gotFjwr=EA?g~9*n{)+CqHuyjFCv&RS|5X<+uJV8Ct((^d|EFGR>(jQ( zdBo3e*~Slo|I_xl8#V<0r(UpWQ}BQ4qK#XU9e2Ov*K@J`{&n4q*SrgCe$xq;yp?MF zpPrxDHb3va6?5|Re7>`Jd(vk90`K?Dk8FCe(0h@2Qv9Fx$1mak)cB>vQ!2diQRBy~ zN;UpZ`{MFu|HVDCc9PNk%`^Xl|5KOR{4o5VdV%>F{Ga+h z`+36d>G3>i?>GEez4W6h{}(s@PmO;Y^5dZy{rt-Rsk#36KXrw@pWy%0@_%vT|Ki5~ zsqumMKX3DM_`kUEe`@C0;s4akgT?=;@niVExbc5#*2l&Fsd+s3Kehay8V`y8)8`%A z@qcmK=cPBk{qO@iXY_f`{u6)7@y72h`o3$b57^V)o7dO)O}XBjAO27G$K%8Q#f|?{ zSJ?gG|8)QIe`?;Z@qhY#hriF@|J1CHjQ>-!J}>@H&EI#J|EIst(D*+!UJw5lH~uef z{9oKQ|2?C>5ApbHKD;;c2JwH|&ic>zKQ$f^|EJ^0|HX~}Q{yjx%)cnrr?s8zjR$Q2!`Cel0m-s(*xxJs_ z|J1Di%lyB%@qcRhzqs*#>iH|y1^=gBP-*k~Z2q6RaK-xI|I`H)>w^DNFSOg^|I`aA z)&~ElE?BlYnL7Sy-@a(+s^I^$eWCe2{GWQ!vX#OAsf(7a2>wsKsBCHQe`-7+{!cx( zcuDYo>V<_R!T+fjm0S zECx_Pa?Y6nCJ#AB!GIuOR?IoA2?fNQvxosvB*$Tf8N!gG1TnDcn&awT!>+ro`+wfw z=JU+=^snk#x9Y!Dx32Fxr_VWkx~FG!Uh{mleb(Ih!T+h}S>ylIQzqXN{NF#nI41bN z%O{+Z>eO*zL5tDH1mD-9NuAUg*^4SWuUhbb+MYA8QSg82{Ju?7>jy0L{b~H4j$gFj z|Eas1C;FvoiEl5od1uW3)AnvQuMYpG#$%n^yv%!udAlj?%Dwy9{J7a&R(j(B@qc>! zVEg?E{!cyB=J(;XYBSKY{$d@Y5ze()BaE0eOSxXs4MsS_8zuAbHR=8M4k43+P{bS zP5hsl>&5@6xxPvNeBZB^=RfPe`@Hd#_&@E>{r&0a4=cA@*Er!LZ{{oJ*ZQk>Kbwbf zcEgXo@ss#J9S=W=|5MBVspbFFct-r6y07`VJOA;eH_s3Mr|tBl(O>)dxxe^7y+63W z_&+tr|MAN25{>`Uc6{suPyWrnzUYO|fA3v5q*dyjmw)gsvg7~f^}l=fHqY5$-v1;T z|EI5C=JnzK)ObYvpBmqX|5Nw3^>^`qYPSD(_dmT^Z@1z5za|?0r~TQE|5M`&ANlS# z@BTJVblH#p@$NOaRcha_zbE>DRH{&qA7tmRIB;bD_&;0o zHuyih8teb6SuYp=r|xGS1plYT$Kn6f_&DbOspbFT-f`d+g=Xx6_hWzjpSnwv=E47| znRkW%Q!_sf|EIEv5B^Wjhx?EJQ*%E2 zpPKc0@qh9~%vZwysd;|?+v}6L9&lEZ(x9V_&;@n+9w77=WU)2|JQi%?ZN-Co-h7St@VG^%mc*# z*&5ry|FIqar^egi|I~Os{GYmMgIZzzUv>L>wSxasx2sz-_&=SmW$o(0|HaMxKV5&z zlhgiB-L7uh|CzxH{;!F7X4e0WoB4m=j=$6WAM5|B@p-KOt8Q-Z2mGHNPvig8cs=}| z_Q&hlHs8+I&+6RDZq=Z6@PE4AdiClB|EFd?qS>v==Vv|<|EKN28=C)9w`$Wo_`kUE zf9l$8S_c28uG`MM-d8vHc6{EUN8V`v7Q!`Hx|EI=};s4ak1Dy8I72bF){GYbt$C&@8^Wz5_-FJyM zz7YSX?RCuWoo4<|k8jY?*2A;;f7;Iay!gMkng6F|y*)F6tiqpL%Hbp27d=^~f$N zOnjbp%FRjii8-ATojUQ@L=QMA`T2aQJ^%Rgxm{6q@P7@~R1N;GeYc$8|J3;dI|cuz z?mjF#%>TQkb+zFC+Kx8AWd2XxZcJVZ|EK-4Mt2SVPu>3XPQm}FTb!Am|EF$!R)^sK zPRXj8@PF#gV><``r-q1LFU5eEQ~_clmba>z#Df&O|S~@GWmV9{x{{$M1bR za(iO?l!4p4+1{wfR_{~JEljP<-r_y%?EKW2cALHB|8%`{-}^R{{d3dt!Q0@=UYWQ) z(fB{@&wMZZpBlf0|5J}N|MT+S)_9Mw{R=-^?TyFU_x`Fx->`F~H-4zv#_~kZD=+ir ze1n#(Nc2~4mU`pK?tZx>(fB`IAIE3@pPJ``|5M|i@PFz&^IG^n^$0sZ{!h(%#W#Go z(C-(|Z}-~^yzz+bw$1nE`tA2m-aRfTOnq58*PG+_Tr|gf=-D}`7iZ1(9&~os)W2VP z)4TuJtkmhx%<{%J;{SAg@_*j@{hwO?PmRyQ|HX~}Q{&(Ejd{h-*Ly;Cs_V#?z43I9 z4SdNPZ?|FDbboxff9C)6{^tJS|I|Dl|EK2h_&@b2_WI%f)I1*lr{?uP`ub=5d>rrf zOP}_}li~mT`B>xs)T|GS|5JCd^<<0oJ?76R&(`mKcGsic*>=D1f7+kK=KYWVQ}h1E|EcBw;>Q1}dA;y|`aI(G#Q&-BxUB!H z{W(AWPtEc1e`@9d;{W0v{pcBGgGL-u@a-`BySmd_r4F8Zns-h6?`inInPrCr|99Ez zcZT(UKl%Bv;Qb!3zc*+7--2<62k$rYt@Qf8>c#f^3H+aWnaxjlbmY)7J$`}xzNP$v z!QPAQ_q$)+IMAE*%TBnjzc=fX;s10zybJy>?sL!V<&76P=8_)X%#$j;rCVj&d_Vl3 z9$#*a|5LB9#{cPhY5boWzl8sb8~>-?Xg(1Cr^ff;|J3Vk-WvW-jYq`)>HIwYtvM}y zJN?_r=HB?jn?^SC{keYppP9JeALrRTE9U>%jJ)9g7MLf*|7rUsn^%bcQ?Iw<;s4aD z%%kD|)T?b?9{x|w_2d8I#{a2bGoOb4Q@`=~x2fV=t9rA3@fY_WmuUQ-_Gf)y{9oMo zKlNJkgZ9tf8$SEae!q37-;dpP{rErK&zn;DM_lx|Wn)!hEKRurH zftmlOX8sxePp$cXYWyDlFK+ywdWFq%!~dyEZJrzcPtA7xpPKFXKlO6^Ji!0ydY4)= z|4+@lHvFF&kA?qJ&c~>V-D{3je3Z+u{GzTo3+FJq6K0on)ZybJP@PZtF$nRe#dgUqadoy1N|2Ou7BZL2=@qcRk9{x|g z)Vu@!PtE#~^WMJS8~<=>vs=7Z*!A^)d32(S>g0PbP5V0UW#;QnZT4G+xou zlKH}tlDY1H=Y##r|rBS@qfC%H2zP$ z+^!e@r`GzvapV8g@_%vT|J3vB`!VzX)bq_x;QyF8hUYBVKmSj?WXqo5|I{U0(*94^ zPvig8tM~gq_51}D!T+hJKDR0OKi$tE;~xzEPkl=6b7B6UdUVh9`oHRNL!J%(Pkq(+ z*}?y*FTeir;Q!QD-0%cmG++JrT{owOcR0`c*{OG!54+U6?18JygI()ga_{BA|LO6| zAGjv?KlS@_9}nyQs*9J-OC9t1J$^rSy|sz=v-eu_eZ$s2?7h+E`~A4|aqr^YyMzDJ z@mAP8JNx?Z?JIV@9sHl}XX(y8!T+gCcJ2-SPtE$X_&+u4`{MufdM?}hUhseFQu})h z{GWP-eg5G8)Ob|jxhP|EFd?AoKs?#{a3A--rK;+rEDk==%qL z{O-ne5{>`!{cU^mqZ|14)%(IcTJKGN`D<$XPmR4d+x6l9{PA{v{GXcZ#s8`Ke$4zo zHQ%rCf4V;Q$N$BR|5M}b@PGRLjc3LGsd<0n|Ki5~sh8U8jsH^@+x~Ob6nJm6@6QJ; zDe`9i-H4gpz4`uw|I_1X`}?H={XB!G!~d!AdiX!J{GWP_eLuzjshOvX|I^R2H2zP` z_b2>c-1t8=*Mt9y8~>+&Us-S4@qcRO@!|i}CA;eXDv$SJnE$6Pk7HW?}z`> z{xtLd)Wx=*FaA%x%se0S|0;WZ@PBIN{W1Sfz0jKVf7SEL)9e4L7nujd|HaMxKlNgp z@5lT<^+NmaE%-n6n@g7k|M%OR!@}QVzP@O2@PFzV3m2t+s{TsBi#-ps-^bouINj#` zy-?* z!T+f{^=TOVpSp9u#;I?IE%W1No3}ac^kVOPTmKaQ*X@_%fMZk6_&+uN z4F9L@W%Jzde`>rR{x5F)pBlf1|5Fb!--rKGpJu-=!T+g8m>%9lq{674j9^dWM*1`Y9jsH{Q1@V7zcWxc4bA_l@pJgU zxbc6_k2^m2KfD|MPd&_h9{x{_$D6!vw?7`g_U6_--g)Nz@PFE$>%sr2@qWzzi#z}8 zcm47BwzL2KUZU}Tx?a{7#{b2=G|LOU1zs?@{m2VHe(fpsz&w9i7KQ$f` z|EK2h_&;?&^LrOR{GGp_xWD*6eSLMad5ri!bq`xl8~+zK{!h(%!}vcn`{V!O#{a2% z*?PkGKegunsWtykjW5Lise24;5&WMT?}z`38~>+f{a^f_df-~`1n6{ z@BYn$|MMQuEcid&-=6)Nr0U#zV4*s%S9<=RUeD$oPD<7PpMwh3?ON0b{!jlszGLfJ z_Fo59-lqS{TrW0rJ=x58Vwv;ivdv52|IDlf|JTKQ8U9a=cf$Xv@l*IeHNLI(>6aFk zTysnCeDs{$%e?U#g>^6Y#*g6tv_IE_|5M}BnE$8d{P;gL>#5@Z)Qy|g3;s{t%+}Yn zS$)2p<1_zH+p}!FLHwVZ>&5@YZFbL}Uw`v8+ne3&-Pb$}>;K9Naeeqd-48sP{j)bd z5C5nATQ;c|{GXcpuh)|QpJUe(H|LL=^T*BkHYq%o%#OD?9BCX zJ2t43cs_sR8#6s%=J7MVW9EFt%=NM}{a%}v$@|^f=1a!+J9Ga`518ryn7MTee_`mCpyyu{?UBEDpiu}16Qe<^n%Bql=Oj_>;Il~(n*Q)SFc_@ z%>SFT0z_Y6SnMW_{m>3Z|A<)VecxKN|n1#-ri?)J^KvOWoXLO8J2o z-4VPWJ`n$>W;^~bZv3CRZr!@U|HaMxKXt2mHG}_CH#hIc{6C$)MXi&9|5M`u@qcTG}_&+=@{!fip#{Ze|3;wT}`C|N^8sCTiQ}cO=|I_1X{GYeI zKUx1*&HK}=k$2PP4Z{3CU0=NhHG}_C*Q#?;@PF$14QmDer^esm|J3bUwN5erPtAJ3 z%>Pq&XxlQ(|5G<_-zNA!byM?h_&;?Ad;jDA)EpoGr^fH$|J3+E{GYnMd3XGuo@PF#O4sC<~Q?tG^ z{!jOhpC9ml>hY(I2>ws+_jAr38~mSo+}P2<|7ri>!v+Wcr|w{{H|zhZdA*tcr)GWR zi~lsnuODA`b>A_5z4UowMtkGy@PB%~H2zOrkZpd${GXcb_&+t<@qcQzRi2qZwKlA_891s7eF3Qad{!cw9uQ2#O_2B%X#OEhoF#f#H?c62NE!!r)zgMfC zT>ri3G-?(2n@2|dp zx6`wN|I_wfqqBqm`*QCI!4u|=$qN2YoqcA<;Q!REN2mRty6ssuuiobWo!s|?;Qw;Q zbO`hR)Olk&1^=hcAD5MS?zcT{_yZw0G#&-?=Pmj+vzlHx( z=bHz_|EY(J&q)m#yCc!~KW)e7;s4^^J7w;s4ZZ z$N#AZ+41pzapV8goFD%eH~vpubWTC=f9f9RcT27OVX@zjA?FpQYJIuLd+@mh!T;%g zF~1N07dQUT+x!y#FK+ywn)!S9KlK2c?}z_WGp`W;7dQS-jsIKp@EhLvzhm!t-5Z~E z$?Y=}z2W-T65a6f8Hv9A{8zo1zlZefU3}4-ba_Q_KIwjsH_KFAo0~ zH~vr02mgrwi~FCO9`VjM?}q==b{hYu=KkRSbo@T%>F|GQ`9HP%pPKcb@qcmS|J3+A z{9oJ;T{FeckN^8-!enpe5%xW2k~g02l~H$lbG+2>ySzKt{l)+3_%!}ct@(dyzMk=a z>Kya6%>RoU|EFd?A^uPIi^l({xxO0?yUsi3;-XZ$e_ZX|!@TAfpIw>g7k6Lo-RGjB z)N_|#=I84;vQ=vL=u5mCoza!`oyr~=a%Av*SI?Zx`cK{uFIyh`pSH7}oc;dDw=c4J z1Q+xeUbgg;BZ3!{|5Jzc&&>a+7wq?cYJQ)G|BL&)&V9>vJbOg=@7=-s^y{7Ir&ss% z{Y%XIRP65V&Hg`pUgTYB>pSBAbp3SSBlCUx67wSXKb>Fm|J2MY!~eyN|5I0(SHl0r zeQB-se!cj?r`xvmW?tZ{&$agb*O=GC|LO6o_oe-xTK-Sh&-_9BpBcH}|BCJLO@C?R z&HBIiKW*Rn*;m2;skeXpdGLSg3Y*`D|BD;{=WU)0{}(s@PhDa@4gaSuH7|$%Q{&h0 ze{pBGImTZP{M%;*M|-cc^@#1cdgIsZcTe7H%p2nWbU*NQ_&@b_yWaC!9pv|u`FRf) z9N^9Rx%fZr&-%qX*ZymT?l;~1>tDQA+Wf&gs{H7^=Ci-0_ICK*oArI$p7u?mC*Ayo zH|rCBFzplXt#*A`6(4%b|LJ-**!kXA^p0O2>rEf{_U=TF`o|7$JmA9WTfOm?N9Anv zX1!8E?EE{!hoJi*J3@8*hgHvo)jB^Dk}w z(WNE#`gZnT`|f1#(s$GI|Fl280RI;^{!hKoyan_B)Of$mPh8}^#QekUTgQ9j_wava z?1B%RW4~W!{-1ij{XQH2r^e6V|I}sX4e)>J6*j*H{}(s@PmSlp|EZVT@$i3Y)`!La zshL-0|Lo2BmH0nxr}2L_BQW?sycqsZ&Ae9ppPKoDHt(wxvw|mMo}l?5?_zsA{?E)< z@PW)@#Q&-B8~8sp>xtt3)XYD`|EYPs@PF#?{-|Hu&qv$*x)NOv_YeQ4{qZh#d~fDK z;{WdLUL|-y-mm;m`>(O@C-}c)-;%4|WZUt7YW#+sKUe2pYV-HT)vukWW<7iSpYC7T zJL&a*)yy-*|EZaO#QeXw@qg+v`+my$ziM7z{GWRMj(39pQ!ldlM)vyo_Ok8og!zBE zzU7gAjF1plY!TefOfnE$7qGk;C+f9iXl-DF;^alU%MnEUMg(Av9i z?(?=DZI*YhuFr(^fAxBd=>Bx@f9lJ}EDHWleZ^Ie1^=hM{>Ep6|5HCX>CeIcsh^sB zYw&;S6?nfs*ZBDtPrQKlhd1;8wj6w?_q($mxA|^&doNis*F4ufet))a-(Y_0e(#da zn^QNQ{;+q2c|ZK0?#IgAds2_heA;`>-n9SI_R^j9_ZG)Y_s5sn{;&S_iuW4xaecm? z>CL>nulBy_z1)0SNx{5)z5b=nS&nh5u9Y{PBP4QuAH-KQ({vQ&P|_>JL*#ck1BH_Y>Ct)&9({ zWBp&9A8&{M)Aw_HHU2Md{GXcdhxos^@qg;Ic76E2xbc5#o}bMpFVN2~t89P#pBjIN z|5LBG`;GsLoB4lnQ1} zIY0CN)Odd8|LJ&aXZ>F_^9k{P-uwMu-1t8=^BM7fYVH^QPtEIz|5NjN@9l88Uk{%z zv+7;xE&r$e`Fz6vsmtx>HT<6%ABg{p8~>;K&362s8sCTi)Bf~peQx*jv;V^dcT~2$ zKk$Ek|LpSs|EK2j4gVK6{!d-HeRuGGYCPaEhfVhFYwhvB{$AND%{Sx!bbX6#{@>Pb z@A3WVrJqdoUb1mpYWjQkdKcT{@qaoWo{;%}aWnr!B0E3p|Ed>mNYDRM7n={n|HX~}Q!n0-p8uy_Vjdj-r!HT=DfmBiX~p{B z|J3+E=Krbjf%rc)^8xXH>IM7P|5eNX#f|^-E?$;8tNca3AB(IvES~N?e_7i9>Hf`G zoc4d}S&P#C@8`Bh1phZ{Ga;SXPyZDZ^boLga3Q##&N;_sSE2J8vLKS zdDA}y|EDg@uNnNGx8Y&|BD;{r{?kazqs*#Y95dO ziyQxU-WAo-^Z)Gr;s4ZlK>VMY`FHp~J)Ze@_&+t??XBH!C;I32_j=>kYJBoeqNmvU zz`7rU%y+(7>pkzm<^gv$c;6de_m5`#ym`HAwf&1X=kJ#Ffj6)JdAT2Yvwdo}kG$DF zx6fa_@s9XEJ)fbrelh+}jZeh?#f|?{;~nvTapw>I(wpnY|7kndv*(7d{QTVCf8F|Z zqVa#)pZnMA-fw+7jsMgAO>YlcKF!TS^ctiYO-1t9rzd`0F%>TvB{6961A6@u+ z!N-SHEvRwuq(Yw0s-FM#=JEJH?N2lRPu<)6U)OsoyU)Ppss2YD=-a#XYLuE+<)A{n z9_>0+4gODGA6;75yeeD&SN}aeuWkLr?}wS^6aW7Bk31m1|Bv^_F9rX%`1auc=-~hM zH$Lp&4^1e%{eaukzR&u;YcBD|SK%)BfBa=KrZPy=G?rkuS^K|Nq*VJ}tBV$OmR_&+JTpm)YGi)+;V*Tqp7V z?9!}mqB}QDZqM|CneziP=ND#nw?@f%ikXeqioagk*!wZ=%=Lyd`;R!@W3MuOEpM1LF?hYIwNFkx`#<-1SF2Mq_2_MteL~&Zsi{X*_DS{YrY1f; z#rJPrw|?+{I$oj^?%j)IM)AFx3u-?BBZUMc&z+)BaD}xu5tyHQtc&bjS{GYbB$?6pRpSoR_&cXlb`N{w3 z`tWb~KXrC?cIwot&h*aB%}w>4Jjxqym;KxsiDvy@Jw7ilFI9WpX^F=F>HKVG{-2uj z;s4^s|EY6wa)SSh8~>-~c+CG(_s+>ne17)H%};cvyzE3bvw4m2_m|AS*Jxp0Io{5^ z&#nLXtZdG=Ck2l;uutFA#ovAE-M>$d;QtOERXupXUfm0V|5N7-=@|Trj%82q2M;{)-3>Z0+TQzO3F5{te ztsUMY$L6FeHf;AEaaMM!-pXy>_&l3$lW6>(&OgBXApS4zhs^(}nP2$rV;jBki1y3`SYOOcEXW2y+-UDsD+G^w1cym2hoW9zd>)$eDl{cQSS)Y~O z93TIu*Mt5jtIW6a_`KFD68%)8(nRC`^mz8i|EUYiL*oD9#{a4DNzDIK=bD$o|LK0< zoA7^XoQ1}ncs&0Qx7#ShW}IJ74d&+j*tIS_d2(0@PE3W++X~kn){3YQx{%f zKI^#`5}p0%^WLoQy62wfyzzSYKYzS6{!h*R_&+uNuhlP4R$ia=l<%JK?r!t{KK=CZ zMC1STd@;Q!P!Z5|E&PtE#q z_`iGKIx6_TH*KB(^Z(Q{_s{=RzhOS1%CQ5>UY&AO@O_Kz_n|or`+GAV3je3=%tLzE z{GS@Xga6a<7TA0+{9oMoKlM`cM74e`@W%V$|FnIft*3?mQ!m~>|4%Ld7dQS-jbFn5 z#f|^d^|BrRrPqYmPs4>+pYZx7&2GzrJg29^Ah7s(Y_D&vwr@Cwgx&Uzhb;wM75*sH)!h zw)<-z=e^0U2mhz{&pPvh_RroG=GW|ZQ{MPO{Gaxx@qcRO`Q@DaC%->5{!jOBgZW1M zU)(oM|9yqJ!sZ9!|Ki5~sqvKfKXtj?U;LkX)qejMH~vq}`o8!-^%}dM_&+tT-+f=c z?~Q-_^r&~d<^S}2SAY10{eE}H3N`cl@PF!+c0T-{n)`wOQ?J|a|NQl~#{a2VZx{ck zUjET%!T;&;i_O>J|I~Os{Gaxx@qgORJT&}Y-1t8=>!ITR)c7s@U)=aV9iOj%{Ga+& z`+aZK=O6Tb%{&(VPurQlhW}IZdBXg^XKGXlUQqroZv3Bm{(k?bUTDuB|EHc~=g0r4 z-!yNA|NCiDmEiy8+j^DwKQ;5B@PFzR=BM$0>XNOyga1?Gsqug6<>m*j9@x^)x5z$E zn@()#&F3-xPy6Gu@qclfh45Z%{tN%7?R4F*el1ncw%?!Q|1c<3C*EE-$Ig%cQ*(a& z-^}sH1pmjpSNxxPiCsVbFSY%c;Q#Ox_&+uC1@V7s<`3fk)NIH9#f|?{GY`>xou6;9 zy&m{KogaT-*W->Jy?H;G_gSvv(cypluNNPP|I>Ef-}d-i9e=C6AME(vTg-3Z z|FoU;d+~p2<}Km>bpM!t#QeXw@qcROd*T1o>&@HX|J3+V{9oMoKQ$hZ`G0D>3;s_n z|EKGd|5Gos^?vbx>V@mxVm_I7>6*7wHG7}n{l@$Xp0D?$$JYh_r~B9Uv?;;=sR!jh z7yO@kVBWL%&V2QSy`M@={BKY1TSmPZ{NI^*W}sfbqwwO()ARq-*W5TQ_&@a%ccuNG z`q4XX3jR;M?CuG{|LJ@SZ$F>+pPz5ZUJG{R6dVQAf-kWOu*o)rf@9wkpRbTPO(_M4X zOz$%DCiZ^tUT%I4|EJ^O^YDM_CFa-gf9j>?0r7uo`9C#24F9Jtw$H~0%hr1@HXn!o z({{WZ^Z(S$`@{dKx7mC`{GWR3o_BbEdUJp9f7-rw_uDD_pYG=x^DUQEeBnK-xGeZT zZMT0l4*pL)XWhos$oqfv{pYURociZY|L~r-ehXi}m2Lhn|J46_FS2=y_&*)*1zW!p z|EGR@Lwf$7`VsRfhtxf^K-WLbz8+c2R*eT@ww;>$gM z|EYOD;s10!754oA|EFGK-!JfgYJ463PrbpuKj8n=tL*b0|EFGU-w&Aor}J&L_b2oJ z^!<6GeZAoS)c8sKU)=aVwbuVtvp@b%z21B!{!hKZzW+}-zI%aw-oU5f|J3+!{GVF$ z|J3+3{GXcjbMb%bjrRQq|EFI2_J_g$sn?kw$N%Z)rw!K3|BD;{r)It%{x5F)pME~w zV%zb5>aBMF7hQK|f&P7FwS9lR=bSO#%qPsM80-75-t%GVhy~-l*S!6a{XBe*H{YKZ z+<%@o-w!93aEk!vCr9c+CIP{>yE?AO0_H z{GXcr@qcmS|8&3Ej{l1r|EK+#=ZF8(`T72j|5KOR`SE}1Vw?Ae|5MBVsquaIKX3c_ zj`e@z#{a41|J3-uPkx@_+hecHvr;a-6X+M8?#fH>%2R`FnV*c-=e^xf@{r3OKNTTm0E`-t$+i zPSxG_d}WudOx?5d1@GC*OH)5>nC896{=O3br~AP?K>VNg(xqYkpL*eb|EHe2aB-Ob zH=yQG!T-&kzc9@IQ_owlAoxG^tl6`J|2yQ46N3Mn`O?$D|EbRzGa~pu_31g)ga1fAw1QuseL-sjaTR(SU} zU$^PHGVgvPJEZ=0OL?NJPF(5TcT`97KdTar|I_gYoZcb$KXw1p+NWkbTjAT8?}z`> zcKJUwo)7;QH~vp8{}=aND>wP}5vR4b&-cxV-nM0nH|PIx=hj45e|MWV{x9#t?cRgU ztDQXmt%BXhpBTI(^YaRp?eu1T-Z|yFyxETbi}%O>shMY2Pz2F z6 zzwWilF6!Sh_&=SmuwRSd|I}aN`z2LIRQ_7j7j9o(*F@PGR6=|elzPW=8i z+kXEZ|2{a=1JaZFUR3z;t#=0BhYvip^~K)ID|>h2MTIYIxFh(!ZcUn`Cd|Ir8{dZi z({>vFr^a*P|Ki5~sagLO|EFfXTju|%@pQ2Q{lMeb`}6JGv~lo%+RpXh|I}PB{?G51c|QDK+^qkr#`iJ*FK*`lsqtpVmEP)| z)3inE;}>u9&RqXDv$JhI#JdgM`Ye){P_Q8UZQ<{#M?8EpVS6CHk=Alj{i|QSG?I_M=Wr zdO#ZgXEXDH|Ep5{gy8?o&;|d;{6GAkx@OI^|BD;{r)C}?{x5Fk|HaMxKkvHL!~8#W z&Dtl1^?&2W|EZa8hyPPEUvj`TmEF8ios@0!?JXMH{J`FK`}3n0b(>UvXUoZH-)HZq zty}K)Zqcw&@PFFg(&lyI|I~OL{GYn6eg3rlb)t8@W-WsM)ArVlS_J>M`l?C68@6lO zI`}_zR@;uj|Eb%zY@5RWsac=5-o2HL_rw2bJM;GNe{tjg)LmM(4*pLq|EHG!iyQx^ z?%2V;ADaJDXLV{3=Kra4JGMwM|1WO*pPqkid;59D{GXcjZ1I0;*6+pt#f|?{cWl!( z_&+ti5C5kwY?JnX>ikx1ga1?Wc;^49@q+k2H9ipkr)EAN{!h(3KGy$LGmj7dr)E3; zFK+yw8vn=qKQ;c3`G4w;9Xp2kf89Tw9DE?_8{_}fJvx|&%0JKdzjXB2;Qw^LM_hPz z@PF!|=bjb(pL+P<-ogK=+qG&G{GXcl5B^Wh^T+?Gn{`h6KXvmiS;7D5`g6N>3iJPT zy*XVv2LGp)|5M}Z@PF#Qc?H4$squEq|MTP9{5|IXsq+iEh53K#9{JsZ|5N95>Kgo? zx~Nln{-3&6c5d*0-gr9mf9j(A?BM^@y)%4YpZw(dzFi9o5}&V4+a&!T{x|-9(zHSH z`)|$WZG->2_JEUv|I6t+IQT!c{NIo(P7eOBdtq+yf9kINn+5-;?s;mb;Q!S5W4oko zEdH=e$D{Fo>ONGAkU{GYnt*sj6-*+ZdEK|;^-eux zruSg;cvt;C!@JM9`KkMVdDR=w_{QH}sciFrYd?QE(SQBmC2xG=Z*Nae^bb9z`}Hty z4*#dGHyZyJH~vqJC&T}#<^STw|HX~}i+jiKPx<-f|8#$t4~YL$=UkK*{GU2+LP1#n zSIv5|_&+tr!~eyN|5LL+{!h*R_&+u0$N#DEari%V?s?{a&Ht%c-xvQEH~vqJuf+ew zjsH{Q`S5>g{2u;Kt@(dy`9C$s$N#DG?e)R`sd+y5KXng#KjQz?yx#afH9ipkr^dtL z|Ki5~sX0FWPtEPs40r7uo{NL$oF7@s-yt%D6I=ajZR`7l`?Z2Ng|4)7O z?5V;3sh=|ccTC+=%f^*g3BGTh{XROk{Rrq5-emraZpL)(;J`VH$)FtNo@PF#%Hh%*D zr=D*f1plXAVjhq6f7Rvt=l{ix|5M`w@qcmS|8%`e?7OG2W$0IJ#XgE?VVZ2n|X0}71v5M{!gzz9&ggQ z)ho|${%+oNCwjBK?!GD25`EaS$0xee>|+yc&n40JyO>1d|8)M%=Iii(aUXNop}zk{ z+m8R!{n=pGga3;g{}(s@PtEC3ZagpSsliApTFy`S5@0iVwaB^Z)dI zS-s!?#eHdcvG31%zRdsA<5`av{}(s@PmgE)Ui_c7%m2lV|5Gy$2LGq7u&-DApL&gX zKK!4KUt#l$@PBH282(RW&U5> z_&+uCmGFOYXB|AMvhDZ7U*`<>USOY>_`h{G9UFY$%B_2X|5KN5*_|?f;QKGJE<2&4 z_fp#*|EKebl|I}>9|EXEO z68{%B{!h*0@qg;{@k_i{rae}o@qgN%`C~ROEl<~9YTvKz`Fbziv?usKZC|v0XYhaO z(zWjf|EGR!UfTbu?|P`h=G8UIR}VPt-r)cA`u8t*A^1Oa-@NC7|5KmQ^U2`<)R&J+ zum9V!^YOv|op~OFEsCUhxfZP?hF1;&u8w!Ip(?U$=ChdynPd|mv`xowExro%=^Rtsqt-}mp$eC zuiLXX_&*(QnXUJW|5KNl&%^(zD}tw*>AlkC|Kb0%z1Tc1{!d+MpI7)lHR}W8|I|y& z-{Jq%i|y-~`G0EW2jc(Kyx;JDYCJ0bPt812{GXcb_&@bV+m8QJuQOkV|5M{%@PBH& z9R5%Dk9mjqKlK|W<-z}{A1YoQ{Ga+o`@F;dsf*3G;Q!RDFKO?8?-$o^3;s{rY5bph zj(xtK)9IiBUEiA<-%2fR{wMG0Hopr0r|oap^TYqC@j>`MHS^-|f9hpB)ARq-%WZvC z{@L3;zwm!*{5<|oy~I2o^Z(RKZ9X6VPoM9l_WI%f;>Q1}`TpJR&DsU}{zBjRLS1h@ zPj^35-RO)q5ry)N}$Z$Cfa|Fl2z{_ub5_4f6K z|I_ow@8SRA#{a1+?DG@<7xx2GZuXY{)BP{EuW$UH_GkU@UbAlZUSZquf4ZI$J3jtT zz1%!8{!d+Qf6u}Ezqs*#>auO=`G0Em$N#BU+rN)9|4&`Mc}MVn>V@|6BK}XU`G0EW z_vJitufIO@t5fcaI_>}T`s4ZVe`@)^xbc7L#rAoM|5GpA@BeiEx%PRC|5ML1PtE$j z>J>J>5C5kw+pyXG{qza%W$QNv|EKN68#aace`>rR{!iyGTeCj+KehayTK>;_)%xK7 z)Qd~g{!hKoJRts0J#Tq=@PF!s=Kb)0apV8I7cWV@(E6o<7Z0fteBVOrehpvtmjBcC zS##&7*Z%8%Yht*o2=u7Kw@a}(V$1wj-$D{FoYSt6R|HX~}Q_KIU@rU?7 z^$44HhyPPE-w*#+yMFcH|L}hJKlL!?4VwQ`Gp}&RKX&=!>7V|y+nf1y_&*(=`GEL8 zHS_QAe{tjg)I*2bdcx-a;%5GzTK-Qh|EKO@f3M8^KXor#zl8aJ-uvhO#f|?{54CxA z_`kUEe`=l&{!cy7d>;N!jlaYHsd>KlUGjyu{GYbt{qTQkj*tI~8~>-q9~OP^jlW;$ zS3mjIoB4@He)V0VulU>FyqUkZ=g058nZK9w>kr;|I{cr$UTOTF8jpAJ;Xirj4{Z|s zpRR9+9j{ZhUwk|LRE>Xl7n!%i|7m|3|EJC!+$go7`M-RBj^DcNzrE%EbUpHaapV8u z#{a1~AO0_H{GYmTK-1KXEe`PRW`3~c?8@$G{_lgf2m1E>9_AkxRQ9kAbrZk;9nvo8 zlQP#6&2N+RfSK!?()hoLeeJh?)4ndmd*T1qJUB7Udlq^Z(Rb z5B@K1{GXcja+&|9?$bEE{;!&OZTLSm{_MujD;wW-_@*0udx7~Z{GaY0&lmp}H~vqZ z)u3_ke`?mx#s9?}|9(Hy`*m%coY(kA{;xxmuP>8zCPx${cqhX!$0=4^-$yeGp|4M`ZDMLwQZ4{7npf{of{{8 zM&|J{oAqJi>uG80$Hsl^;mP@YnSJDuM<({q>?4j!`oY7GOwJR`^nV8(om^k|fMb*E zO&)Z7a=l6B1LFT)nld@~Kjs56|IcRd1^;(k&9wiEoB4n0dNof7^Z(TKYn>R@|JCuB zCy4*kcIF4-|J2O)WBuQ_?Vr6H*Gtd;({?_O@PFzi_I`h(^(4Q3n)QEme%_z>zqpzI z_tzd%(jKo-lQ92JjUTqzU*+}wJ0%O@sea*K5@<_3NVB{Q4WTX`Gt1^;Yjzty%^Dr~R3y zhyPQ{|HaMxKQ;6CnE$6{ULXEX&362sn(fU0Q}g}ms*yMP{h;xGxF<@wCpmA!JM_W<*QZA-84?$@SGYTB;Lz4495esh_3=ZTU9;M! z{-?&Jz8$}Y|I_)4I(H2IPtAJ0_&+t<@qcmS|J3+E{GS@{kN;D*Z{I#O@VLtE-@kwA z&rQ$w?d`^n4*pO3XJ2?;@PE4h15X_h{GYnEeZJ1_Ki;2D^OlW*|I_yN9a{zer^X}V z|J3q->c$=0r?S5vb_@n4fFrhea3VN^Z%~A zy=L%#cs%@H+>=jyx2*cHHG}tKejxMz;=cBxx68_>ogBPh?=hW%|5I~3{9oKQU*5a# z*v`TKX?wxAuEGDsjsH{kxBa_x*zVoe&NrgPHt#NDJEksgu+=-~?9Rde>GAS^>Vf71 z@qg+O=JW7>>Ql_;;s4ak%ftVv@p$dOS?ir^^ZW*VQsJF#KJB9S*LW9<%?|VbbpHzX z`#&}Q5dRl9{!cCc7dQSdZv3Ab|A_xnZ!U@ajXK@n$|C{!izZ|5M}B z@PBI7vt|CDI%`5v@PBH28U8PB{9oMoKXs8^5B^Wh_2K{2tPhO;^S0-U|5N9gx5NLb zd42JJapV8gcuoADn%58ir^fH$|J2N1#Q&-Bh0OnpoB4lg`9C#}$N#B$zv2JXTrd7l z&HD%c7dQS-jbFw8sqw4$KQ*r({x5F)U)=aVb)SpV{!iU+LigbR)a}gw+4@aoX0n3k zt6~5B)aE;QUpwy}^GBz9Ke}dZ@PFF>wY~2K|EFGJzt6b;?O|nu&ptMIKDzj;A>IqD zKmBb`qVa#)pZN#O|5G!ci1~l&+2;H3e`FA!`Gi)Bl7ngVUe$BjG)rm#ktan!M zM1eQ!17G}lo;UvJ@zNY`=BupS-qjn=^zFx;z41>c{nE+1%+?d`ad^i>erW$9y~dpU%Jfvu}g{Q!@_`{}(s@FK+wiMBDFPyzzth zKkZN3+DP8J_xnFx-%dLp{!jZeUl0GM-eA{<|5Nk)@qcQbKmJd>%N~#aQ@^#}|EcHL zcKn}uo*f_mr{;R`e`@CK;s4aEe|%_*Pgdyl$M=mH`k^66es$xPM0a~(gEzhp|EK#$v;MEG$sGJB^Zu&6u)??FUGaa~pT_^ijsH_G zwXa9~pN_}8!08*_@Miuc^Z&Fz>lfnx)XaOq|EZbJhW}GUri7@PFz#_WNf1pPG4i z_`kScxU#?Z=FK}(wqBt3T7Lg&{!jbQuhW3E> z2mhzOXZHNy|J3)*U2O9Z5BB3dFn_7}$6rge{ifm-!T&vV+3~?E-n_ib<{Q3Os=jIU zI=oLQ1_cjzo6S=(Kji(2`9WKcv~<9bs=)`&Fz;tS-*~^Ub6@a(+CFVp@NfS3H|+H> zALl*Gd;8etO@>4 z`wu_k0ee5R%2yBT{7kCN!cN{pvz`wA@1^pp!Hb@o|3vVA>g$KT9_Ii3yREHpYV-fj zxcH&q|I`=XJU#e7^$U03n!5k4bMy6h`9F2>T^E@LyV}pc@YZv<|9<_&cV3V>zVHt3 zeXmY6-*vb5-1%<=|EK4_dF#61|I|yj?=-LVkndk=e?QS<_ha7cZJr(ePy27!@Bh?G z&9~wI)FtNq@PBIj6Z8MnrRG`ie`>rO{!h(3Ec~CE$K(Ih``^#r_&WTbwy(4E+RljEI0ki(EdbW8y{GWP7$;#mW)C=b?3I0$0;Ifk7|J2iMeP8^ay4dEm;{SAg z%=^UusoykTi~m#e_b~WB^*sB2f&Yse|EHdB{+Zc!>Urh?v2MCwd_Ur!)#2ycv#WVC zk1y}k6TRnu@Nw{e+Mo5D@qcRO^O+wn(C0sX9{;E2=X3m@n(g>MH9jBzr`~SYhyT;@ zci7|ce`@^T)%%)zGY=U5r{~LhzW6^i-|z8%di**&KK@V5_jmlC&X2#t|EckJ_&;y+ ziugbMJizOR|5NjRt5THb&Er3ASK!S&x5f2~ym>tSPmjkV;{VhY_VdiSXZ9-4&o_9# zrTzPO;{lJ#>F2%0wvTN-!22!x`DbDELEd=0Lk}C`jn~8f>G)-KefYn)@qcQ*AL0M> z^Cdrj;s5mWD%b3UoJNQ2}eh~ks#%JRH)XW#e|HX~}Q{xBme{s({=mPIm_Wk?r zA1?F`&+ji6dvCMvXKgoK;=RSzyFX~@W!~%T>kt2@=SSaBqF!J)ObMV|EclQ_&>G$U)=aV^^*Pb|Ke^q9~L=Do<~0ruH28=pL)J|z@MtW;{E#UIl=#F`#kf2{SKbt+wp)u{#w~Dzwt)!f6qK! zBY40GS6!8ww0L1bx8^m1?;Ag)DD~~~Mc$nooe=z=wm0cqHTXZZ{GYl>{>j1rshbtn zN`1bk*pHW8P&3v4{pH?;J?p3DepKR}-@j3++UKR-MYg_Yi*YLozFbzlVDt353z^Th zauZsy~zxv1Q`z&zi{m#y?JH1Ah_)hcg%-FerqPV~D+R`~gXpELib>!;I~|3~v$U|EaS_v|I~Oy{GWQT zT|fRWZv3AbkB9$LGv5&Zr{?j@|BL&$ZD0E9!TGM+^_BOKA+1yIzw@;>^AYiXdcV*g zXMOAM$06qbCg*(T&HB6eKkeV!j)(tK_Z-wR_&+u4;o|?|#{a4Dclf`!w^#YuoB4kD zKW(S+e`@^Qf9m`*(dRV!)th;J_&@E>d_Mf2TK+HYuDAc@&zE_E`|kQrqVK%tcW=($ z?1BG!2NX;L9 zpzlAVQ@vD=tb_b`gF4hn{66@P{9kYLB=PT$dp1wc|7&#oq=Ml8%)8uo$AyJ6p1mvh zydKtnIp-p8d{mp>7bhD3_t~j;2QSEW{GYmGgF33-7qKQ-%%GXGDFSHu6Q^J^zx z&mJ~EEPlN*J>dV<|7EVno6|h$=a`=upD(jBeOso#`y;=X=@&Df5A)ID^JmUGYS%jH zAz05d-k;Q}gwM|5Il-YZTW1{k_`M^!mRx zpNsW>)y((9|E<_LHTXY#-{{tN`F4EY3B?n=@pt$?Jsy9D|5NjR$N$C6`oC)Y-y@Ch z^z$+AkNJPv&g1cax_%n}7dP|&v_D=C|EJDw-8RhsQ{w^ge`?kr#{a4DPg}>|=*Q>l z>(-lYNHqRW`^*37e$h3mU+>$QH#oKJb&390?`yqT-*&=T*Ldf(>yX-a?bY6V9^n6U zK71PfPmQm`|EckV_&;@r4joc!Ub@t;ze|@csjEva@n-$nM!P3?J|LOVl?2{k-pSoGg`oaIHdB4;-dz>GSd3_JwIMzF_OV{B4 zv_JC-ng6G5)v-hHe>#6wUT*Mz>VAc3|EFd?9{%r^hwcsjuUnqY&ocj~?op8Tf7+kN zkGtk{zhBJTWB#AEbA9+fHU19&r|y;8HTXX@J`?|^?%Jkh@PFzoTb~>Mr^e^5?=jr3 zkFS^b^PKw;cYfF8dcQe&T@u?_pF7?^)3=|PInVW&qk{iCsAZkB|FikdtpBTS*1l!% zfBT-R6Z~KE4y}U!Qx|lzKVC8ar~L;H%L@Ka-DOl(@PF!DTOSwyr^fp&c;zpNX8vFH zqqT$oW1b%VPu<_<`{DoWcV@x=F&_~B7dQTI^4wYp|EKOXx?}KvYJ4F6Pp$cXYWcso z@qcRhKXpIm37Y@&Ha~~|Q}^FL|Id3|c9{RCX8m3KpL(!u$N$BR|5Nw3?f5@6^XKq? z>Rh{j_&+uC5AlC$<}u#AYjvVu+`P&g54d8@%0$0YQtpjk{AppC_aO6!_&>cK_`p`L zl=^nM&vPZ-tZ$6})BZI6PtE@LKQ*3i$t_F$@ihKV&xgkU#f|?{VM& z$h;u_PmS-w|HX~}Q{%nxe`@x}|LK0?zwm!*w&VZe#{b2Q|5M`u@qcQ39R5#@AH)Bt zdzcr)|Ec?%A7uSsbzhr@hyPRK3-N#IoQu=`PtE$o_`kTHANPnq-+ty1?eDh}jsMgB z%=g3pshRJ0RJR9wfBaq3?E4dq|I_|m?e)h0squLDKQ;IN$r|_gTQ*6ug__Z z|2feQ-F>rn;dxzy|I_oK@qcRhKQ;6JF717_KR(;$`@P!v%0%yLa=CZE%kqQ&)8pHX zY!v*T8Li;|s*h|Q{Ga;fW%mXDr+#&9Meu*>rF-8_oxSFivW7#B58iL7&4#XsAapV8g%u~VtsqrEBzsk0GE9U>=zSR7my4)WBw9WrhvwkH0FK+yw znt6XUFKX`1{5brd?mylS|7UCL2LH!AH~gO(zc=gf2EIQ&ZEwwb-uScw+tl&K|FtQq zm1z8*&WB&a|HaMxKlM8Ea`-;FK*`lsf+D;@PF!(&%O!%Pc8qa z-eA`|@1QSM==H4lDDD5^#{a4DfQznsKhZ}%zt?+(JwN=Pj?cV7{9oMoKQ;T~|J3-t zr&m{aIJLT1plXAZu3K!|EHcadv5T5>PKFBDfmD2)MuUv{!e}DV~+>_r@sA(Cxib} zU-$Ghd%j2)u#UbOeLiE00*{hzt@M)P44 z{P;`F_dT)eDnI{%KcCJ0_g;3#`N99``M*8wuHgUF^XI-6{GWQqwzU6Kmu=n>{GWR5 z&RxO(squCAKlK{>`DtPM=koRbU9oGot+)E3_o}_`1plY~<^SUDwPTj=zt;TSS4-z6 z`hjT+y_ebfI!s>bz1-F(x38DVw(Yl^TJFvJuU^3#Z~SRR|EHc| z^P=#7>N$&+q`H><;`jeG`~0-`zxSlsi&D2e`n&fND=O^$a6p0X_na+zga1>{-~L|k ze`@Bn;{Vje=AZF@>ZSI4@qcRkkFC#Mpy$umBWu~Jm+g2r#jH7f9xvMQUJA>mUSgh_ zeYO8Ad;Rf$>e=SwnE$87zfWCX!yixM|8zV&+j|{q7wG#ZJ-cCDZ(e`=pYLzp4gaTR zecYR_ZS1|#&cF47rrxX%TyIo!@0B)Rwbzc8etr18lPX##8vm#3$M;WY*xnyc27+H|z1@|MdLugZMu+z7hYY#y8^s)XaOu|HWN;OSc03{DS{G z=8_)X@_*WnFU0?;SylI8_o0K|Gdq!Qejp3IC@qv7evte`>bl|I|y(_u>EI#{cR5-~sV}>S8VM&+#dhwga^IL_OJh|?aOSvbmsr5@qPHexbc5#_Q(IJOKm-0 z{GYnS=KJCQ)c8L9U)=qtJ?Ynv55)iJ`7-Yh|EDfqxi0v>xbc5#ydVBAZv3AbABg`` zFDxkw{!hKEIPL$`OU;|(|I|yC6$k&PUc5Bz|I~Arr2U`z^?CEs>;LY5{pQY@mtOyO zf6M=A|JUA}mHOqc3k&Av*9!CEuDtHr;Qx;5R5SR$b4Ke)bfAo4&Cd9 z`G4v*`{)0~jsH`3Dyo&r9=^PwQ|#v(&q*`5yeA_GdmI z{!iWA=Ck4d)ZJ`89R5$;!#p7VPtE*1{9oKh+_J`-^>ydoUXkdLcdzxv4>JEx&xgkU zd7Hn(|HX~}^S1r*e`>rR{!cw&d*m;EJi5+PA0&F>^B;QSGrxT4Bkz$mzYqVXTpx zsX1P&!oPXr|91BHKGE0r{lUBMz?P}ngZ}Q_XF!WE|4-+`2jc(Y#{a41|I~Oq{9oMo zKQ;T~|I`BqHV*zzJ;>${;{Vir2Q~@o|Hh5~)AQ|P>x1L})P3!E_&;@jTR#o|r|#D; z?f-N<{4oAc+vWd84Lv#dzrF)n2mhz;)wf0Pf7*Xwm)gPq>3BWbRI~p&u<|zjU*F|GXd*K54{ znlHrvX*)g(|EKQMuzv7=>fBl<2mhxos-O0Mx*ohD{;%Tw$-z_N;qZUzwvFor{}(s@ zPu;$0avt6PGyl$>U;O&8`7?9BZ$JJS#1BjV#_&L?DE zTD(1T{o>5W+dH*LKEKS) zX`b{Rxi-HkK7Q4z$@O;eb@BGh^?Cnf9wgqL>Hji2(*tI9mBas(I9_Js0r7t}^Dp?n zqmMp1_&@cLCmbLApZd6()r0?2SF2Mi_`kT#=K1j&)~O!m|7m-Z`sw+9>SosXKXnV6 zmxcfP$o`$7X4~%y8{2$O{GYZn-w*$%ZfEoR@PFE$_aFXG-Lq+{;Q!P;nzRi5ulDEn z2LIQlxy|ph^?%QtabNI$H2zQBxK+#G|FnOT)~$m7Q_KIU<^R;I=Q{3~iGDoRyT$)$ zJM-z7|EJFC&?fjlHJ*(1f7QI-S^rnf@$r9Zyc_;cUDUQi@PF!p*6o7-Q)~X8n(M*; z>3*@^F8)u=db#*N?a%x@*8hzg|EI?5;s4^s|EckJ_`kUEf9g)1ItBly&dSOP{?FSy z9sW<SC94gCw=IXl{olCpe{tjg)c8L9pBjIN|5M`+@qg-$<{j~W z>Q3ez@qcRWKmIRn{GXcpf&Yse|EK2q@qcRk+%a#i@W#90|FoUP|HXawW6Qnqa<|=A z?9Kkq+_lUbABX?b<9pitJN#eV_&+s|$N#D2|I~x*@%TTr{GXb~Zrygqa2l0Pu&X507Y@v~rOvzJF~6Q37Zj%MxbRVL zt_T08`@`|^e`=1uXXr!T_`)ChKIo0d!~bc2d>{TVZv3CFhu33l^Z$>v`;N}4O#67h zMMTCnN|D}skzPVV5;`P=Ce?=uon~y2#Q!J(n|tK=)Hw71^D|Mk}f5dWvf6XO5WctHH0n)eU>PtCkR{GXcV1OFFq{GXcF3;(C)e(`^5?svzHlM{{q z)8ps)?>y>8-_G^$e>$G$7yqZmZ{q*deg4!ls#0yD_gN!a2LESfEBL<#=d=y}Pd%;p ziQxa#3%6~Hx-1`A{LhRk!TS}y^;YnIYSvrC|EZVT=d<`f?^6G#UTL3K;s4Zy=6Udc z>J9e!&YWla7eBwNa`^m#`5^t5_4Q_66aG*8<16rgYUcCd|J3+9{GS?shyPRWw#NUd z_u9NN{GXcR@qcPQ|HA*NH(BHV)Of~;=Ks`N&3oYg)H}>4;{ViJ&0FFB)Z6U(_&@dL zkG_ohO=;%Mda=VlZ&Iw+2fua4KN}?)|EKM{ZU48-|Ec%b`S5>g=Huc2;*I}PZ)cvJ z`M-GM|I~Ow`~O7SXHDLCJp7;b#{=U3)NIH9saemL^?y76R;6UVq4`7npL+8LUj+ZB z{W%~0Pc8qa#{1#_)LV~z5&WNe`^SF`{x9D6KXs937&iG zYj5WH;s3N9-^cvFc;o-nn?L?b@PF~f|EYO>$8UWj(FI=}O!R4|?@KiPPxo8+VTu1! z7k%`Ft&hFQxAXoRaB`71^J3<{4D-Y+xhy%|EckO_&@bF`}#St*K9w2vwi-1-(P3>cKYK}W_t7eqg$ItyqVAT z_>c#@`F`{DHPgLU+dNU`|LOklB$Lman&<^r-0Z!|=4s*oKKrC<@Pf+@9tr+Wz1)09 zQN4?N|7AAs<(l))@n&8M{!ja_x6d!}f9fZ9?+gA#w-B$$vr|Yl0>& z)a#~R68xX~;L}rr|5LA7{6g@5>bDPUOe`@AE4vS*4_|)gU9jVTz1}}~Z?^eU_&+`W8@B8Y{!hJPO;PZF>ZL2! z2mhzO){bZXpZZqwN6i0I=i9umMe8bL>HgQ)dcji`SM*+G-g(HplM;>p)BgA%{GS>h zg#Xj`Upz1VFW%TV?a%i={$I^J)UHRX`Tpze{el0}@%;X6KR>ec^AX>N|BE;NPmNc* zvq}SRJlpUS8hNw5+0Tu=@oB$)(bOCNxBso?iMIK+em|TK|EK%s`0DN3`u1IRe688- z{P>+V&+xkkI(Xw5@qfBs{yc&IQ{x5ke`@^S#Espu^!o_@Z}ZX&?=9v9tIW;x#{XUM zPxt|i2sW>^Z(TR{J{UkyXV{iS^9mA`>Fb1uJ>N^hxk8j=l3)GpPKu_|LJ@@ zz6rh0_U*wpwjbe*Kga*+c;@xl{C97>r_G1=#uM87c<;k@J^Y`3UuC`{{!h*KAN*gu z@qg+K=F{TP?1|5LBnyfgSeb^gYZ`G0CWApTFi zcGLFY|J2O;yYY)TSp!B^&N|%i)@;`Qz3{!~yqW)(duXmV{;%`)dEWTH`s<(fUSa>f zC#?Tl`u8Er))hoQy*S^uFE;=8(bF$_zf|h~bU&K^r{>=WG5=4!VBxF5|LN~TC*68W zSpT=p$~wW1T{otG@P9|M>I4tiqiMaM+N1^=h+lvT3+uew9`I?G$pL($QGW?&K^>XoldVB+IJq`Syn(g>MHQVuj@y7qf8~>-q z-!cC$-uSy+d-M45e||n|{GXcne)zw5c`&0ZGZfqw#)y;`?mbgd^_v^ep2+gcducsga6b1JU;wiyzzhPY@1Js|5Nv{^@yKp z{k6Y;IKF%Pza|?0r}r1n5B@LS_&@I<_Wm;er|xU>74d)Sygc(^=Ks_K2eybd5BtFz ze~16m{ow)ee`{!d-MVXff*;?4TMYSzcZ|EXIwtsmLizTWbG+D_yD)XeJ} zctcs^_j(^!)_7Cq|K0K9gTWK>{$l;#jCBu{_`fEtg8%#1{${oi=E{pD`&Hn#rkfO}%yu2t}V+MoGg_&;4A54eBxRKLHD9Xm!%2A6e4+xB7p zpYA`cb(=8%Pu;?{pZCRWetavNr+3PKr+DKD3#*ki^Dig1yVbWdZ?I0zE#BN8>;LNh zIG*)?)vTY3|5Nk*9RH_g{ayT@8ZU_dQ!`Hu|EFgC+2>EY-mgy&ZFXIvkLz)*H=c0C zm}|W8k>jtu+MAz0mG1wuH|y&%|4+{s&oA@;)ajklg8x%@>)17VIQpF6|I{~JIWhP@_2@xE!~8!r z9`U^Lm-zEVe>D6Of4}uh?;f3T<;C7v9Xdt5rjGaK`L1j8|8zdQBmPf~SHu75{h5`~ zHTXX@>+iDuuNu#Hdd~qg8x%@v+J||uey6qiT`_S zM8n|!m=}-#Q+GSBWAJ}!=IP=8)c7_0->&=y!T-^Rn!Q*2eeVXr`{Aqbe`>Zf|4*Gg zu5<8zH4fHK_&+s%4gaUs`oC(tA^tDkpXVG-H2zQ9bIb$c|J3+E{GU40&WHa~bN~3i zc;o-nJ#0JvPtAI__&+tr7Uw!~bc2 zd{g%KYkWIh>#Nn?_&xjgq2Bnv!|$&2=KM?FSmDj}ng6Hr^LpU_;?4X&HR~fY|4*G~ z*Tes*<^R<3e`@X*|EFgCSNxxv$J^th}lYTyYBmPhKgI~k{spbFF_(S|(yzzf(=GWo>)V=Ka#s8^! z{_%hD?%n=DZ#*9UPuuZ&_&>G$U%c^uYL3VMsad}l|EHG!Q_KIU@um1bbzggb;s4Y; zU--Xx&NsquXOx%4LQ?8{61pSIKZKQ;3J@qh8g|EY7XN)P@| z-S+JI%x@^(*Zj=j`I^`~Sex(QJ!9ij%zyA+V)Ik*f7-w3=-biky2FcqTvavrJU$=m z*KwFP>lJ?Ae~9}{}*rkpL)A($N$9}|EFeN8~#ttJU9HG8NA>(H=2jT|HT{sr)EAN z{!fjE!~d!GoBzxGTP;67^YA8>tLcred!cG|Z+xBIi}yi0-acC@JD(ko|I_)Ihll@* zH~vq}{ow!9%sXWMpPKcDKmDnq_eQ%u^Z&FRZ-@U=Z~f@YF#k`zxzzu~oB4n0qEi1C zZ~UK{>o0lqha!Let?_@}c0K%`8lQ>(Q{y-BfAPlud6)XXc;o-n_&xledcy~wnXf(Q z&HB3dKW(Qk?Xt_8_ePJ!d3^Xk?^6F4Z~UKnqj{v4=De2ZgMAhi z-S^isgWp_XU*Gt@c;o-ntapn4Q*Sh%!2G{>&G&)GbQ!}5W;WNX$i}vgb{ttuk-IP1B7jN7c{GWQ}E3Ytr$oHS};50mgcka0(%vZMb zZkf{uZ{c0FQ`_MGbp6Qwy&3*bT`tS~xcNVIH)QiFYsjqsiAoxG^ z_3O6;|EIpg{0{z4{le~}cr))8_r4YUpSHht5HGl4gPQd-@qg;o_WI-h;%$Gx3p28~ z-?cVh2>++;%!9P!GvbZ^Q}ceb{k`$&_&;qgFfW1sQ{$=de`>rR{_l(8>cJo4Z}5L= z=1JlI)c7m>U%c^u>dkil_`i7L|J3VkJN{42{4xBW8vpn9*7BLUzm2=!U_P1misB=| z|7rW&#U=hvJ^hhQ=G7Ye{(bUpW4@R7pynn1PuCmWVIK1lGrhB(4F0dUV~yYeFU>3Q zf9kR0?u&ZWACalP?uO@r|9j%q8o>k3ziUeHf9hv%xgpH|)BbC29UuIku17QfPrdGr zlKFq?gHPQa{GWQoE6)Z0r^f%8XZ6R2|J!lPqu%(xE5|?KU3mDYz1N=hF1Gc7@qc>$ zm+fJz@NxTJ!(ZD_=hn{GWQQ{r-pl zQ!_6W|EJEk^@j0(>J9e&l=*-0#{a3;oA1N_#T);pUVFI2|EX6UEb)JOzSrzM5d5Ed zkW5aW5B^X6 zlFi4&|Eak@{GZ>yd2jrm`bArh82_h!)qbAf|J2Oy!vCr9k@!D-zh%8-{GYnWzMtX$ zv_HNbJE!L78~bYi)#fkpf9iGidgA}|{a^ks-uOQ?^ZoFDYW(sY(;H^#=QY1i*nH|l z#{cR5dHnc4HP^@gspbFTjsH{Q8@CEn%WoVdK7 zH(nC|r~T#s)XXcy|Ecki_&+uC0B4RI>Mj4L?ec$W))yYNeU#rXy=e6qZ}!LkX@9Pd z|5G2d-~aG``u+2OT_69a#{d28p>bLI^Bdh~@_6qp_WR#6mt5k_dcWTdxy&2?*C*rh zL^JE{}2DC_Y;l()Ar5g@rw4|>-V$C=Jz$*GR?cd zzMnjnKRwaU_nG0(XQBDQf$8^oZ!iyt|I_QmyuIgbmWP`8e)vE2TAT0p^XU(HuQm_; ze1(U-i+3If{?DH;Yy6)YkB9$LUG;n{GWRD=G|fbpL(TvKj#0bS8d&6f1moK zUq65A-e}&!S>6S9KK!5G|K?r6|Ebq(D)E16d>`xos@H8U@qh7V{-0X@uWokL;Q!VY zZVLWSy=HxJ@PF!6=KJt}@y7qDR~D4a|I_(bp9 zTYJ|_-pm7h;ii|p7rk2I|Md5lcieVcnEy8~r(W=WS6wtb_&;@rW;Me6KXr>vrw0G0 z?$Wbnl+$Nj)~+LUgYU!t{cS+LxBQ>B)A+x5GyhM``oYZqQ+LQ|8vLKSo6QH?^mb9! z_ZQX;o~OI5XZrH{#opONS_l89{d?OyylX$(#)}ojsMg6@PYWhc;o-#jsJ@`{!cCc7jOKZn)!D4zj)*S)c895pPG4s z_&@bf^K$q<^|0Zsga7j`^?&ik|EXDj82_gpVO|dZr{?~c|EIG_y^BR5WuLtu3|K9AYMC1ST{^5B1U%c^uYWyJnFW&e+H9ipkr|vtXW$=IML4!;D zU%c^u>Rj`(6Gr_b(WjpGqc`*WR$lm%H}m_(T=KIw+kdPpl&S?<*pE|F9y$JuO=JQqN|EYW0_Xqr+zF%nl zUvA+NhuM0-_&*)rt9|9*|J0pYC+Ej?X_H((Hr0Qn`Ye1~{PSeGZ^q@>{7lBf z(UWRl;f;U8|2_QGeZdQ|{q>Ws^3G~|R@Cs@vc`wu|Fl2X$N#B0AO26x`S5?aOYRSz zaDc6ciT_jMMVSAm{h3FF|5M}5p4ok!-*4aMXGMD#UGLq$W!vbt2X64@dicNipE; z(k$s8e{X%^|FxcQs!#l#$ItsS{`gX#pWpRzf zFIcU;LlCzIkQl z|HT{sr^e^u|J1D4i~oyv`os5lvwkoB@7x)W1pn92ye#YgsvFq*X~7HkcyoQ$|J8Py z^?%iM%^S1+uex5llJ$Sp&Dxw5)meDw#(G;H4*rn7p>tW|1@V8{jt9j5sacPg^?%j) zSJwYk*D)`R|5G>U&^Gu#HJ%Uur)Irj{GYmR`x5`BZqTX3|LOka|Kg4RQ{!v#e`>zI z@PBIgKehayI=f@%;Qw@e{2KmGoz}U1g#U{-{!h(3H~gQP^kQ>|MYzD_?iEw?%$6yX*%^LJ*@T#56ui^jHXW8Rt{-5^m(WPVXe`?mt z#s8_h+WNcyeROQ1ng6HrWoD-b{}*rkpSo*SX7GRNwCt?l|I}Ibc@gvf)Of%%JCE_} z^~%hOrsa+HW_{p)UOdX1?f5_4FWZ^_ryiWyBlth{pzhgW{+}9;i2qaL0jIt`#GilW z54Qh$uy@}cJ)@7ym38mly%XPm`}OOW=&^lzBzjEBJiu1nx+b>&p<43${c)$A9{k_3 z4;u&ncVd+@ga1>HXmon;f9gqnI|ToyZZf)knEyBWipIhJwK%V2{a^Z(-eGyhLL z$h;f=FW$`mQ{(CIe`@CE;s4b5xStjtD!%XXhQXuZ<6fVC&^yiM6E2y3z`HB+37^>S z-TuPP(Zvt#^X_Qt+h$GM>&^9R-m%A<>;H7qZg18Ki_VR|MRx}@qh8g|EYVA?;iZ0x|hvsyl>xf z-<~l(ExL63GVgBVxYOj0EoB477T(-m;-}T0;i@ouHOJ7*zjiVMY=a2b+YMw9rpPJ_j{}*rkpBf*B|BE;NPp=pA?(lzVeAmAQ z&h`EAfk*m0m*{1gbG(O7NQ>_8GCR@uKb?=`-+StrMF0HA(}}J$<0)@EUYn`2yygFN zKKlOhPx$pX|7HJvJkdRWe$0E2dA>S-d(=D6Jm0_m@`!iFWogloj~-6+vUeWx&a(N7 z_&;4g)7~%mKlNF5{$AVe_x;=0db)Ls?(^pT@XMMRi9Wh?x;LJ0`76^B{lN40dgBk7 z|EKHG%>Pq!e*B-B*Bk$*mj6@Z^YDM_p_lat{!cyV;>_Ux)UEA$_&;@f^L+R}HS-vm z|EKPGMX%uh)Wht07frv$9}iu9@}CpU{6FpAIj>Rhe`dOZ|7(11m*D@@_ivgL{GWQM zt&fBMQy1Fj)A+yKdDVjdW8NM9PhDuA@8JK`1@?Is{!hKZKCi<6d7D4N|Ecj4_`i7L z|I~Ot{9nBBe`?m}#s8^`-u)!P|EV_}`#ktRZ}WioKQ;6I@PF!jo40}gQ{%7jf9iq{ zKMVd(&(DUBzlffDyq#}nUfqCK+9VqPr~S8>7sLO>8~>-?_Cd+~KlRpQCG-DmCSUM> zMYbL={x9D6KlL{AgFo)7=jUU++H?d$hyPP=vGslNe`>rR>;J0p zg3SMmH~vpuVCQH3-+1Hy)U1Du|I_oa&AcQ2PtANk{GVF>PtAI~_&;^AJzo5udV_6e z{aJ+|EbrS@5BG8x7hm^|EJz)Umy5CHS;O)e`@Ca;s5mbw%d06pBfK{ z|5Iecr7D*jKs&OT3l z>YJ;*`FwLg+snO+x9 zw+;R;-uOT7o@WLB=bhOi_&@cD-P#2Ihatf;o}Aes_&;^U&S^HUaB-o!O3yyQ|9zZU zGkCzN*?GbLsXJb9CBCju-E`U$!T+g;ui6~^pL$C1{^0-AGxofLzuTaGdG9;H|EU)p zWS-w--~N()zK{RYcAEdxtVfFfQ!{@O|EIDfQ|kY8e}#LG z2LGpCzVT@Af9j`RF68lMs&ATJ6#SpMOTQ_>|EUMHd&1_?b@cs5r_T-kPxo^{))Ub; zZ}iSoPaM3!9?wAUt1g-m-E#YI@0%w+!FtNx^KQA`){DJ3^O2Udf**YL#yS z#lipS{2QiR68xWf?Hw0~`G4xev+oH0PrYtY$^1X{dk3}$|EI^d`Ox9u|I}L#<0YT) z$BTc%|7m-X`8oWbdcFO=h5u7;Fn@>t^EU5=|BE;NPhDv9tnhzo&X507PrreDH9X|EK4B zjd?)k|HT{sr{1x1Z}5NWt=o15|EFGL>ytD8PyOV=<-z}{?|c5`;Q!S3&Y2(lpZbm$ z76t#Oo;rVV@PF#-SF8*EPxn7*_4?rd)E5=+2>wq!!F&q-PyNKMH-i6D&)muT>2%*d zd;eR}(|@kyJ?FsN!T)LhS8cu;{x9BGKYc%5WAo7XfAu<>hl>Bx_ji0A^Z(TNJp7+} zzx}+%|Ec%d`w9Q2pP$Sp#s8`CsLd{G>dpL0{GX1;!{Ptb_&fZcdaM2Zfd5nD@$i2- zKaKxW44eO_K4?FGnE$6fV2=m?r{{ymhyT-d8vm!>WB)z`|EI@8N|%m2munWk6z_5=3*{qBsby!V^$!~f~}TkPi>^Z#_e zH2zP$$=2g#{-2upe)vB%o)G`1^X<0pXZSz$X8ZRb_&@DW1#B-_L&YeCJH_=cCB>|9SBAMC1STeC9LH z&#ZyE!0s3Sr(R<|5dWuMx%*)7f9fT>_6Pr`e$6~H{!fh`%>AvbndgW9)BQ4^5C5lL zwRLwi@YrL1JoEN`I{dgd^Z1_MHPd^U`MuoYC%jjb`afNN-IhJU|Hb>q=H~yJS1a*( z=KVgX^K_zF|JV07@3;Cy^M9rL;{oUWR@TcmZ;$T(`)uF7Y}2+d|4;iDl=?q){)Uag z|EX8ym(2fDuUuC$|4+@lzmu1};OAewYEAHe+P-K_iT_hCT)jH@KlQ8T{~8_lQr4W6 zXJ&O7drS5!%T`2#e=6(zMN6Vi9am*--qRq=`+M;AsloqUIif-Ee>aUA5&WOJXUn?5 z|EXJcJR|r&b=Mwsga51iLH*$WI%n4p{!fhuWd5JJV`kmp|J3a>YKQrMYWY8Po4yT$ z|5K;sHV^)Ld1eoMw9$Kztv8GR({|?D;s4aEf7|_=E#7#&2H$T@ z^oc)i^JYFE{!jNqT04zkX_Wq92{J$D8YQeqnD}oBw<7rG1IU|LJ^qHT<6% zPlo@~>mmQA#s}j6)c7|1U%c^u@y7qf8~>-qw=w@u&HA|bKQ-sa|HT{sr|y1s>)`*? zS>_?}f9iAXeE2{07@L>(=8wn99i#9s_`mq;F>%V5{(fQq;Zwiz=J`vz=WFkN zcK*6E{_34Qq*+w{!Ed~K4r>wC|JC`qKm1?3ng6FAZu0<{{}*rkpPJ+Gf9l*pEh7A% zTK+HI_&+uC0r7wF#{a1~9{(5bZzuhaH~w$tt-mH3|EK-s|Kg4RQ}@m-ng17W{GWP2 zPLtsO)H%6Lga6alJNN(5HOFPE`}J!a{GU3fN7HEg4dr}$@AUdn{?BEd+b%ipEw#^1 znU9v*__w%EqVa!Af4e{UKj!P<|Kk1Xzss6=d-%WhOCJaxuuJO}!T+i8X81of^Y`$7 zYUXR<|I~Of{NGjAKN$QU>$~Fr)XcBK|7m}E!k5?j{c%40pYAuWd7I$>;*I}P^;u6B|EK%w)vQ_Ye`?l;#s8^UPnP+A@=vM$FLgcH z-&f!ItK;;`fuf{%`8~z^Oiv^_1hs_h^*# zb*bGbWjpJ?#*a^(kJ+tx($A*O`%CqRJsT(YPrZKErb(ZhdcFVUA)6-WK{l?Ood1{V z|5E1xruP5xfGP6?n^sS*FWjK=X^H2j+UZF@SoO4|A3WWBAM^i?-}6Yx{6AYSnE8L| z<4-(3_&@bYr=1l1-+*$D1pjw()yl#DsVmuf+syyd{?!`P4gODEr&;3&|EFfXZRY>Q z8~>+nZeO4Hzj)*S)ObJqpPK#ge`N%c{gike%}0F@neq$|JSr_i{Ss%tS^lJQ?tG>{!iV;<_F^c z;*I}PGyf9*r)Hih^Z&d%mdyW)H~vrEvZMWcxA}kS)}7mi^?%jOFJt}Rc(<8(lXurn z?V=ACPf9fYPtQlUE+zB-)ahN#&)EFGcr*V`=g0fu|J0qjl=we&XIt+V|EK1B_&+uC z?C^hT*0aU`saYQu|EKQJsY~#GYWY8P+b*4h|5JD9mKOY~^Z(+F|5ImYXGdGVJJ-)gcdAg)zfp_`d#wJ47$O{fT#v zF&(1^fBL9+^ao9X=j(Y+r>OZiAA0vS54i1<54`bZ)w>-lo_bl6;Qi>oKKfqqqVF09 z?}taj|EcBw;*I}Pr`xrK{!fi3!~dxV*?c|xU%c^uYWY7k z{%^?@JAHfK3pzy8$M5hSVDk`}|EK4J=M(=IZ~UK{>*N38jsH{geB%G&jsH{Q`z~ow z?ANEW8y0yFv949CFwyuwJs!Lo{!fi(`({{v@yTyB3V)x2ui80qop%qLH-`Vy{`jri zve)=_{MI?$R(s>;?C*!Xd)fWq|8zX_{h0q3Z~UK{$NxgjWqy2j^LJCKEcNDo@qgMM zZ-@U=54HQp|HT{sr{?*>|HT{s7jOKZn)!tIKQ;G{|5NjPp8VE}et+4Qq(@&In(xi? zw|UPC-u*7^7R}lAym#MA(xM*cKJVwlht(NAFVXlvT~Gcm-uOQ?^Y!q5@xH9>v)*{V zp3R@}=6rP;JnhZAzJJwt${W9i|I_=A^>mk={G@NE@qfA=`{V!Oef{N+`QzpNVSk^S z=$7X{;*H+f{ox7E+~dvu=0g&V|I_ouyg>Y4yqW)}X1*Z)Pn~mFc2w=y6h9yHDGwaD#hdwm z_inn`8z0(zwth4IPmhP|;s4YFugH!LUU`*w+d(D%&x}{_ ze~rd;4gOC(y>NEa_oq?C^X{(^eBToL`}yzxFw&cOS@=I~-)Noy|EJz$^BVAfYSx#- z|EV|H=TZ1SwdVh+@j&=LZ~MFn|EFesGW=h>@qcR81I7QTi{AM(_&;^=yPpOBr{4MY z$HD)pcfIpT@PF!c=B4m|>H?dmhX0HA54UyjUTYo;|EKL-AOEM`^!^voKQ^@X#`n!V z)H2aIpEvj3WcSPbKfONmwU0FM=J@C4H%j!bH4VI(ABg|c@ihKVjmN|P#oPYhd%O8U z`)nrB_&@Ex+t!oC|HT{sr^fT)|KdIQ#?!p_+4h%aoRVn#pRGY0d?Q{C|EJdcKQ;3M z@qh8g|9RW-_&+rs691>h=S6+~r%3n5`A1#(v-f^G9{;E92W&h3Prc{UlJ$SpeE!P( zKehZ{yzzhPP4@iZ|Kg4RQ?Iq{_&@dP()oXCd@KG>y}`U5{!hK~osWb6Q?Ii9E8o4z zx9>7}S34Ps=CG^5**q{!hoRvBv+!8~>-qH{t){ZJ)1}wXLUUpVxY?wE0l> z`LFlO*0!FU_q?t9g8wsP7rY|#Mt-?=T#T%P8|5HzyI5YS^_1s&o zF)wy;rh4{G6YcR{>78Hd|FnJ8q_M&Osn_0qY4CsQH)h`z{GWRLYYWVC&G7q`|I_2y zTI&DQ+e+vEshQ7&|5I-?pJ!hmnR*W7vD>&@deyZc3N=Dp$nbUcm!Q*(Uv z_RD;Ky142p@8VMbr~PUCpSsYzAO26x@%TSA_k;h7H~vq(`p}W!|Kg4RQ?DuYf9h4X zJ|_N8&Aci6pPKnptpBU$zi{vV;Q!P`Hg6ICr{243Pw;>0t(&$4|EHe++6%$|spq^h zJNQ5K4G&EV{!e|=qxS{>r=E1*%;5jjH%xyl_&@c;2WAETr~AKo)(gS^smDLJB=|q| z)r$&(|5M+!v@rNT^~39T1^=ghs%Urcf9m(%4`)C=|; z3I0$0ig`l5x9j`+O8fqR|5M|Q@qg+A_Vc~<)Ah6T^F{to&7TkOe`@?R{!d+G^Cxc^ z**wt)`?U1t&l?Rpwf5%E5BNV_pMS4_|I_)HH;DgJ;{ox1YUZcn|J2O4!~dzb+xJ)e zpMGCp9v%Kq&AdANpPKKl_`i7L|J22H{=Zz^D@(tB(fB|02J>I`=bJ43`C!fNL;U&2 zd%bxs`}a}a%qz4%KY4R~`}39eW?R3$;Hx2ie%AAS=*?k?9=~G9C`KQ;3q@qc=JH2zP`dgS=Oc;o-nydLGJO~~3^sYdWx^gCBy z;l0P+U(3$i@ZZ?T`3N7_yC{qcVb>)h_W-sb&fpD;Di3x6$ZJYeM??)2^S?O)#I zy~F(8mml2iz1=(>{!h>EM%(`U#rOLCY%(v1|I_nVY>od@Gw%=or(R#`|KeS1+kO6g zGT*O4!TsL6KmY#P1KvyR?+2Lwr{kBI@5BG8*O&Ugc>nbGM|^w!4x7*Smq)$VY~2<7 zpY~s8zfa@;;*I}PuijGP|I};D57y0o((kXp{yokgI?YNn{!i~Gj>rGS`ybCfo%N4r zs|PQ)e)G<#?jz55uPfdb<=p+O_nM7cqU&#(?Y+8qb2QK90qXd|^&6u-7e1HhpN7x% zUcJ6Bsy|?!_sabB(ZKG{d*lCZYWITolGSUY`Hkm$FE;PDzxs>buh{y(|2k!X_rfL1 zqet&pkX5@;^{i)~nVe1kdfiLj1=g2c_OkcGcitQPU#ANj1^@S_%gzn{Pu;Rf$^1Wc zt4@`o1=(w}#{Q*Y@P27M>jnR(&d4h9f9mwi691<@E4#%1saX%0`G4w`*3AD?x9QU; z_&;@8Zo}aJreEDK_`gi^Qusf0*5Fpb|EZb(*J#wHtd;+4kk#(kJ=yrboO3pN%l~PA zJRkl~J#%!FZ~nR6TmDb?N8|t09FPA~k1%hD|5FdQ`@#RIxj+10yzzf(d>#HT z-uOSgKJtHR`9HP%U%c^u>K-rH9iynr}qnu|5Nk);s4@||5Gy`5&x&|Y4iS=|EKfI z|HT{srygv+5C0c${9n8;eenlBKl1`}U-^eO^8wo}{xQ*KF8j%QP+qg>*Ofmf8vm#B z_s?q){9nBBfAPlusqujLzj!nMPu<7nf8zhteRG?I`G4`o|EckP%>Prf{xS3a^n8vU z*gE(>^~ju-!T+iI+4m>>pSovyjo|;(1I&ZOKTq!ae_a1HqvcsqrE@1_SK9bsiTAU4 zb@)Fu9uEH(Z~UK{d3E@|BiB6?{2$HyKX03dh5u9I?eKqU=E>pz)c7>~-^1w-2miDf9l>%TLu3YZ~ULSPm`9x|HT{sr_O0s;{VhGnl=mmPuK5d z>xtt3bbmDK|Ejw+Z4vyRI>YYoSjO#T+gm2RSL!^u)OmQR9`66|Zr?2F)l$!oXNtey zezzMZyleTO)ZFdXn|3C+7_| zsg}HcYBMho|JP{NW5NIZ@uc#>|Ea4TUoQB+c+b4!KHs19h3`M5ta*I+Kka`;ts24q zsq5K#<4y zv}o1gdp2G$?(yL9I#j3-{NJpWGlK_gSH67kf9l%hD+d1;Z~ULS!AYkC|EF$OqgL>L z>d5Xd>-@WX|MKRuS^rnttC`E-9R5$udbs#Mb(bz( zqDQvfm}u7j)#GJ5{!iVlTemR(Psh{vKXtmTKg9gMc;o-nS>4iu|BE;NPtE$V_`i7L z|I|6%dj|if9+1%^%>Pq&A9ZfJ`B?u~ebKn_!T+gqa|QH7wx%=_c(CB8rNDC0e_MZIYMKR+-2{PE_&_w{X5Bf9e2&%7^aeR7m{$tT6T zZfX|1-W~Suab7*|WAC=-bd07f|FHPF|1=GLug#ba(bKPf;N8o-+N$S|dH1n-c88vR z-4QtZ~R}4Pv7=tz1^SQd&|2c9`DGT-d)Y>;Qw^KQR6a# z|5J|`+b#G%HS^o>e`?kX#{a4DefYn4aN z3IC^-|I_v5|I{OGfBc_%gq;unr^ff;|I~Oj{NIRAn*{%dZ^Hkn@k{gjuJu0KUT^%L zwhuF(h5u8_|EZau_s6qV`gZ31ecg10cMp4iZLh!FoA(#~Psew$^W*>2JU^pPd(B(^ zPmgD$`Lk2YE%xmr?0&!eb)h%&)bM}WKhNe7;{Vi||EJdcKQ%tB-LVCJJ{te0`@{F) z|J1ApjQ>;PCGmgi!8V@`|EKc@k7xcb-fdPs=lf?}-aY!mk~xX~?4{Y>_`Xdx?@#Av zy;uC7&L{t;mj6@B|EYt=t2E1xXTBc(PurQVS9HTnzh3sGY4-WjlWevbU(bG z@qcPwKm4DX>zy#_VehQ*>Cs0+9x7{l|Kk62ecr$Lzj)*S;*I}P<5!!tpW)}@^(fbB zx;LKhSmSAlE~tBNqMxXKPonXEIzPwPec-M{|8n=8-uS(vQ>G?*++T0^=Iagrr}NSH zKQ+$}{!h*8h5u9I`I!Hw?-%$%{9k-K{!cy7<^|&a)OlC-4E|5uVQ8~3|If@<@PB8H z?i4-y(U{^NZ>$x(-z^)S4*pL)clW;F|J1Lso-gbFmhR7dkFfr4tXsT1xOm=gHB0_| zy?x#_qA<^!^$^4Qzoq*Z*ymSa{oh!J^?ysd=xFKszolLLX36|NT_2AW*8kQ1)?xkM z(k?Xr6xRRM@wVP?SpT=Q50%dU)AUgdHTiU+T04@qcRhKQ-&Q;{VjFkBI+M zvmPb>Prb@M561tgU$xIG@qg;ax9UE=6^678{!d+QV5{iyAt(F(CtCM<{CMvQxh-w};Xezte`J4uKA`QFWu4d39^c#E zr}l4e^9*+vVnpzWr{{LE`GxDftMqLb{9n5zb%GB(HLFGNf9gMEwvPHYd$3S_T<6C4 zx59gy)GhIVow9=eQ=ghUBKSXbbmKIp*LLRP;{SAi zH2yE%_&;^N`4jw~dae0A{GWQA`BnU1yzzf(=3kn}^5%ZbS9vr4>%rWwz43(jKOJ9S zJ_!G(UbpLT@PFz>MJ4n9)YG3`8T_Am>f|-S|EWg~zCZXs^@uJd{!cx!>nxrhzg}L~ zN6ee`_P!`@fjypq-dA5ZJzDYp+1|JQX(rF7_j5M?ug|UHy=UKitv%i=z1K~-G|c~d zZ*JY-BbVPemiM1;Uo&M~)am`H-bYI3|7rh%B`*g5r~8-xQx_h3JPpt zns>whsagLS|EKp0^Y`$7>UD3t75tx?d4Bjm9nZW!^R~W!p}jxxf7%~EivLsNX)gYs zwcf1niT~62Sl@T))?(kz`o1Gx-Qvx9!2k2$4(~NKuh7;5_s0MA8Fj#W&Fe>_uhS2E zFEfAgXuUVRmzXcf3}?Ys5`|EK%ev~{Pwo}c*rF<d#^~Mb1{qNhmjK4VAdg$NYJtzLz-Vafh?kD4lYoZE= z%6Ydw_aeStyt|CNAoxG+-zxX)=!IStv-JFzzi>kIW2ck6t6Y7PeLprS{!cw~Prf{xJSejpxVzsn^=icl@6^-+UYXPrcdRZ}>ko z{%umDHr|^5r|tayfd5nT^>nTIKlPqtp9KG>-fe$A+0(OYmVUnD(>5JU%hK;N+wA-0 zlZEMtzH(uAZ@xd{|8)F%^LLf+?%~_ln}@^y>3jwD`;Yzmr7Zn^$h3aA^{9nBBf9f5!zs+|~H2zPIhu_cee`=oJ)sxQi{qdam zKb?<$cK%qupKbQ@Fs%Pu`sXFyFL&>{C`*4n+-LibS$T1y+swJtn|XlvKkZNB|I|C} z-*@2u)U4NgPjB;orGNfpecz|QyxQ-F{`QS)y|)}R&$sb<@2!Vy|3x=?v)(WMPtPxn z|5I-@uZREBc{i?{`}ybiGJa(yS%sB_ecDnj;DW~c#m(F z|I_`*|Eck#_&@bp=JT=sZ|Un%z&t;j{}*rkpPoOwAO25`2gLuWneP|Y|1CWq>-mQD ze@lC#U61*HIzNs7Qx}%{zj!nMPrYH=-r)b#g*I<{z)16drLS+k{rj7axleenGw;`L z&l6cWch?MlFW=?^UR(U6H=c0L%30nkZ2PX4pYmosVf>$tU%jQo|EZT3Zw>xWz1F-R z{!hK8XjAZi>P>~4ga1<(6%ZNP*ga1>%wq{-Mf9geR)&~El zUa)L=)cC;{vwrwPP4|BIKlRHCUkmK-V#L58s9VQ{%g?K7WfhzU;{h zw|cW)?}qW)yho0*`RbQ$_Z~5_eRTNO9ezE$U;cl0CK~^z$1{3lhv5IzBh4q`|J3*| z{GS>R*s1buB-8 zquzKn{Gaxx@qh8g|HT{sr{?)*{a-cn@0kCm=6vnHf8Vb+#MUdu|LOT)-XHV-;*J0F zw&U@C>O6Zt;Q!R!?C(SIf9j00TSRM5|IC~FJHP7ZiN^nFf6f1k_w<|p;;+Y$A!h~u zr}y8`p>3i+9{JMWFFgNU-uf!h_&@E>`o8$Tcz^ZCx8C?Z=KtyXH2zOLAg{##sdEOk zj_`l+#{cR3?2rFb%m2k2|EFeu{9n93Ui;5PGyhN5>p!q%g#Yt4ABg{pH~vqJ2gLuW z@qYL}HS+;m9{!JCub+9u)872AH~#O}tDK$B)a__k)4G8%NWt zl=JS9RwJr8tE>mNtCjdXcu4!&iN?>xKQB(5XNGUW|J``!!@>X2_&+uKiuKK?J>_&>G$pPG4c6DD2b+qr(hm}|W`AO27K)A&E#4}K2+ zr^ais{;!((eE2_gx8_ZQ|5K;g`m*>xHJ*?8fAMDipRSJ|`=aeF-pqT$|1Cf6(cl-E zXUF_MHS^x^e`o$#(eywxk`icAN)F`<<^?Iq^t#z}c zk4x=Tub1laQXhY6r_SR`T^~4g|5Q(zdVH$COkF=aw|UCzW$(Ad>zC50^AS6?NP5WB z`$>I$QvF}5@2gfL>GNvVPOcAGuV$6R{WYkaoG18u-Lh`d1GcJHGjYC_bt?z|*L(cT z;Q#7YDp~(mU8O?F`oHSRCsc^=f9gu*D+K?iu2P|5@PFzP&#WH&pSnt;Cc*!yTefZ% z{9nBBe`@CCG5=59uvL@b|I|&I)ertp-Ka_3;Q!S1YgG;YPkm~|a>4)o*5--e|IRFT zVs!F__iR*Gj><6cmCKj)3FXR1S3P={?|+8P@7h+otnrx4 z|I_*LtE~U4Zr-|nnE$74*`{Hb|EFgCUgrPB8~?ZF*C&EkWZqx>zIS-HJF7+X`1!Yc zw`gB7|4+x$_&+u44degR9Xoam{!h*PIOhMw8~>-4|5MBVsafy0$FUoHfBY2wPxs%w zOM3LDu{U`4NY4uXPsgX(JU9GbyzzhPjLfv)|J1Bki~m!zUM~JG-uOQ?^Ws?lSA9X= zkl_E+e;#vw)M?A*{{FlEf{UUi?@#dl^VqRbm7g#3&NZ(%YsdsYU%R$Vg8$R`+S|Ne z{GYm0dz=6K%q8CVI{W(!Z`L!$|7m}GAO25`C&T}#@ohD#CVTf;7bdpf(r>Ic^XXb% zc!4+9zxLG&{PpPCtyA>L#`C?q*nGRQ-#X8`Q|Gkc|MYrxP0I-WPmQO{`^RWMfB*FC z=-(%oHS6!<|8)PXzsvkTb)TM@Vg6sdng6Hm->Y}y?M?=>#}qvG__S_JRc`J4{H|HT{sr|xx5m*D^6J?&rb z6<<2DdGLPB2gLuW@qqY0H69TEr)HiV{!g85>*?bE)Xdkz|Eck9%>Pplv-2_kPmR~Z z|HT{sr^esm|J2M2#Q&+;j{j5R?eKryJ zZ_R>#fv@g{!e|jc}V=9df-K! zqSv}^@*ZUK&StdR=q>-J{qxM%G5=4EZ^Qqo@oinkuJ^}-|2tz$L89@0divqs=nsU`oUWsS>pTmyEHrMP;rT$|7`PB_&;55nB71APmRah`qQi4 zc)huQd&Qf1e3QR=Ing6NeaRaii2u|1X#AfVZ*}mT`F?-&l_Os8=6WX#c|OrM7tizK zncp`&e{Q1je>#6p^LF?@buXLWhyPRO*!scvzj#0U%ro9YCuBu8&V1T?h|QlH`p{F} zc(PX0XL;kzD%|;`H|z6$a?2Cm>6hAi)#m?nJ^8wVt5pYeY>AC3Q0ce2L+ zsquRFKQ;3R@qh8Yy3*Z=#{cPl!g|Bz|Ge$|_&+sYZ}>ko`{V!OjsH{2|EcBw)cC)D zym*7}&%8hUpSCj(5dWv{dqs)=Q?nj${d@o9kEdg9gXrkZS9n(***O~7bxiS%U(^m> z@7AK{qN#&Mc`vlTuU~ZW2=8_FdC-x`XM6Mc^15$q-rt{Uhre%U{>(+?&Ht4)pHH1! z+x%Z?v;XafbN%?0<_%u`a)9?*`#kN9|MW}rZ&mtwuQM+g*8jbzPVkC+-WJyXEp0qu zSpT=Q3-N-i{~K%kpPKa+!}`Ca+l$QuhV_4SzEc0E{nsBe&&T?|+TZ4};s4?t*8eTt zj_(TV|CTnsi}`=rf8%?f2mcpu{9nBBe`@9j;{VL>1;4rDgA)Iz-f8pt@PBIgzj)jK z`*!(1ZD)QR{!h(%w)nqzGyhL5{}*rkpBf*B|5Gzh@A(Sm|4N^a!{+}6)-wNB+OM1c zJ2d+w-ybjd+tP~Od(6)@+fuO5u{V0}G!KaX z)BV%GhzQ z|EHG!Q?s6Uqaly`@$2mK`N=mv?7hZ5561s#|9tyA82_hc9w7ctonNwEoA+Xy2ZI08 z_9wUP4*pMlUw%C7MUt~{`FH0b8`iT-U<3-2m;7?DHjV#N;{ox1>WX=-ga1>XZ0E=SF%t^^cam+#|EW*RX>aoi7kO70 zVDmG2%`R)3=P_}^1Kv?aO?+M9U32S|%oFU^F8IIEHR_jmz>E&~utM(v=LP?#t~qfk zerJO^YtAx!-UglTf(-{azxPX9>0j1s`)hmOv_J1fX0A%EkMFa2i0OJf_`U^K+?=6a zZa&K%ulGuumxlk-@df7d@PF~H_+h#?ey?-+a}$mK)BWT3@PBIj9{x{VXnxPUmmg2t z-_!~+5A8JpSCZ*wZ#9a-`})Q6ga6a^ z_xEq(_44hT4wm>oZQt_x8^QmnHUCeo`G0!9FkcV<7jNeOshNkmf5I!?%uB=nY5Q`U zPlf+eMuPCV`3e*7udO^ilOj#rA-_bz|#*l6(33f|F(F~R@o_-NG7;Q!PoPn;0^pZfHxuaBOsahf0B zY})<7|7rV$_st6aPkrs|SA+jkUp9YP@PFzXR}@F%##PJG_pf^jcSWqFtDdoGU+{nG zXLr02{GYzxzj)C6vi+=37alJ0f9myz-UcG5=4^?-%$#HGU2Mr)K@&pNDtO($91D$N#DEYWP3>K11XG;*I}P^YxK6 zE6Y3IzF*`2w4JXn`}0YbeqW>Uf8O@>g#U{-{!fip!~d!AjQBq_-!JfgYSu5t|LOYt z{)PWj^L*j|;*I}P^L(8A+-Pr}zmM)aC((b~d#+!P-`D!CJ3rC*Kiv<0GOYhw`uplu zdw%eL`t#;a`+0@`Q|~h0j{j3{H}ALQkj(=u{qrN|t6p%q_jWt}>KCr`-ey1V@P9g< z-}mr;x*vX?;{VjFw~POaH~vqp`G0EW3*!IOo9*Z6(^uV^=x;{f=3Q+5uXpb|68*Oh zQ~mz%g6}rFGtt{?-&NK&A9mo)=Ko5cKi2!j|EcBw;vLriE#1GszW;{xe@k2bPy4Uh zwLfZiaE4!RjeUQ{|LOT#ySK#u#T);p&bRIF&wtQ6oZsgE>HI~d{!d+K*Tes*i+0-j zyf*(Y-eLXU()-RvEXev|Zmp~tXHL%Md^Kvnwr<)vI>!f9h_%n}+p&)m?ft3hV!>+xDy<*8f$v>(wC4|5LZ`RVVmAwftY* zJDLXn*Rfy8{6BTNtzU}&Q+FTSH26PtwymFv|I00JGiYu8AHE9zrygM54*#ddXW{?U zdFJ!*f8MrUFaA%>dcXKTU61*H_&+rs@VVo6dyg94G59|{zL95l2>wrv=fnTS8~>;C z;p6as@y7q@^I4{IGg_}BNm<^Oa&`9C$=@qcQz;J|Z|EFet z7xVwr@_%Z47XD8y{}*rkpYDh4_&@bP^FH`Lb)Uv{ga1>rek<$$s_}mKKQ-I&fAQXW z`pw?*f4U$1U)M^v`u#HRZpM#g&3d=*yg9|Ur+T;4PF+7X)#J5nlJt0~zAn}CwQg7^ z@p`9vvsBObd!6e2Qaknd)cZ+&JgFWq^?a#bF4gy?cIxw)Ve2=?-|wm3FSS$W{iSy5 zddrTV|>)syr4YSl`5;Cc;`UN5zq)~lbmUTU{( zR5!6b)&DiFS0nhpi`zUI{2!i>^?$u9pBCo-scW5DF|7aF>cS_&`oHxmo)p&qRo5^N zx9z>@8`bQ8!4+lQyk^ztr=O?!_NYzM=)rr+x?IOrQR7Nw9kp*970$c2Z2v}Q2LGq~ zX;|ft(O=i!Qn7}_&;?UYu5i&cRA^#;Q!S1E1eqrpSo3@>S6xh z8~bb~`K0f%&oqzvPs40h#}&#t-8E)bfA2|FpEU;Q!*y{6Fo_JV5-Pnt6cuKXv!+ z-Gl#&H~vpOvP(wrf9g?PyNC6E)kB923;s`i#pPE9|EHdG&e-7p^!^!P$K(Ih_&EHZ z8jpzo)A4<}m(2fD_qNX;@PF#e^e(~wsquLDKehZ{yzzf(j>rG0v%8zuGXJL@ZO;$> zPdzFlBf|fwnU9D6Q}@kCi{88GeDBU#<~z*)>Gh%Uf9fz_(boS}Gmml3yJP%#JRSbe z&u^X%|EC^c9uNPg&a-)e_&@ci9({uUQxD51ng6Hec;^49nLo(M>q@u1BA zQ|FjhWd5HT4~qX&_s_^oeE;O}#J|7y?v=7WaR1!I_6u^8+s_-&JF&e-9zM(b-x<>2H_{^Jsf6`~u$Hm9jZ56!V$dMg`|5JCmpi}UF>W=4kj1E=!pm^yEErai4 z{@>#NzMp9PpSI)O@PF~f|EXC|7ylP;{GS@Hh5w5;{!h(%srWzj0GqFe|5G#H5C5m; zdiXyz_lN(BclCD;6o2_^i{SHyo}U)|X%D)>L0 zZ_v12(S_@G`}P6nWd{GJ^A8!@KKMWNuyG~p|LS=8zj)*S)XW#e|EcBw)PpbT9Q-ZMI_p!ZRy=C6H7iI+ir|mTU zPtEhw=8PrY_{XvLFZT0uf4|(bDA6-qAL9SwjsJ@`^Z(+F|I_2`XRiH6}2YJ4C5FW&e+b!(dki2qYF z-w^+&X1*W(PtCkc{GXcbxu@La&HTP574GyNW!v$8`ub&FC;m^(^Mn73H~vq}`-k~| z>H!ln!u&tA{9nBBf9ie{dPb|ByV~!k|K+`+D<7NajSt2D>G8DfS10&Cbd|4|YwhzV{GYb3K5X-n z%>SwJH~2sGT3hdGO~+hs{KMFR1H3obyg&S3?xDKDBd)S}8Tdc-QafMMR=vGf+5W?N z_ViwD-Y=~Gn^!ORKs+G+Z(eCLuLJ+5eyP;|sb4W~h5u8pG>R;~KM2ktlTx3JECiuCyKi@opsrAW^|9`NZ!KY6dW z{`QT(Cz|=CydUei{Bx*PCPWL0JD+ee3hD1plX=^5|2+|Ec?oxiI)Yb;lut zg8x&u$sG{tVjHSZ?Bru3SZ}4uWyIo|5}{dF!;Yp zX-$IvQ%70-g8%dGKLo$CLEZnt8-xEl@@RwL2_IXyG5A0AoT5F!|EXWub=3ZR7e%_i z`Q``kf9eJH{>A^Pmzi(D|EWuS;J>{2`DXL9x@-Gd^D+28U2nbl8T_9bFK9l|yU5lL z#{cQ@?698?HXqKnZ?)s`e>#4P9gqK07unZ?c`WaIn;&Gp%6o(P1M^be%qud#=#Bp~ z&y=b2t=V=U%>UE6#M%r{fpgJ~{Y5^}NY91plXAbH{|>|I{m| zTw?E^$(ia^cU}_a|Eb@4X-4pW>P^dDHqSM~uYYXcR_0lHZ`yw_%>UE=JKkVk;uC&; z=HW5_PurRI$NWD%-|~O)#{a3A&xik0uebSJ_&@bBn-_@xQ{z+de`?l$#{a4F&GX^^ z;{8dx;!J=4+V{&Dm9}^@uMGdE{aK$E|EFGM>-RGMPrcf<4?*G`2pLW^hQInOQdtW{vH~2s8f9i-q!T+hNjUD~}uy!BNRh4Pm z$2TG(iXcUhA}w^103nTpoPBWSdl6Ss31}VsVX47q<4Dnh=3LAIF2*w zsH2X~%y(b+$#v)1=l#|<>s{-6*P8YEUwfau_u1zpB%B}j(N&YY|Mk6mlVEcJiv zDo;MG{*N8~$m8n&*e&m#p#G2DeZ*br|JYG|2CDyKH^~^~y*&Ar0AIgBGhSBz$G%Uz zAp9SDUcnKpA0OcN^Hn9M)&H?K9J!?a&-%2q{Mmv3HE2IId6Rs96OV2Ue>&}#Fl%_g z!C$tp&K2JV|HtDMmCgTS!^>g*AA4V!|6{|qJw3m@9S<#D-Woow*#z-_W!Hzt!~e12 z+rIrQHo%`Bu>Q6D{2$=YN0@Ie|31hX^9bSpxIg_L8~#sz|0v&I8vc*R+be&b$nP%! z{yu}2-*0@a>;IPh{J&2guj~JoHP+YF^?$item>Imf6E%{A;bUidg%Yy@O|)qY|K-H z|6?DJ?;r4gY}`NiKeyrk_CwIvG>`+(yUs;#P_DU7R|2h4^ zH;-GNkokbS-<@K8T)f|$lBcW>NRN8w8DB>&mU)0>$19cJcdvg=<^l5f^5<)_)zj>H zkI8!6Mf;~)A3gc52mif3&XuTef}A z$+PPJcs?}zA3IY#Am;zM4gbf+d_ed=cIJ`O^84M()&=7IcE2PZuhebAdLR;d5u z-`_2p^^`XotuMMqO#G2gIo-+61yH@x%k1#8R?g#Y8~gNFZOj~X2Gf9w(B z)!_fwxPJIQx8eWTSbrD(&+P-LAK3GOf7_h)p*7|+E*$ugHSWjbLqGQQ$Pu4dkCFNJ zDPyksy2ZFpt#SWuyyr7(+`k_ter}E9zxTiwzJ~wf{l<3qKQ^8({2v?J;s4m!4*$pZ zAD$oP|G7Q-{co(XKl~pbkK@7ru}6r%g#Tj?m-jFH9~oD&ZYpf64r{b^H{rk1_9=h%~Yk0jSRsQMg{HniO zC-iTj{*Tv(hW}$@{$F^Vf7|}O(^`82>;1<%HLaDGSj|i3{Y9TySl+lk_&;vXkna!h zf9!6uemMLeyGx%I>i^gSqW$x^(mML*d$kYu&nN5DA>8-*aYAGVUw4j>^}@yfb-8Y_ z`oF>LBGmt}Gh}`p{2v?h>frwh_byidhxKi-{x2Jz3iJQi@O-|HLBs#C(<9rc|6`}NX|Dc{P5;ME2@6yI=QjMG+wgyGWBwnn z2akvUV|QrQT>T%rqs%XZ|6}9)t_OfWbo;;gzt&-X&llsNK$Miit?b_20ivO&a=+ z-?5S36Vm_9{^v6Fe`xqWc6hV8>i^iSWnSRYy)TxYY`skVAN*ZJdU@BcT3P)cx7Vsv zS^XcoMcsPp|Je1L)>8k+Zq}xO`agEVwhh$(v2SivUHu=gr{+yn)cQF!J|O%b zyQ26)_&>M5sXpD#kNppJo@QP7x|_Y6!OvUQxVgT!_0;qBc&v8}|Hu2$JTmD2*tbQ8 z>-xVuUz51@>i^j7qJ!)Ivg!ZW(Xk!X|FN-tF#Mmj_&}`x%Z`eQQvb(>AB6v7!~0?W z-w&%_SHIZ3bFBJ5HrAts|8w_;|6^mmAp9RYT0GWWk4(0X6%Pjg$L&4D>tX&Mdr;55 z>i^hx3?Hffk3DY0Xs_oxlk9$uA3RL`AMa;UczgAKY|K;qGIpXJzmxbm_&**mDZaDL z|8pDukB#+VG5?Q^`F-$zY^>Ld`G0J9Klnel;s4ly#5nbT?7`yY;Q!o)|6{}N!T+%_ zj}QKjjd_aje|&ucDT(U;*nJZ_dwkk zUR}GX|6}8NG5?Q^^?Tv}+=l;S!;fP9UpD+G{2v?M5&q9@_xm+`B~N@&vTkdH&iCuqTjqH@@VRxO{Co`mcOoJ}{a>%!@%mmZ`DJIg z`o2V&PxsSJpI9e|mxKS~_MT&+)c>)&kLuvT|FQdw>ZtyY-FHkUo&U$~CB6{;kB#+q z;s4l4cgCpyV+Y2?ivM`GBGo(gW7;e`6Nz_ciAK@%dpp{2v>>?QhSO+WzR{Q%bDq|F}OI z{*Tv-d1&x|Y|Kl8|6}X^XY)$N&Tprl58dEIt~I<{&Y>J@_%`@I?w=vYhyP=z-5IO? zkB#-6;s4x*|6}9+!T-HjwVnDuH2fdCtN2pP|8pDu&sw}7{GZ$Ke>^@s82leQNv;?E zkB#RC|HsDjJNEb{Ys_DR|KoOeNccZCydnIb+wgyE_$~N9cAt9!>i^jEe{RG7@%4eP zga30I{*U`(JNzFT^Z%+wzhRBzZ;V`Nohs`E!~gMk11H9-|6>ohH%|Q@8^?$La~uB8 z?cUXv*zvLdXV<@G4L>-w;$mOJ|M7a^A>senxZm)9Y}{Y?Keyrk*m!*#f4;yPuW!Le z^R4mzA98t~HQxWeqEZV|I4~~S^Xb7S3VzmI5ne$`@{dOxGT*%S3X~X|KtAf zfbf6p-Qp?W|Jd+;@PADTnyCNFlh5nm|Jaxx0{_R(y!eUwKX%UL&(!~kfm8oic=>8@ z{ok_2yuh=w67BKZWq#T}S9JDui(PTndp`I={U48?_0d<}mW)nzz4@|z@Vy?dbVBX1B(CS@zC&pY|PVx|8pDukBxbL zt7cTU=YLlAhyUaK#QZz>KlVxSa19Ptu|6X{u;=@gtI1h z`kCVY%I+U}^Y5NLKlHc5|5eQGhp+xwKF|BLnCCwve)5BFezGo+>x2K}{+Nf@<6nQZ z#`?zaf82gl?!T`8TXufT=bLr(Q#&5kE0*LHS?*gpz#5=+NaesWj!TdkB z;s4m#;tSya*w`Qbj}7kx|Hs}b-f!4_Q>`Xd!hP27zcQVQ8Qmv|Hp3L zZ>0J^_6-AissCeNpWZ|LAG_wj6!m}XYH3~6|FP?&cU1q!uHC=A`ad@2{mFk9voQ}4 z{*PU+e_Qo`>^kE8;Q!e4e{A|cHvJ#_hV)2zewT~bRb@RT_&==q2>*AZ{Czq6ANxA_ z`}H$Dw)nck@s-v!`bWrm#0z{4|2Mc&n0mo_eIwxGidxMIQ@?j}SNVKT=KuZSH4n}M zOo~$fXWgQ{`akO)W7Yrh@#$;w;Oh$6i}Lru`xLO>lF#4qe?0##`8*u{kG<#gdG&v6 ztX~TM$A&+Z{hhv|{*T+?T@y1By0G`lpHB~u9$^h10sqJA!F(<8WY+M2GC$GwFFyM| ze5G~KnJc)S@|Hh;Wj>>IfxO=z9(~1{{?E===Kt8m$1kY=V;3Ab3!jw4-kyI>=l}73 zzq&f;|JVzr2K^uVp5Y7C|FP4%F4OscZe#sl_OPTS>i>AYkzHR`|Hr;_#0>R+Z2CVw z9{z9osd09_@P8+kO|srS{a*24k67=RIv)4mde;k>_cq=7%-b)?{g`dNch_e1e?0$3 zrw*(CW0#ybDPC)l?SJsxdGT4VS!c;Sz_^Rct@AEkQvYXi?{VWq3Dy z{nGgf4d3{^wfEdK@85HOD(|V&@%3BY(_ixX_WPr}XD{-euHyyx z{439#1u2KfED!TNmlf9w}>kEs7+ zza$-WgaLj9sfMoBJ)J?-|TJTL*f6}^nYypdEDwkE8C71-)@chZSa3QALgHK zSQTO0F;5QukH^D&IQT!d&JPs-=XTwHL#?N~zuikErd4uhm zjqEcy(->>`Mfg8HKlnZPKQ{fJ+Yfv_KEU4xu^s-;ZTLSnjtBq8 z#yr1+^B%CqeE9~CK4hIKf4)94@?mRuLHIwOAKj?k*3ezBRtTFHc$EYxqB2FSf(~v2%_E z{h!HpZhWIZSN zKX&h79lg{IhpaL0?~zT1eZ7415o`Frryo6L*N=w(i;yYJw3>i^jAVDNu# z!~gOAV|`rsKlXqj5$gZg{bhb3{GZ$Ke{A?b_&>Md|JXz2{$T!}+wgyE%#VZra~uAT zjrn)*e{8Hj4FAXH1D^-~$A-^?|6{|)!T+&wKj8n^0|&PE3UfcP`-{F>aMc?7!~b!A zH2k02@PBSUb>s_sJUrx@<6l~1edU9vzOu&ozB&6RYp(yx_b;v={?BdrKQ?^ejF0}} z>vyhxYt8w8yuLK~_jNyh^*7tzFQbiD@0;&@4gbge;oa`}{s-GWAfv7NKc1id&u#cW zx8eWT@P_bz>~!&X@PBT@|G5qS=QjKwyT5!re_H(y>wfa}d|j=7S@-A{rv8un_m+8| z@PBOjKeyrk*tkCUKQ{fJwahDo|6}*<*L}|yx}P`0D`EZL zbw^)Q?*~5z|HsDqrhD6mT4;wpK6L(I==FupBMhAn*r{2_Ji3-meDCK_4;bnXJGb_G%h36I ziSmAOUyo4V7rI_>Xovbg%)fMx7dj6x)c=KEZ>aYR?S{Aby>HX{e$N@YesAlB{_hV> zn)vTu+tL9|5`O`sQ!}zih`agEf8>@POZF5TF8ZFoLw5wIV-kXx(bd^f#|G0lOY0Up)-*mmK zzbo_q*f&(F;0=x_@9Ni9RR72AH7j4I{*PU`Mm6<+?5cHYssH2iyY8l{>i^hY#i0LV z-zeU%{{ESEe{QHy!K;-~-q*_$=w(~YrE$?>X@!)o-#Ny6V&nt%_y!M5^6q*3 ze(RC9-|h{4A;G0$+pqEXge0-e1sn@3uw1-hvJSoMEwJb(Bin**-};&z^K^Jm05w^tbOX@PV6- z^|MY%^7}u`S9Je8hzlh7x^qghulocNeI4ovvEDEI-`7R$)&KSE8L$42-7&qD2miMu zslEEYz$o!};{Q@gBGvz4{vZ6G+wgzvgfjof?mW7q`ad?;|8*Pl|Ey)6;N3T0E_tqY zqxpx?R(ak=Li4C{rioMQ~$?K9U0@n|FL7l6VCa|IqO(i4|v>{ zXRYD?x_olR*YJOQJdTg~e{38d{*T>hY?AsvcI>zm^?z)vXN>uOY@9Da*8gSqzoV1- zKeyrk*z|vF`ad@2AHx5!;eFu$*zkVw^Y-~#K3}(n$Akal{^+OwQe4t%X@q&b+Fup< z8vc*_t3Udnz_urgKle{9SPg#TmXcrRAnY7MXTMddBN zhX3RF;mzRx+=l;S2gb*#|6^l4Tlhcr0P$V$e{RG7vFZQV^ncbeuMPA6*zkvIQ`cH! z-dsYDHP#&_Ch7b??oa>cHvAtO>%qeRv9aE3*ETDx;qx&6kM9>W=Krw+GXJe+y=AsP zdV8&<);K@>ACFJ}$Hw{L|Jd+;@PBT@|FHvi1=s&&V|`%wKQ`X~@PBN)pW*-5c)!E{ zxefp4HvAtOeh>c7ZTLU8;s4k;Kl~pX^E=`H*lBl0d+>j3%>Qe*eTJ_OZ<=n6^TYq~ ze&hWN|HsDjga30I{*R6O^Zw~4t$WG(&G3KR4*z%UwU62P&i zz0YDEu&)>RzvbcgS+|#ef4Tm|?Imd&nyUA!H!M#5AN$$76<)!Hp(SrNZ>HYw?E{C^ z|FJXAU-Wu)7-)~*DW5;V|MBtLh!`K@N^0nu3hH#ICwecw*;6j=Y4y<0p5=KrxvF9rP{d++5>)&KE$nc}11 z|JZmw!kGsG@%UI@I4maII$w?t z|HtbqkoAG#|Jd+;@PBT@|B3li{|Da(|L3-R_G9}W5U&XT$H$}L|JZxwd_O(Wzl_{BF~U~NTf%qu+9@EUtO)(8GB%JX&9;y;Rc zeEL83(a-*({*R6IlsnY@!S+Yb?*3P6Jl`vm|7?xQzjbJ_eq_O`P5f9&N2d)5E3pUKKs z|Hn>#`g!$#Fb(j3L+^h`{U1BFe}?)$cC(D0>i^hH%lsd^&XA!0W7o(?RR70rEb|Mn z{x7?c_&d!1V>giXcf~eX-zNLR|8aXvzo7qPcS>!o{*MhGi1~l)TV*~V=Kry4$>#}} z|Hr;XK7WD#V^=Eke^}#D=l@B=|FPi#;s4n1g7AOr+A^OI{?BdrzgGWfuKurPS|og& zHN2qsIqO?`cEb9)MbA9ZLVe&hQBC0a3fUD}V*i3d9`BCX3*h&xCvM!K{*U|5J90*T z-}5}~zx6o0->(Vm9rAfT=KrztPn^f`tuaqX&Y#HR!MkAnUv{p1y}3tXOYUzM-aoY5e{1Y7KGV8bj=v@AvUR>3U%ZqZ zFGu{NJYVag6Bpr`l6by?V;9u_@%ij1x(IKS#C~;cp3eU}^HU4;nR903d18@l`yC@+ z6`$75y06Uhdu45>B<|n8`wE@^#~u?1`ad53F4>Oxf9&zM2mK#=>LV-RMQ!`WnL+=@ z?dzU@x=`L< zzkjvS*Wy8~u|99_Ejz5S|KAquvCb3Ev-Cmne`UwR{55$$TW8AoYp*Fz;`?jo8SyI5 z?X$-EkTNgd8uO*({brpl^Zhb!J!QSM^oTd|m$TMuiVu0$y!Wp4{qq;A|Ks&Mc=rUa zPT(WEp593*UUB13t-axcyzv#jw66R3Wc7c1y!XN^^?%kc%~$_tJ#UfvKkEgH@&32t zc`q(e|7Y9hFH`?#J#UHnKkFA3ssCf&Fnh80v4-mfh6lDFOD>sqU;TMvHnS?^CT*RW0)dzY90d@bvA@sIF-JbyxRz?=7%Isv|( z-pISv|FP>#dr|!#`~DU0c#$a$1N?r!ApfX`wQ|{8N>8Z&W9OX;&i`ZM`w9M=4d0CU ze{A|cHoPkQAA7IN4}|~Y^&F7(g5m$To&L{l_&+x0!(slP+wgz<^ZbZxhyQaM{*OOD z!4qQsANz>Rw}byaojn^CgkB#-{;s4n1dzk;n#-E??fBgMvpBx|l&u#cWcB#ypg#U9J z{*Mhm3jfE(zb}z_`2qfZiusN6W=Q3arvS2Ra)l%_|GR%cQ}us4_5}SO`>o79>i^iU zzq3jGAOAjf#m4pO|Jb7@-mU(RJzjj@+sQcr_K3Lp>i^i$fqLryrY{RG^M8%h|FNTb zHc|h_?$oQPm(sl;5K%W=eIMri-P5bkI;wjk5B`ta>-KD*{*T=twXyoYi4V3@|Cb{3 z1mXYKJ^Qs#|HsCBFZe%pclrGU{*Mj+1pmiQ7mtPce{6U__&+xNAA8u4j_Uu|LuLJ7 z_&+xMUGdhV*8RlieZKveHRcZx6*7t?~P0UJ|O&`+wgyE93TGAZTLSnJRkfY-ydlBKQ{a!{2%v6!~e0dKm4ED@PB+f zt{47~-Cy26@PBOhNccauG5?QE|K~RR9~9i zOZ9*39^zl&|LpmQe}n(ycKSayJRj!&xefp4HvAtOUoY@~>;Yx|&u#cWcA8ut{2x0* zt`Gi?Jy4zx{2x1A{{9;NkB#|(GaCHMzFyF>zK1paANS|{Keyrk+{XMr_V9k;>i^hj zUH$X9`o}i)eLmbby0Ne0BK-a+wBeiJ|0*t6s{Rk23I5NzMQinc?AWlDI{%N|uDQ&! z6aUAKXxU2r9~&MnY5fDXy;qwy>i;VAU8Wu|tzEeKKX%{NZPfpek2j}2c1|HsDq z!SH|VsMalX{vXc|e+K`@hOhf$!QkUj_bYr{o~1}a+b*FiC-qe|D8Ddgf+Iq z|8al#G59}rg51AW7oN7p{6hFYUSALKj_`l%(0O#xZT<8ALVa3XOTS+W^<$x(+|2)e z2{iS;Uqa{cg?hWt4n2P8^@Vom^9%Kj|E)uh7t`GTd|Eg4d$jP7^^ila|Gz!oP``-R z-}M@y^BFtIJWO|cOdJ2azfcbt7qZ@O==nmscJ11}Ai zrt1IL4Q{LBRci^g`UK{j(e0-H_Dysiu!{fpKS&R3B z|6^ZY@mlqN>}pkRQ2)oSTD7YBKQ`_^=Kmd7yfWw=Z>pjGk6qupR_Fh*F&_~Ak6pFQ z|FPwA)&IE-|M%3SH+=rjZTLU#k9mUdf9#5KeE2^$JRtm^+wgzvYh*j-|FN%=d5c*8 zmwio*THdvfPc4m1S*2dDw#+YmY{7HZP1{F!U%vUQuZI>qV~zQChtEB29WEXZ{*TAQ zdi3yre11vd1L6PJu^oc`kDU~ksQ!1MItBe7pAY_gga2c< zXw}49+VUam5u=89vr`_lzUQ8?>i@X^-FJ^x|Hqy%I9>f8J2_nb{1pGkhDVOxKhe5l zcuVzv+>Uv?@PE91`aief|J;WEV`JVQ=Kr}3|HsC9%9#Jhh9AWIKQ`tI!vC?86B0f6 zKQ`vu!T+)0&+e%;#-0y)NW^Gs?BBEZC~Npd_&+`#4gbf+{65V8a~tdbvf=UI|Jd+) z@PBMvFXsQTu|NDD8$Phwup!nsAN(J;|Hp>cga2cvi8qA*V`E+){2x1BJR#QqWp@@I zhWUSN%%?lw@|ax@`oX40t>O1D|Bw5l;s4n1W|;rShTp;bKX$)6yQu$TWBpqAKX%3) zUDW@v)5autJ^oQ@=f~qe`M$(j*TWV6$NLRW2>-{%{IH!@3$5YX`ilSKcFeDX|6>mk ze+2)>9xT@n|Hr2PbNk;3*(Hq|w^y$R-zV!kSof9tE&u-0y3g2nuX@BDYk1R1t#?~@ zxg%QrACHH5lJI|Q%!kDMKXx~n#|HmrE!PkK$Hx7K|6^m`8~mT!@PB+h@M7?PZo~hv z@p#Pta~uATjr(2k+qdla=&^r#(;8kZ@3ZyR@LIJ#US~ZJzU#_bU&H_L_;KT7)&H^M z?}=0Y$Hwc6`G0J@zVLr;!~e1A|J?pC>~-4?ulHo5<-Ughx8eWT@SyO2YIjrE}6|JeN|1^pktUg-bW^ncA?3RC}AYiNx6KlYRPD|G%J zd#(7tMs)|5uy>UCKQ`9ag#Tk>eNFg3HvJzvTRso^c1fyj-zA^N)ZWqCdZ&CI1ONAH z)#mCCv3>V5J$#M%e!X%!-Gk_zUGGnJ08|A-FAIv z>mBlW*o%u|?Rs)Q`pnzCIoj9n?~k(16K{3xhaIeQ#rsA49BIw@f4n|4{2#mUgHOHw z{n}a=iO-rcuC+CM-ufq7`g%>Z7A5jO^^XTW5ib}PW_|GLmpcEC+u_CF|J;WEWA88X ze{RG7u`wU;r`C1t{OCr>w^$z)zX$)v=W|Sa9Q+^qjBJPh17Ck(jr&zv_fu=kPlW&D`O)o~zHfa{UXST%?^$F1 zAN(Kpr~hLgm-&;=pFeKfkBD!*@bAOcnCFM}fBAaum-j2y|7918k6l%#$ht_@&xZdK zW2(M%pUlgI|8pDukB#--;Q!dA;%VXkc>E&S4*$n4l&?4VKX$Qr!M@{G`x^d_$HP29 z_&@d@`Fs`rkG)+!kH-8zx8eWTyJWpI_&+utkNJP>oFgZ6{vUfoPJ#MA_Ve3!tN&vs z-uIBVtKz-(_^5GXy)gssu&$rl3+v}u-#RcE>+xCFAKcZuC$^7uy}@zfF;lGT42YKd zA8%cMU~v8)%mlpQt>XLO|JXOn`akf0>>2|*sQ+U(ll`&&FT1JuLCpVSSCh{x;Q!o) z|6^B?&vW4a*w>f&KQ^kAnYW*OTjq|6|ve>;G!= zlh*apqr|J-Ze2&#Lw>Ndv-P!U(eNtPUY9WVoxwEi)y3(j~)B)z3^SOz2~CW zv3~)#KQCSh|Hob@>&40T1oj4*p9BBL-gEf0`agDotOqFj+x8veudx0vw+Gh?POyd# zg#Y7qH2fbM^K#+;*zgQ;|GMyg(f_fFPQ9o8kDV{`xZwZTg{Lp8|6{{j!2j|1@CS1J z*6@Dtf83rg^S&_u@6^4m)LZT^Z(%g*nNAilzDWW ztb27|CiCYKtkZfd)%kzie_)@W|6|{AdvN_<_LRvh)c>(J&3I1d|FPFS^MpL#iS~T5 zr%zD-$LF{6nLBa+ZTmLa4*$pP=Qb=*|HsbX`L_B$_LVaS)&H?ePn}f%$3A#I=>K>< z+2_y8JhtU_{M>inRsYBRi!Z#V{?BdrKWlk^!2hw~o#6l2@P6=r>|B{A)#w`We`Q~f znd12lUCp-6lJAe=N3AnYom2m3`%A;6O4|5=Y5t^SW)fBH^#Hry?3dO5u@fJks{W7N^R6*o%pbJ_yuZ-{`>X$Bd+F)k zobk5?`2D=n*s=KY!@9!M1?vB}J$BDt^?&RY;sG)LkG<(gaQ+_~^TuHB*qA?x|7OEq zVg4UGN8Zoye{9TSJGY~qHGCQTAGgEDt!Upqz(1eS4>s&*4gcD`N+;_g@oeya-2b@v zSNK2nG4ZbOfBgAmzkL0`|FN-tF8m++kemHokwr z|FPkZ;s4n1a1*AC2=M1+e7`6jJIWgCIm7>P|6-Y+2mi;0H-!IVWBpO^C!e*3-#e8x)z|QUe17@z^C|qF+wgyE%=^RqKfb?;WZobA z9~=Jqh2Lk}{_uVefB%AY-ib5b-e>37`7w|0o5^#ncON+J{r>A*dw!Yn^Uj2CU$oAX zdB5jAnP-i8t?+-m-&u!){*R5v!~e0j%KSd~KlXO{c^m$ZU0CM-*hOXjkA2|qaWDMY zSMB_m2MGUXua|f~%>Q#6^Z(fSW&Y1?%>QE->^tK1zq%~YEjCPjT)ud~_zTN@-CSm? za63F;_52mqm=6g5$KzohAp9Sj^Z(eK|HsZLELH!<&ddw?KlX0i^g=y_M{Rs7wq>IVW>zYhdzp?&}VFWIkZo^M_X(mUYtCF*8rw{eutuve8+4Ju>8c@PB;0)W?bc za~uAT4L=C~=Qig5u`wSI{?F}*giCh5{sUX7|KsbQKDdqgKQ`vuU3&Y9T`$)6{nw`V zt%qbpdd;?eU_D6I(@Nd(p*8&5QG<|0VzRduz-Gg#Y7qG}ixR!&k!pvEc#X|Jdo$@PBT@|FJPo5A*-n zSZ^2p&$`V2vD4*x;s4n1f$)E9%mak~W7Gff>!El5HtPS_8FD_X|I7W+nE%Jd{_ub7 zK51=r{av-{f@PGHFEf4xXY4|@j zyc6dCvEkpa{x6&J|Jd+QnE%Iye}n&HWBuOAGat0Ze8F{hKV*&hf|&pJcD2{l2PU)$ zSO3TE(k@c{9~(Xp{*Mh`h53IxU#E6K|HqCFZ>Ii_o!TZ${h!n`cl&SGA37f|bberHhwdNh0sqImLz!3Se!Yb5AL3So-X?mFoL$5wCk@;aux_;(1f=oKxEC!V3NR_gaK`O}~4gyl=SP z`(+Rx*lnYubp2nRzkkP$>i^h% zB4oa@_&;`>tUr(Wf9%+{;p+d`m{)tT-_p1On>+*n<)R>i^hS&lvuXjpM=pu~TGyVE8{?KjtIC|FPloQeR86uXp&oHx~7? z?=SFwH*D`~9UI@t_x&~0|G^Kse?ElzKCGAQZcpy&_kmqgqtySk7}H7pU$?%U)c>*Z z?_uEo&c7d}{%`2*!TEn|uK(*c=Krzb?|y0hVM+CfsKC7w<|L!x|J;WEa~uAT4gWXt z(Mu&oTRH~k&58f}`GNPW!$(J{|Ks+^u|faGPL=KOe{8HT4FAU-G$z*jec(Ckfum!* zW&O`u!}E3Qea0Hz??l(r)&uTL@+NdSWerbPA?~C#e9)?nCwv_je%u;f3;vJS15XG4 z$A<5@zTpvH!~gOAzz+p#9J1}`D>ojr#^WEm?tnEsShWiKtq05cwwr(7>udNwo*&l( z|K~R5|G5qS$EN>d!<)hXxefov9&>k+`akwaxgPjGHm(=z|FZFX;QuDI?x_9`4gbf6 zhlKxQ_Z3eH|Hn=hZwmj%P8{1w{U4kDj}1=+|HsDp;Q!dTKk$EU!~e12^@K{*R60!T+)0;o$$+L#5&W z*n?#L9sD2fH?9}+|Jaz1H}%9S+aF%+^5Hjp4gbgeQ|=DV|8pDj|JYbR7XFWod4=$Q zY@8qdk4^u_#yms#Keyrk*z|vF91s4FP5;NH|6}9%!T-4p|HsDH8~h(TVO*U0KX$y_ zfA~MQ;s4lpec=DxhW}&3-@*T}PbB93aQT{6BU~|1h2Z_xqzQ)c@5T9-RNjek$*E^?&R)4hH=nd+WRJ>HI%- zo_xLr|Hsae&p+V**zkUs|K~RRA3Lwi|FQ9TVBknk+nyuy0pb7Be{P{35IuTvH|sa$ z^SA4^q*%W#^Obh)3s~of{~K|oi*=SfK6Y$^9Ut@l?sziZdXIP|_&;7xruZrNKeyrk z$~)-)*n7nH!T+&~q&F>#u=8U*;(-r$lA~ zs{ey8ga2d0lQk)5V*8)QyuY)JtWSOTrT4^F4XuyB2mVpt8tc~{t69(2@P9l%w!{Ci z;nCp#*qDd6;;2wz@tie0;J9l~Tf_Ik|MB_3-@*T};rCj$J7B$E z-fzziFSW+{!0>;3|G?+{Jvq-hS3GT>NmNeeR+M|Hs}@ z=Kt8+i^gaw(e5@$4(q|r}{s3YI>UbKX!7D?&|;8P5Q^H z|6{ipn56!XU2|}(`akx~1B3pLU3*Z_|G`MW|Doak+=l;i8}t9%hW}&N5?=@Z$G$=4 zH^Bd~;r)i)_m3i;AHA#MpL~7e>Pyz}hwy)VJR1Jb?LYQzwhsD4@qcB{CwM*ct?~TY zd^5!w+rOwP{;zER>hk#p{NFP}TdODZ`gK(QXWctO{NOKz)`=bAnXK#Go(^AVefND+ zuzvyf-?XDZe&6%FQmdKlT>! z2AKcH#{4VzKeyrk*zgqae{RG7@p>^|2=o8g@Ozm5$1alfiQ)g;#{55aws=AKKOTRN ztoIB5$Id<)T>rPp$TsTzcJ4o={*S$}FgX8@J?r&7>i^i!PRmjM$4(zKPyHXeZ(y1F zKX$+5~2}z69|FOIFSRw1nrY7M4 zl&~GvS>jRP|M+|}&s}hU z$}07L?3-pSRsYAXJ%5$@Keo4Ujru>gG5^nc(OUI?*2^|{og=FUc)#k;TjsrdTMb`- zTD6vS%9Ll+|8f7Y5o5evQ|bix{j|rRf$IO*VI9?v+jg)2aP@!O-hJ76^?&SnZ)d9i zV{hDdR@eV!7wtcx{*S#+JQ3_3J4<{R{;c7jH}HR0OOcJ=FTNYv&Km3a9_$w3bkP5C z|03~a@PBN~6Ndj|@4xbi{5%sK;LjUp<@blxLt?E@iw}hV<97N#HoPDF9~<-i z{ag4yHh#Z>|6}i#pQmoRIMB`q4>`Vgu&-tQyEQ!C&94miHT)m1e}|k8{*R4+uT`t} z80!OPFRTCK`H#xagYbXs9PyO!e{A@7_&+xM-?ek@wWj~$`MCZs8=f8hkH3Fm9v}Rl z+n+R^9H`f@g?g_-dH>~9dc+z&75L? z{x5sG_*nQqKHnYk^DX=zyFj+@tTD?vU%ub2yl%EN=IO!zaeu7e3;)N?6CViw$Mc~V zR+?+iXP@|N_&+|sy@yVy|6^m`AN(IXN4#Ish51gO^xiqVz&cwVU#s9H>)kT1Z`$^k zt@nt>`)1uM)|me{Y{^3F;*+PneRCICmmEH({*UKJ!~e0d{_mRFui5K|o?m&1HT>Tb z|19r3xt?)^?%vj#RJ0sv3vAwuKtgmn%YGDA3GzXrT1CYeSz&iMyl`YCiCY~ ztL?Y$K1e*2_&;vPJU;k8x2M)TWDP&|MXkfuSg$qpmLt~id6@sl^QR4LtMmWZ@N@8g zZ1_3&KQ??A{2v>B4*rk#3%(EjkFN*%M6+|&cs%C+@$U!G@PBOhujeA)wf!-_Z(P(x zYxuz4vF}-9{a*M#o)5=cu;!9o4|@0d%htHR@PE8sH2fbMz6}14ohF~B!T+)0+u;A$ zJqNT=|7R`h*~0(14gbeZ&S<6nkKIkyTZaE*!ym%`xefov#`D4aKeyrk*tp;De{RG7 zvEeu2|J;WEV`Kek%>QF|E1Unv?k&G>!~d~+rbnp%vzF%%|K~RR9~<-V;Q!ct(_5?m zV{`pqHvJzvL*5_oe{8%y@PF(9GH-KrwO{Q0nIT_)2X6k=8lLaZHGi{)_p5%(KdpPq zdcQGsf4AQGjw`{HJ z|FUttSpS!e=L7%8#{Gc*W8?Vne{4KI_&;_)=E=eTv70sbzdl$mlCKT^f2jZaAKlXL z%Q}a4$h^7#<_G_`>*I#{w%#pT`mP`E5BK?m&LfOz=J$-4FX`?dy8VB2^CrIiLp|Yt z>(KRrBgKQd=MVLWp~nkd|2IkekNbGcw{#o6)$P#rltaB`=={H1Zt;7*(D{FjZ}oe? z&<^!`q28~4egF55Q2*Dgf!_;a9w7W*M#gIOf8k~RkKMd+J@tQVtQQRbx9YJ~>i_D6 zHBtY^ZrrA&`oFK2zoGuGd9zmP|Jao(2K^r!^YykLeZh`*lXyA!KOPVB|KR_u%jW;_ zdMZ^4`agD+Dpl0~vEcz5yf@39-_0@~5dM$b8(m*X{U5u5c*L-nS)~=*tx^BS`G0KA z|6{}N!T-4p|K~RRU+#5leg4ngj`@FXWB#ApnE&TC{GWR~_&>K7kAA-NzR%XG_rrWZ z_&>Md|JW781H%8YYt*W({*PU|MJx4x?8Y5}{*ULwdc2tb$HshG_&;{%_TlRP*!ceb z<=cj!|jj!+K@7{0Mn;ssa{*Tw&IikJ#KXyW72lapKm<}D)|FL5`MydZ}caDxx z|Hp=hga2bE#z*V?KQ`C@Wn(+$|G5qS$Loh5g#U9J{*MhW`1o&QtZ{z$KW@i-J@`L% zx7eWnW7Gff{G9*iHvAtuIyzd{|7E9i3eNvy_eo6gzW8it`T3Fp-n)Mcv4-CpEA#)j zf3KK$^?&UCi2-jz-$Ay2@2)+)CF2KLCwER#|Htdc{J&eDO1Jk*TyoI=@$0>7K;{WP z+P9S7kKp-wFX~eod48q-JcZ|b%g)}ucEA7kO7MF=thelL$MN0nmYnEq?f6AWgFi>B z=Y#i~)An=g9{ppyyTU%RP8t@W{*U{2mw9`b|HsC>Kdk@Dh6jZIV`H8k{NISq(dz%O zUM~C}JAGuV*L>=gk~!I()c2uFpS*01`GN3%+}=~x6Ndj|cNWhj|Gujvt79kiU^u`0 z{$~yUC%+&1TK@f*^#D1a%$K(wI4Vy4ACKREOuYI(x8eWT1INax|6>ojBVPR<8-5J_ z&u#cWcDl^->-pMIJ3o5eD@Uv`{|^3-`=j5gbJ!Xl4gQbY(eQt4oFD#=jqUJ%Y^?ta z|K~RR9~=Je?D!J99z4G7oyFGhZ?i`gSz|uoC&LP@;gdQKDzJt}TAG$`Jxsh8=Kt}0 zgXQt?f9!taqSgPo4gbg2oAdwJod3t}CG#NR|J;WEV{`r=J1{O*=l`+k|JZo`@PBOF zANW7F;s4n5e{A|ccF*zg9{eA>$K5hdQv6?ecTxYxhEIe4W8?Vne{RG7u{(>eg#TkF zj1Q>)W2Z~Q|FQeu)kXau?>CMQ|Hr2Ppp09{=l>rPlC#nE%Je!-s8O|C()27tdCC^mtI zaG^EczmLv;#Tvd3{*UKNlJ_tC9~+N{|6}9vnE%Iy2ZaA)+;_&+v$ApD=( z@PBT@|FILr1H%8Yd&+vz`vyL0*Vp^Lp#S6hrC*u4D5$KLi{(EqXX&cCPr&u#cWHa^dR|6^y$ z=S}c`Z1^9{|6^l)PxwDJ{NTM;yZajc@9mFTsRzXR!SH`<%me(qUBLE-|Et=wi*>g6 zBltfaKl9?p>i^hTGXD(zkG=omC+h#$2j08t!T+)0^)Ua>ZTLU--uFNEhEIDyq50kZ`tl|0K|G53QtUn9?=QjKw z8(t6okB#+f;s4l&#izmlx!vn{ZMz(d zKMDFjHr9*A{6F>~@qF-qY}_x*|6{{L!vC?4l=(k4<|D%Yv9aDS{2v>>6aJ44?+5?q zHvAtO^Zc?q9ryM1cOSMsEc5-~|LpaXhW}$1T?x+rlQpN+lNN~Qga30I{*Mix2mi;$ zdcg31ZciEaPWkcW^Y{}lzwPTL1?zkb|HsGU^LzL|cD8)}4FAW*JU{q9_9pqf7XA-r zpvt!AlHsl3|JZxP2V(vod#B7pf&XLgIC@h3AA60=-xzk^6x+UF%XamD+#WYbTIMCzw5~7vpMB#7>+6R^$^E#-*YJNlKeogFv8xR2B);*Ib)!L@)c;{- z6MP~X{*PUEP?UJZ&AuKvXr=Y7ay_}9&$q54^A6$v`1o1_qSXJfYi4xB`pCAu;sEt3 z)?UAM@H>TPdbCv^cth71^?&S!gL}hw+4eT~O~(EO-2U+H9Ql3E6GIhz{F2;aY)@cs z6z?aGPh`XYiI=j*d^PyL^+(&PAKWD#5B`t6N4x?29~=G({*Rq4eiii^ii zdItR;uXoJQ8S4Mok4##M`1GFRTA!=kM97{*V3csl%9OX^-E3Ht7F&e$4-a|6^yJKBxYVop=5s<~!QsOXU4< z>76y!Me=@`Hup_y%#VWqe{8&;;Q!e0eei$m>@(s`Wd0u;*8~5@&N+ET{U1B` z)LEVX$1WBR0{_R(-+xT~AN#GMqw4?Ik1klQ{*T>g>Rk1IY%guN`akPo!`1(>Tg{y1 z{r1RJJ71+aFL~<+d|`d_t3m(A{XLn_2mj|b{GatptJVLx4gXi(E7kv5FI=tuue?`z z-@REOU@ac6+v1AlJ!7%Ad`6}6UJ&$ue7))atY2NH^Z%^N=Kop0wqE@o&sX#1)$0G) z4VQ27;Q!d^Gv=uOW49SSPW>OhpVl3kq5hBUCCPdKGXKvyx~uv>cGN@9s{dn;T)am8 zAA4rOVfBCPwK6XY^Z(eJ<@+UO?eWhO%$J1CV`t0z8~@FQSB3v$!vn(qu`z!f^Z(db z&l>)ZT`c|gsZjy`ys-DuhwA^>N8bzjKlYJ}@2me~@0Zr~f6IP8Iw1R>os}5i&rk4y z@PBT@|FI9r&m-`EY^*m7|7SnH$?@U;*zk7nf7~DQJK_J_hW}&3@4^4M4gbf+zjuQF zW8?Q9_&=VH{*R6G!T+)0>)`*~hW}$@9xeQz+wgyE%;&@WKb{{A|Hm#69|-@)#`?hU ze{9U>ga30I^Z&|^e@W;6u`#a?{*S+ZVO}Bp9~&MJ{_lqhthyUaGio{35|G5qS$1W)Ie{RG7v3H9ng#Y97+av4y!vC>zWc^+EKXz`J|6_Ch zpWE<%Y)AXcHYsT|6}9d%fSD+4gbfc|6^y# zygv9pcDBs(ga2dG|G5qS$A-@fJzw}gzJ6%tNxGY%PsSN?2VaO>i^gq_5|1eWpCLPT>qE7ZsR-N z&29GtZf+Z;UhnO78@$+vOzTm@M|)#BWLZb`i1TK4%C>IQAYjtitW({vOwcc@S_&fMNUO)U9{GZ$Kf4txDhwy)&ZI4pViH84U`AB6wo_2Buy|FLm=_&>Md|JZmu z{2v>ShyP<^UR}X^AKLTpKcKC5_3}sME&Id&+5Y0w;Q!c|ABg#XZo~hv;Sb^e+=l;S zr^x+;|6_NRe@_Sh$A<5N|8sln-~MFRhvz^0`>%by_3wZ7_4%K^@%69&_=`2}N2A}q z^>vTm|7x8o|6cC?fBnt6Pycp0|Bu%LZwLS9Hs=4a;R7-MkB$3_`G4#|^7R7$=QjKw z8}t6)|M>ny!~e0iKf@$>4A;x#b;j}6}h|HqD%`E&4p?D#fK)c>&)+BMVpe{A?Y_&>KX|Icms zKeyrk*zkSue{9S%g#Tl=50`m?U;7*L|F|7q4*rkbMf@QAAG=4p;QGIA-;qAWw!i^jAAn<=|%sYhtV~2-$ztG10b3gwN^=8qn{p&l2c8?bR z?cJOEy>fX~L-+r0^9V!lcSJkC zR}7uU7kd2oR{r}Ni0I(EzR->dxgX&nUJ~nPyU(v~UH{i}==#5*^Zr8pUTBAUzgoBX zy*e{SVZW?Z?}mQsp7N&u`{CBL>I1R9@XBs;OBak@t-h~n zfX;@GFAGdpT>Z<>{48)E8oZ_`i9X>(&2x;``wL z+=l;SSG}f^xBZXjN{e27Gw@W&cgfW&U9bL++cB>a^Z(dU;^iV=d(zGq(Y~$vKc2r` zL~HebY^Q39xUr6 z9sS?|+YWz-^?!N%4iRnC|FL7DBGvz~<6}Ci|Ks(>MR!pD$A;&_{6Dub|Bu~K<{x7I zA3G{4=>OOq#M5E@Uv`wNUkm@o#(KV3|Cb#b8;ifsuqEb(eQt~el+|a8y*n; zj~(ABTKyjz^Zwxf*nQ#>yta3YvGbuZ|Bu_TfAqMK)>yx{`LiRe)yFNp-5UPy+MUC# zlfv73KOY@tjXz)E|9JfP@JRK4>_Akscd*V7+nyZR(aY*E*w^rX+&{TfjQT$|)(6J? zKX#0GJorDpUt+ribp9W^Zy-heAHN^ePy2fMmQ&W45BR}`lh*yj zAI7XdVI4Cz##^-NxOJS&r~794F>ClW_&=T>4gcph{2%WJw!{Cq4gcph{2x0})(eII zW5Wx<|FPlO>OZvC&Iix-_@q*6cs=+(UJn}nkB$A||JXPl{2v?Vga30I{*Mih^j)7k zYxt?u9=Xq7hV6C4Nryne{N&`9~<-T;Q!o)|FgcQv-&@`;s4k; zKKvgWo(uku9WD+3$8Im{v(}RNe{4J+{*R5vWBwoCALy{Nt8F{|ANP+RAM}6hgb9gW zr~NB!e|Wu@i&t1<{ok+iUbh}RK3V-AA3sRu1;YQaaeeTAY#eX!#wFH+WF8{?AGc#Y zWB5Nd{U00m8~%@t_aFQpoBodtzjyM5mu)+IU8@-{Sq~YP=*@g?f%PC+AN->y=Ue0b z8u!>dYrLP~|9E`(Tlhb>;s4n5e{RG7xefov#(c=#gJxR8*H%rRVLhbG|Jmy+&jtW5P6JK)lPp$Rypc3(aTROyApOE8S=o@W)T#onq z_$ccv@nOxUb+FD6@0YeB(z^6Y(Er)_#1Bqu)y~eJE9aAK)_LNyi^jAZt#EXqgR9ekA3RPzp4LY!vn(qv2i`{f9#_l2K^uJAABAB9~=9_ z|8ajb{2zOt%=3f)a~uB8ZOs2;V;&#o|FLmD;Q!o)|6`w*^TGeI&&l<||FP-++=l;S zV?H4KAA7&dXN3P_9~Hj||HnQe-VgqdeMr`ehW}$9`S=T2Kl`vX?jQUgU+;ru^Z(eG z*Qe|Mo^7lC4-NmfrmQg^5dM!{B3=;wk9|_sZwrgrX2(A+pO3@;@%Sb3c{BW<+wgyE zd_MogSF3yt|HtDO$ow4mKeyrk*zketu6xDT@P9A^@PP0y@PF*>vi=$TAA8NQp#Nhp zDlAd|$9`$!7WIGZ&Vz@m|6`}5c31z$PV5oT`G4#x8A1QYzHwlJ`agE{K{4w8+=lMs`;J$8I{jv-&@F!$HyN|JaoVcU1q!zD~R!{2v?M5B`sR zqx^XR|Hp1SG+O;1)@X$PYdtth{U5ug_(S+VHhd!dANy8${_ub7Is;^Wy7)hK?SY-t z|FP=~j#2-|uAk8fUd8smrEes>USYH7aP@z+yNjQc`G4$oBm3g`g?#*=iIb%NQNUiZ zWvl!?=y}{9^C02>*jX}P2L6w|?dU1>f9yTtuVjDQo-IBP{_pYpaP@$g$0qX&yKsNZ z8ntuc>Cj&GeO>j{e|v(6E}hxvbee5O1e^Z(eGrzOwVI`>3y{vWraG5?R9CG-Ad zUYhl8na_p!f4tu92hQvIzwFJWr{R;5*qM3oY_+VHuFS;qwSMa9OmA?dFzbH(=ZIHq zYds)tsrR=9QP#I7uZEAb9v)cgy;!rG^&P!d>-;~SfBf*->i^hNCM{F{$6o*36XM10 zOycuh^Yo+gd?#AxJ%5k-KW@)??rz+F+rC@o17iLkw_kYkMfHE|>|I;b|FO@V4EjHI zp3ML29J$aQUwH1k`afP@!P#@N9_upOUh;0x|MBtp;#J`P*tzolg8yS;G--iGPFtv*U|z zg#TmTJY$LaKX#qDE9L!C*|vKxt@8qRRw?ggTjcBg#`0dY-up6eQ+dC#R{bB3=Pe5Q zKkJo2|HqD>y-58ZyXB+LtN-Kk51TYW{U5tZMt}8x?AocR>i^jFGcwfwvG1DjxcWc# zTbr`g|FP#5>{b8AeqH<#{2%}P*dg;JM#FMq85kDXuU|J;WEW5esg|FJRe5dM#yE6*?Y+l&Bz zKE%JTg8yUF|G5qS$HqKC_&>Md|E%Tv3H%=$-VXlHTAn}rAFl`V`QZQDhW~RL{*Rq6 z>-WO{vEc>b|J>ta{a-fL8;1Ym?+0l3KQ`v&!vFF2y`A#sEBv3^@PFLDxXk~#4gbgU z<;!;XKQ`X4@PBN0LCpVS7s`A;_&+v$ApD;_KWX?sx8eWT`SN(o|6}LLe85Ss&9>vA zm(G2`x>)=m{2#BsMEoH9AN!E_K+OMR?-$<(|Hsag$7B8<8}k6+|Jd2`^AG$VJL`z7 zcQ5n**ahP8u>LQfZ;|W||HtiE{}=QB*ab(9>HI%-QJMea>w|{>V{`tW+wgyE&i`X` z{vSK{K+ylOvt*uMysZDrhUdflKQ{dzoAdwJod3t(BmVFFtE=qs+w)7j;@PXM^K(no z|8f6$`$JW#&n2Q515#etp1N3A6`rS zAG=pVQ}uuBuF1El|6_McX{7#-e?QfsYeV&a?2h6C;s4lC-5aU@W5WZ&|FHwznyUX} z_Y&`O>yl#Io+zGZ=k+ClKEFk&??c~mL#cHinLh^q$L)P(o*euiJ2^wvo0a*0>=bx8 zng7Rz_rm-?x8eWXhW}&3i^2b~F<%b;k3CrCx559h>Hpk@|Ksz;cKAOwyd3-=@AsID z_TK0h&RCC1i|}T?c-9(^e`motYdjwQ&;EW^@sA^abk{*O)n$Hw{K z|J-hR`m*o(d!M~xjs4;O-2LJI+=l<-^T+=1e{A@`>pu9{*Wn+1;_JbmT=g~lACKQt z=I6oxxefovj+gbL;s4l)a{u7}*zkq$e{8Hz4FAXL!*=*Tx8eWTI6wTK+wgyEtgj3I z=QjKwoBog8TYTHA|M||gWBy)lg&%zVQN_RiAJXmv%8D}G+kSzVzBJR+JgL{Tw}Ifqea97mne8RxwB^>qL5uG+J{GwZDH zUF)oOu2r?GYS-SK+&}Io(Pd8hn>Xw8Hag`e@BZfZ`j`FLdw^Zf-KYKHE&r$U%m1m_ zAOELjeO~;ZTK-Qh{}*rkpPK#gf9jq+8wCHS?$M*j|EW9MJV56Esk_*`K>VLt{!fkn z>sGO}Z_mp~dZ?_-(Ju0Os%=Zkmh`m?G2FSS|EIsW)mU-%#M2vg<_{i<$Zbsk@8r``|NCyn1Pd}_Q?{cYuXNxxgQLDJWy`o90xsopQu z@1=I?@&4Q6|6~4N^~%Bj@jKv6Uwxaa^?xUSIyZQ~YSqsR^Z(S9t5yvDuUXAG!T;e6 z@qg;5?8(9ZsZS|=Qt*H3lcF-g|EckA_`i=!%?WKQ-TP zPrU6;zdpWyzUub<@2-n(^z+xXd48<_tL?03%ltoGe_C2v@PF#It;J0Tv@TlzSDl$*pYNOhQ@715n*XO}{vrNP-6^wZ{oidxl<@PF#=7o`RN7jOKZn)!tIKQ&$v|L1Mji~ox^{!fi(#Q&*zJpNCOkHr6}vu*ug z{GYm;-Cz8lx<|49Q?uUiZ;v1F?evg`_a}PIxP9Ju#Ij@ddbhs9yzM=E5?y%vZg1w> z;s10#8vhq>{GVF$|J3*?{9nBBfAPlu#T);p?s-{O@PFzaBiaT3r^Y+t|J2=Wo*(o7 z)Lm>ICH^no_&>Gg|EamZ_&+tr$N$B+|CO)c7>~pSp`35C5m`X8wuwf7M;h1LFVGc~`d!{x9D6KQ;5) z@PFz|J3szU&HA_azjz-yKHD3AhyT-dycg^LdYd0({$ITDe`=18|5JCd`Fr?3HP4^< zfAPlusqvQhzj)*S)ZBmkpPG4s_&;^8YdePdf9fvgGx2|F`9HP%pBk@+|5MBVshQV_ z|BE;NPmLeM|Eck~_&+u0$N#B0KmJdhW!stmr)E8I{GS?siT_h)+WP_jr|xgpkN;Em zv-4luW1KgBcl_fIc=P_u7&pe7_sjQp-y+@ z6aS~LpRU(-2>wrv|NFGfjlO^9YuiV2b1y2GbF@+LZB6^vjSgQp+`ESPkst3E>OE$| zl;Ho&s0A-Leb1iY|I{nqws}N*`uqNT-ZTCEzTV8QDEy_jH}n4Re|o&;|EZZrf&Wu8 zuLA$4W`F!&yzzhPjrMsL{!g86pYNS?DBI7!)7F=2{%Mvs>xT{hSEe_g_u>C^e`x%l zde0m02mcpu{GU4ijSqwWQ*S!{QSg82Eyq6$^Z#^xwEgdr>otF9pLKX|vU!B~KkZ*& zz7PKw?|+c4 z|Kg4Ri#PsH%{)Bj|HT{sr`~Jp=l*H#8Gilr+1pO@=JDBYluh(C-<{&U%X}U4|MdKK zo5#cdsquiHwmrcc?}q==`L~#-!~dzb+WGK*YL18hQ|~d4i2qaL6Y+m)d?Ef%&3elC zzj)*S)cb5Z>;J|Z|EI?L;s4@||5NjN;s4aUp7=jC>+j zn?K>r`g!<2W(MH_H{1GX^Tv<&?ektb8htnHe(ypxq z=YH3CH|UWY&742NyI!~KsLRhoy{q=iihk(U&%0Xx_R$M7yLmGouiN*z-ps!wqk|EI?HG5=4^yg&S(y7Z8u`G4vY zh8E5LQ!`)i>hwdtKfUYKE#Bu2&ItZ*(F-=S$$Vg?A(_Gdsm~pn9{iuWqWM7lpPJ{# z`oHmJ{-65%zO91)Q=iqf5q@X8`kW4J@rd4yZT(;TpSBOY`YQI{rk=HWrTx7ZMe2q5 zTk(AD?ylV|ctYma;Q!QX_Zee0{og8$QYydd-c zypO&f{GXcne)vB%^V0@>vB<9%&u8A&d+E!^?7h6odztOu=iYVRD{TEp{GX1u)Vv1% zPn}=v|Kg4RQ?DsF82q1laehJYf9fZetqcB7T{*Ku@PFzkqi^tk>I#Fe5B^Ub-7-4( zKXv`-^Mn6W*Pb>%_&;^cDRX&0`}IZB=0?qjee2IRnz1POKfT`3#M#0Bd7H1p|9L+% zH~2qwsi_Nt|5Hbk=LG+!^G6dV2mj~&;IqO1c|Z0-@PFP<%nAO_d-CGo|GX#85B|^l z(HDaM^L~6*nE$6PHEDjB|EI3^*!1ZA$Ii*o_0||aDfmBi+tCjM|EE54(9q!j)OF4K zHOs5&kFRbXuynHvyh~kiZSa5EzyI1z!T+hB-n=dNKlSW`F9rXnpC7Ajy-?QD)z9xu z=2`K7YTobIJT?E`i2tpY|BE;NucY4z{!h)ky0HFl@$U;;UwgM`{omr=Zolu>UE4NC zzmM?y|8Fxg6OI4VcKN?}>DLd?@};%{;(U+TE0+zsCyg z=P&+Gy~P^;7jOKZ9>1s9|HT{sr}Ojk7yqYbzHX~2WBmH%|FoUP|EUYi|J1vR{hwO% z|J0iQ7jOKZdXudujQ>+JkB|9(>Ye5T@qcQ(AO0`i%>PsKc;^4<_2KdOKX3c@7|j1u z@7Q}d%>Row>;I~^?>Q9a|Eag^IT+^usWe@KKMWN{DnpSPyOViXQDgC ztk3y!e4Fs^Nt@Z{WiuYw;9a4?$-)0EOHU6zuzq&c;Q!S4ywe`uPq2?@%N7KXuy<)q?+1XWM$f_&;@~tsjd2JLg}mga6C!*C6;mHS5RX z|Kg4RQ+MfGd$|W`9=JnUJvHA;s4b5IQ*ZQ`EIW~{knHo^NILBZKs+4r|xUl zhyRN=^Z(RbAM^jzTp#{V&3rxlpI$E-|EK2hH@*I@H;rQ{x9D6KXpf&Pssegcr*V`&ExTZ@y7qDxgO^K#hdki)y)6I|HT{s zr)K?d=KsYT|EKPjlblzU*EZ>iGFzq0W3&0F@z0-`uM=3E*9y&YBuVFj>PmRyR z|Eb%xXd3*VI;&-~F#k{8vuUf~|Kg4RQ*%E2pPG4T_&+tC4*#cS{v7^K&3cgdKQ*3? z`G0EW^Wp#0?Hby8(dPfu_$>Ti$Gcw){*QT2_&+tC?#Qvbyty9ypB^9PQi62F_&L@uj=w&s^XyU|pE{o}b-mfnwUV!Yhnh*B#`@3k^QF$$ zOPz<8dj8aI-K19HcxjE3UNy7P|K6$V3#T?dD1N=Eo-)->c1XFOsh%&jTh>orf9m%C zSZ_IX{pFNSUEjEIy&8$@PhF2V)#Ihk@B43luW{w%_k#wNlJoxl+v8K$3r_7CwW@^m zf74dZ58kh4?W)l=iykjjpI56!@PF#Fs+=GE-?1;|2LE?brL%+oQ%5J24*pMlR;kj# z|EVjKJ|Xx&HQw*l(;hBVpJ-lf@vMiu<^M_@o)>%|jsJ@`{x9D6KlRBclnVY&eM*_q z5&lol=cJQP3jR;cyg>ZlRnII49`ck^P6_@m-uOT5U(x0V;{Vj=m>0zVsqusV{CQl- z@$7!!|8zY(fBav(@qc=}{9n9T|99H$3w_=n{!h*QIqiSOc=Pxjm6DDB+dpJc@PVg9 zCxrEX)#Xk&DLQ(^D1Uq#TTl6c`|kA~+Ne=fH~VgXK72o|IP9)OE7A^uOzcIN-7nFomfQ_KIUJGW~a;s4Y_+O-S*Pd&hnhyPRK{SG(1EYbKs zZEt6f$N#CB=ZF8({o;D?e`>B5|EF%(CO!B+wfvu&d4BjmHS_xLf9j5DErb74cWBij z_&+uC4Do;Q#{YS@P7nT1&HBaoKQ-sW|LOga-7+osKYhJ*PD_twP3q-ef6PCO|2#_d zf6POSZ*S2y{eSI_?OGe2B&pL%yPPq(JqC*G|_WJXVP z_}IIJ`L?UGKJu3T)A8_sgC@RT@a3DC!TZVo#T);p?pN&p)O~G!-!JdHUGQw5%;5d- zdH6pyz7GGV?sjS0;Q!QJZGIpAFW#*G8*ludTK-Qh|EKP6^A7QU@y7qD@q75cc;o-n z%$LLeshKZ_|5M}9@PF#=<|~>1rh|VSe9)CEobD z3&t+?#`od>biEyHz8?P1+vcq?|4+^FMwtIoGmj1br)K+(Yv=m$@r7?)HOCuYi2w8b z?fm$^c;o-n_(J?&yzzf(`M-GM|I}O`{x9D9@}~RsaQqM3KkJ=tuMhrD`{V2Ie`?;( z_&+tT59|NN8~>-~^xuu1H}n70_)+{{yzzf(`9C%D0P%lnt{4BO#s}j6 z)NQZI2>wsq#=f86|I|&dXcPROx`nMLjsH{g{P2Hjo*({C-N(*{|BE;NPtE%g{}=E1 zH{I*a^$q{S-QHQ|_3(e%KgT>E{x9D6KYe}VjV$ti@y7pY|DGdrg8#dFLzCeDTJ^6N z{GYmt`40S_denwVQI)3$dq2DXK-78ZK<_1QzZ3kQ_CH{szu^DWtZ#+?Q*XBZx_qxh zGyl)l#0|c1lX*YxshRhO|5I-?pM?L@`FGj+r1(E|p?M_y zpL*+C9|r#yZ~R}png17W{GXcZVg8>Q&&d40lKvq0KV4tGc|ZGX!>@OJvH#Qdb@q89 z{!h((LHu95@qbIEH_gHSF^>)Zr)K?F{GYned>j5xy~{is{!hKv=Huc2;*J0FHZO<& zi#PsH&3wD(Z?53iNAG^Lyf=Oi|EKGx&o=+3#?#^d)CbJ(;s4b5J^Y_~yUioS|EZ7I zygvM&`mjBJ{GYCGvps+OpL&ZufBc`C=a2tWvmP)0PtE$r_&+u45##^V%vZ$!#T);p zmj8=4{!h*Qn0Mrzox1))d;UNDe%u@1iT~67H2zP$-(G+GU%c^u>cV$Fi7uJ4$D8-d zn%xE7@_+xhpjq&Nc)y`FHv9H1Hjid`zYX4-?du8ur{gnE2mcpu{GWPdvHy!V{!fhu zoO8nqiT>Nn=e?Jh_v`x7v_#MNb&~h~*WQW_JU4NtuAi>5?{RO|d+T-KBRiQ9gb$Se zQ_necB=|q|Gh4Pt@BQgcfBdAyOQMH5-Q?YV;Gp3Dw13U6>B0ZSdt9HPzJIGeHqUNx zU+=WOt%Lv5{*}%9;s4a<+j_S6KlRxITG+hB7Ty*5H^)bKpK9~)erj9OyX@ffF#nG= z5%G@Y2c-x9r#{{0>#_c?n)QY8f9f;LBjW$m(XbX_{-5{omSO&%`kWyxga3;+{!h)k zzbe-)^R76otzF+t?<&LF1^+kd30uR_eBk**Gw@eC)Mwehr^5fKD-6#J^Z(T64NMRI zPkmOe=J=iMYUcmp|I|${>CN%IFC96O{kLiRqP1)7@4YBeuQI=4+uNy`KVy&2QnTKj z9p9VzYqr1lTASB{|9h!Ii{J;D*N6X87ubA2{GXb~Q#j=2mhzuyz%wm|J0Kvt_c25J?f?v z!T+g;_Ixb(KlOmLBLAlz-fm{_e`@Cc;s4YZcbpOYpL*or@xlM8AG~Q+@PF!g58NC4 zpZfW`ZiyZleQma0ziszj7W|)j>!=aDzP^3qgzLdP$l8MpPO(uA6Ub`$h^OQ%u z-*|aH?`Q8lhYv@W7e4KM@Re7hQ)W%^-hA{G^H|fpH@$q+-p?~j+ScPO-E6k^W?Qd! z#i{eXmlXRyUH@Y9e)vDN{GWP>`9S=idYO3&{GaZR{GWQ={-a_3pL*r4Lt*`2^&>Vf ziS>WgH!NBn{GYnZ>>0uTsiP+Kqp3rV`T3)kb)&47$Gx-e9BE(g?|4TKKNUUo^?TlD zzPK=Iv+pDCv}uc?59fU5-PHWvBcs3aj-FW<{GXn0G-;8|bNzF+zCT4zFNju7`q8`0 zlqG!s^NuDih@#HFmGsjKnJ-e(6K6(~b4um-@gI27-XABF^!-mo?JA#G(vLqM{GZ>C zr{)F!=WW-^{6Ftv|L1M~@AASk{CH&^ofWlSRo?rAM`qgltAh7gk4y{xPuEAk+~C|C zJ^z!(+dR&S=XpmXZ{+8PcaO_1k9z*4ig#we{!#V!t9h5Z_>$vhL_&>G$pBgWR|5NX^`Gokt zc;o-ntRIa3i#PsHU0{Ddjp)@qN53!8`Ds19ncr8gYHx4+pUq#-(eIP^Kby~<=&mgW zc=Pw#1(gPQvtIE}zYq4t>mB)gXrkvG8Sc%$uef*pMc#PEelsrd=6=*0H^Q6a6;`^! zuXn%Q--^*y-gv;}t^eTruebSsE9TpJz{P*R^7rC|$80^|;^y_e=;rIZx4!yL)N=3* z-h1rv_&@Ex+vfe@|J3+<{9n8$etWz3Ve@@|c z|I_PDg~4u zhwjh#{bgR@`&pB`3(TM6|MdFM_&;@FvHw#SnEzWpWok~{#!Z5k+iC0je)!Nd@9ldJ zL}l-J)?4%c^myh2GXGD#*?b@K|J0kz_u>E4`Gxy}|5LBuQRM$hx-iWDQ*YQ=R2u5lZ^J7rdmz8s(LotINJ_&@E> zJV4g}RX5407W|*OnR!6`pSpEk)iD1r-pv0~XXKn8{GU3<<^%RPd1uZi|4t9yFRgcx z|5K;;E1LhO&NeTG|BE;NPu{$A zZ|1KJ8@Jz^`D^$;9gq2K%>PsOw|Q^9#vk(idHj##4<{P`r~UC?_`i7L|8zfi{QNDi zB>M2SSH1CWf7x-&8&6fS@HOvjyS}X5uY2d%^&vE<^3Li~FIu*- zr1NZ^>BVhI`}WMtN{P>l+cd9{==2szZ-u{ze;&=eKK$SC^XCTt*R4sD;Q!)1bKS_? zdg*h5m&oTHRr?sskuJ{ok&CaLRhc{c9xe59?LOufJ8jq-RX^d#TSS zy>9aBA+=MVZ)&H$KL6KFy`I$TJ@35p63;Jn{oixXIX|)e{7T9BpViMxZcpvh5mldcyC_# z{!*^u*-^E6B^{Zsdno^5-(I#jdA9cf#(bf1f@uzEIDf?f0El(q+q* z4fFrBz2a#Vq8@jQ^W#-G^~`8osgh=XUZbt|`}LHy^?3jI))?<{<`eOMx*paC-hSs8 z?^1UEnE$8q;rZsAp6q8I9aA{r;zhwL^86o}H`<&1@7jJ}qHk(3x-hN7;@}5smMZdp zpVeCuJYd69%LV_Z?YzGDKXonp{*C|B`S|{c|5N9-X%&sGc86bY&+h$#|I_tfIBZ08 ztn{t^{B9dID9WvVi+7*2=F#e`o4rq~St+VE+}86ge!VK0M}B_SO@4elIQ~z^Pp{h` z_&;4wP4nE$|5Mj%(Jc5sJ)g8@&4d4oH~uf)_`i5F|4+?4JN%y-|AzmIH~vq}JVE@Q zx>=jn(VLfE<=2NN+jq~E-W}SsjZQvtrSH#tKK!2^-@k3!;Q!Qp%@^YT)XZDN|EckW z_&+t<@qcQ(9sW=Et4-Th!T-e@|EFgCWaj^=+qF##^Z&ff2jc(YjsH_~{^S1|?9KUE z|5w|YKZyTRXSQw=;s4b5zHJ@)`|FSI`{t5<-n>5eKfOO%HMRNaQ~P+gZ_z68{Ws4% zVf^P&r}X4{zp0InjPH++jCWRAqv%-17X`VsvctT;>^4n;{~LFG`{4gFI@bvPPu+WX z>)`*?%&)`$#T);pX1>~%DIXN9`8X?hKN|n1#%q1~<+}wR4b2Lk5091i=^wrEf3rS# zC(-yn?T_cf|HT{s7jNeO#T);p=KT1-c;o-n9H04r@&2F6uNItnv|aFOJic9Y z)@L8}&bd4z>U-wP-nr)Ut}A!Mn|XTpKOG-Wg#T0HbMSv^d=CCk&35Mhso9SIQ!{@I z{}*rO|Ecjg%>Row{!iV}JRtrr-uOT7V*jU>|5I~)KOfuf&zC;)=r(Vz5C5n8$$F>w zKQ;ai|EI=N;{VjlOT_=Fc|Ts-Vq-yGr*`4*SG;L@(+%FN2aNyI{<+rpKQ$in+{J6X zc|Gud+RpRC|EalN{9nBBe`=mD{!h*8ga1?W{PBP4KIR+oe`Psf-4Q+K~MEBHU1kH-J0yO=Ml zJNyNIJbo{C@GNh9;YIytdNWV%&fYT;{dD)|y?H*%J3r^m{6qYou7~-5_&;@fyI;R% zO!Maco!w@tH-4^Z%PHQxzW6^~KVOgdKQ*s6{!h*Rw?FZ;H^;~SX*+%o|EJC?_J8VJ z^Sk&zb((#DVE$jc@qcQr2mcpu{GXchGyhM``SE{h`9HP%pPKc9@qcRWC;m^(JV5+k zyzzf(`9C%5KjZ(r?fCdVb%$$;{GYeIKk$EQ<^kgW^m^h0S^rm^J2E%S|I_}g56t{O zGiky9HL?F*!u&sV<-s;@%KV>t?AGbQ|EXse`#<&SH*I}EoByZg^DF#cyzzhP&Gva3 z{!hKhKCd~eaS!ipwjLG!uj$Xtf(N9pysV3F-)x@l$x)rWx4r#Qv~g+&Z#>cmt8%@W zH-`Vy`B=XT|EJz%-Vgs5Z|48S8~>-?ZR?xj|J1wQE?WOry~i5=r{4AEyTSjd`8>-0 z+rDq#@%nqg|LOT|HSfp#KlK*dj{ozv=ZpV~H~#PU2bu@}x7nT#{!hKb<^|&a)Xek4 z|Ec$VSmgiI@_%al8~#td`{SbZf7SRw{GXcR#HT-uOTDOST>Vr^fH$ z|I`I`Jp7-!(5@fpA29bbZ_H`Qrc7 zyKKGRt}R~k#`EF-bpJU&{x9D6KlR=}7Wuz;=r`~Jp|Gs|V62D$NY@MeTB>J9$Io_;K_tFou5?!_S^WLlM>*s_{gOIu&Lfp@t9t)d#+Y9#t_h4a177|=TE^}$&? zF%kGj`se0lz0Vog(&izS_O58__ddV;=N;O=!qArH9luO;m!IGAt~j)ndB%g@ctBe} z+WR!yj{m!<6Nw&r{oUT@4r|SN%HEZRx3T$x8QxU~Wd#4% z=iZjV51!S%DgJJ|x^jn>!T+h#ir4>D54qt+_TQ$SW1pAu|J19t?O=O5^%k4whW}G< zF7|)wowmLu{!hKsK3})>iQB8!*t{W|U+9fLFyH9C-8_LE-w+(xJQi=hfipGq`LnXwdOrE)|I8bC zKlS7?p0D@yBbPG|%)3Xo$L)F>diQNLg?sHisO@vyAMgGhrU(D0^AGMaGx$ICm4n6w z|EIqH<|6;6UNLr5@PFz#cia^GpRRxPeU}FRr(QF<$p5J~ng3f>?SX8)U*B8$H0y_Z zZ&|mT`J&$VKYKrW?>lrj8g-yHv^>tAKwg86^y)i(bW|EFGK^O}Acl<&R7<{L5pPxouZ zjswB}sn_m468xWf;g&7Yj6M7O@%K-j%zEJ7UGIM&`exM2-chaE!T;&}QBC`N+5De+ z(0${B|5LY_^nCDt>a6Lrga1>XY4i9_ZuFTy|1+j6h-|%b?`YD}=%Nq)RMO8Z3I0#7 zXEbGL@PFP@mj(alZT=4b=WSjP|L6Vq^x*$=J<*uQga7ls_p#vr)TN)C75ty>Uo>S= z@PFQui~OIrJ)b9EJ1s|#kDe^@f8LMH3I5Of@wvhOdE0u#f6qE6N7q}*)+@&Usq2n^ zIQT#H>DS*B{GU4gvXR06sjGJB8~mR->e)N^KXuNOX~F-gA6T$F_&@cFdkzQxr(Rv` z|Mc^Q^-b;PTaJESZnpJ-S?g52&HNv;;nW+=_haSa&Hq+!w%@<;e`@Ca;s4YH=Fjkd z>K!(JZfK3RIsW^Fd9{_NWP0zmzfVg4wVgNf&M*99dv81({!hm%uz!z$|5LLa|EFd? zApS4j_&+ti5dWv^q49s-c7FU{yzzhf{gL^B_`i7L|I}PR{x9D6KehZ{yzzf(9*_Tv zH~vq}d_Mf28o&6jYcBWRZQI}IbES8ot=D^e$5lD{`)SK7Z%5aE|A(CW&umsS|IA*` z-LGBaz2oRx(fON3dhfLTZ<~3&_ip=nd+321y?5E~i#4vg*_+=V@9B1{H}e5sZG5{o z9u@zm>!I;~dOq71yf8OTv@qg-_wm<$)U0~iH{}*rkpL(~=_rw3i8~>-y zxAlDSfAPlusWtyE-uOQ?zK{8T@y7qD@qDcR8*luddaG^6|HT{sr)Irh{GWPfvHw%c z|LOj+UN8Pny`$LwsdpYY8vLKS(3<&w@y7q@{Zg>^VDNwHoqLM>pPG4ry+5ArkEii} zIv(r&;{W1}|5LMG@IP0~^xj||@XOh=yw~m68T_C2r&<5kyV(D!@qYL}UEjLx1!4Z5 zntzYN{6BTR&HH2i->Qe32LHFI*#D{7&ip_1y0z=0J1Z?r^v9N2G`(vz&{GXq1V3Ge*GvCho(BFRbd7>-)=?ib3U&eP|CK~^z6qVa#)&idQ0cjo?Klz-_4Q)Q>YuDzM`(h4XO2LGq-+oWmme`?ml z#s8@}9{w-h_&;?Qn-_)uQ!~#E|EFesS^S?m%e)=_PmRCB|EZZzhyPRKx$uAS#{cR0 z%m1n6|I{2G|EK2o_&+u4)8hZstWS&oQ~x*rm+JXay;D}p4zGBYu7O83sdJArp{;VSU>3x z^XeuapSu2W+j`08k2j6Ke$5&tpYLhso}JiU_MEd4UHR;D5`BJ!5rI5V-mT*V5B zu2`{RqEr3fITs|qe^jiV^o97pzYcx8u*Ldd%W@n-lxHQo>Zr^W-~|I~QDZC53`=HDjxc8-Vt)A?!qpE|My zbenWfHvUiB@o@ORc(4EILGP1KC>=d9p`=+ac>bXW{rN{{RgV5Rw4~3j(=;mIVw^v| zS>49bEBB90^!>9Q@QxbR3I0##kIJ4H{Ga+vn+N#VPosVR)9ux4TcM;QyI+kak1n|$ zd;a*pJ98HYugU$u|1GG$B=|oX|EK2u;{Vk6N&Md%XD$u?uVqv!s@CH^@0`=mh`OG7 zukU|yt*TL*+V^-j?cOo?KOL|BB}0S%Q#TwjJorCdUwV(O(dA#>>epY*=FQ^&^nT;} zFaA&6xN7C#|I~GBR1W@6-MV?h;Qw^|Ok2+v|EFfXdFKD=dRXrs|EI>MGyhM|pJx7_ zI-^cW`5nX`!Dn3b!^!>dibLe-tAj8kM8{SQtzDBHgDnVlIG|A z;HH=Oc79*L|LOcqnl%jmPu()j?w9#LHC_?_r*4_iHuyg^^91pKYUT~%|J1$Ow+sGH z-958y@PBIN?cx8_+>a;f4e-~S`GWXAz5cvD_&;^?mdW+po3%*(dkOx%L;U-9H@pAw z=6d4YCnveSZ`bz8d4OHAk{+;o`<79)i#{)S>F%81{d#1#iq^0Cv|!Y?*}>}#>ryA` zv-A`1kwe==U(f&8JN?qkXu^vhdAGSFBf8-E554ho_&*(we(Kxz3L0IW9lRfY3;(Ca z%i;gj%-6&JsqujLKQ;ai{}*rkpSR5i#Q((`{}*rkU%ZdhdadBy{!h*G!~ew_|EI?9OgQ-^Z+y~=Cmi<1|7`i6gNerf>3Z>C_`i7L|I~OT z{9nBBe`+3&|5I~4_&+s%4gVMK#qSsR^{{={J3ABo?(rRo#{cR0GQSW1r^dtK|I}>9 z|Eaki{GS@%g#S}#T;4kPKXsXnMC1Ro9lwYFQ{(mUf9j#;t?+;9K{n3~|EI`8RQZg@{rJtU zY7@07`_Z-*3ME^EhwT zFFxa~vEBph{^0*~z5VU};Q!RzKj#0bxqtXSZ~OYe|Eas!yhi5#sd;_ze`@(Zy*_QP z%?|!goniC-KDGIO+P}Mb!a?J%^XqNir*`mvX4ZlSY&gW`O_~2wPbruY{GWQ};X`5m zpL+3|$AkY<7ux4x_&+tD_u&83@_+Hh|EYJ{Jco8&x_R%g&*Sia+Rl71{GS@{hyPRK z{qTQk)&s`>squCAKlOH7U-!xDG7FCXt$Fx72_KmDa9eNA|K8j--h5v7(2g|k?KY33 z$vZ8*nI~b#_Tw|p!Twvm_s*Bz2>ws!r)_N?-@eg4uR8Qq18@1iGVix2nvZDf3FH6N zTi^cF)>ExhFzDKr!T)V}yJ-HOdaKO~#Q&*xz57}4e`?m7W&WR<`GCy-i#PsH&HOy( z|EZauhyPQvo-h7S*GJ?3)Q9Zx_`i7L|J3+B{9nAsE7~5!jnDP{_fFk^`kV2;dGq+J&A)gvj}ZT->tVhi{!jh#$6wj{V&8h>{qTR< ze$f0S{!hK%8vm!>XI>Bgr`}+%$Kea#@$+x_a{oR{WZy3 z{!iCO(l1J50tX3zhp9eRAdVQuXB ze&Jom)(alj=Phr1ApTE}KZ~Cy=Ks{J7u@5ErQT)C^UZl;hBxy8ZN2718{TJ|w$IzX z+5TRPA~o*^+ulySVc#JhpQYZi_a%<+z1w_%?eD$D+ODs?_Fr$l0sp7#+iKnq|EFgC zVEkW67x_Q+cAIB}|5G#n5C5m$bnqD7(R+h!H;?7L{?Kdqs*>J+jCpC^>-N1G{NHVV zO$&Z-<*rxpOxZgAvYkc#PrV_($p5Jyf6}~_`9Jlo*RKrzPu;ugV|Kj_efz-H(}Mrg z_MsWi2mhz;l`}2+;mbVVzkjD0_I$c~Upr{Ld9wcA<8GYA{q&w~^Z(lHyUhEk8?P}R zc5Sv^k8QUPG7omM_r5Wg^7?vjeds#ogJ$df{K3+RtRL>Z&HSIu7xjMA{GYv_z4sn^ znf1xN57_)Y{GZOh=E$+&|I};EJK_J-8*MxOPrcUWCE@?n>&;8x|I{07eiHsq_iv-^ zkN;C|vE$+Y)U0QX|5LxXdOhzS?azX12mhz;KJgLei~94a_tdm#i0LAJP)s2(vucPGwS`Rq$e-2_1wQN>8VSj@89@qNzYt^e=ccTkGIo z?pZekFW=B10*Ur(`&#J-$(d;wodao?@f7;IXL;Rn9 z{%kf6i2qab{Sp7C&bOcU_&@b#^Z(d6^;-M;g#WExZ@-V=|J1ApjQ>+_Ht&c3)9(-X zJ^Y`Vf8T)rQ!{@L{}*rkpN_}BkHY`O8~>+f{vQ5M%{+Dc{lJfhufzZ8_{`U{`RO_O zeTctL_Kfb8X#AhH^Ys7{qlEu7ux#N_&+^g=J_%I zPtCkP{GWPP@%%qE>j~rk)bfAv#{a4J^ZSGOKlMI49{x{_@5BG8nGcBnQ*SjNSf|1x z-dk*aVEmu9uPgR{YUT&x|I}M-{ww}Zz1ik>;{ViJ%#Y*$;*I}P;|I^bYNEfsc*7Hi zKJ6|4r}vBepIYnxs+lKv@#@L`dhD^|KQecU_g*_b{!gzT^8lIur`~Dn|1$qiz1=)A z{!hoJ@qcR81IGWUH<|at|EbsRF7kiz#{a1|+P^1if9?x@K78NEQ(jE;wBM4A|I_vH z?@xwbKF8nR%QtV0_6?Zpy>`=<;Q#dXuxdkonE$6b1fD zskbbe8*Tk|v2VZWq9MWm9eE}zc)%geiu|AY^2~FC|5JDCSTz4H-uORt>zwLQ_h?Jb zm@-+x_qEBb5v?h;)w_Rok^j^7KJBUm|EF%8eQxl7>J}ZV1plXQ)y0ly>;I}Vdesa5 zPn~XF?WQq>IgLlP3%;+d{ry$({$1XA{hI~ts4KPYMQZTLT3FWwFR=UqJiFW&e+wfvu&*Bk$*#`od>;*I}{H~vq}>w*7M z54OMm@qg+8_I||wsqvqEyZ*_a552M5x87VI^Z#_eX#Ag=`+@(9H~!DN*#D{J|J1yG z;|Kic`_o?!{F^sk4*#d?rSX62em!eNRfqlJ`}gTyBbqS$@7~?I*AD(q=j+k4$p5K( z^{N&8pSn+Y9c;cK{!iV<{2>0X5dWv{(5rrQ zm5nsg<2&2+;Q!Pex)u39bvK(=I^uXK-;Vz~b5m(QUQX+z*U4>@To1Hu^W^%n87-2Y z2_K06`*Z&M;Qv_f7XPQlU*P}Z&HTT3x2t`9?ms@Cm-Fd;pXahZ?&+m(@WxAg^l?cu zKW}~EjlP}ZKQ#L$Z~WD;`)~G^|MTv(!%Yd8r;Sqkbd%uSL7Y>i<~pSpS>< zAAcC{)OmS5YbUpNtC4&^G_PAD@%aDNslKj;&3}uZzh27vyQ$B&O`YWaxwVo$F11s= zUurk2m3+UqNb!KF^A1yeW$OLIZ^oZbuZGF{pSs?1>UzYf^BwCqOg_H`jgtPa()lS~ zuTuHM`Kwk+dcf2^};V?hz$hQ!`%=|EKG1-Lh%$f9kfa zTLk}i`-jVde`H=E{!h(%;I~m2Z;Yub3OP!H9oJ*nql7Zf7+gvl@-*oBMw z+~E7z-tvd{y*pl5K53XDKTi$p){Gayk za!Fe7e`>Z*Z}f)mj~`rH@AX9E|8#u$zj)*S)T}Rz|BE;NPn}`&zVLtQOq&OW|5Gz> z4*wT#{GYe&kN=DJ>;F99oonmme)sqNi9Y$KecpJonm_DKH2zQbgZW>>zTWNI>DxZv z<&9r^^5eopB0ZS8~>+fKHn>un+x9VmlHf6 zy)1o`cdIK}N8{7-z0Tpxsd+taJ$Z>Y9u5De^WzcmfAPlusqu99KXrHW zcKAQ_AoExFzj$Bs*ExQ^zJJJx^8P&AyU$hG(GQo+_We0txl3O3=6v`+9gpoxKbh%| zrzd16NTwjMS9PurPqhyRQBb2Xp#=Jj1yZK5|`_sIEAdE@iGtoWoi z@5iXZ6W+~i|9>xi%&(7rXVIhH_}umLA4&AYIS+f|_pW*2p+t9>F~OVlyem&1@6G(b zpQk+N&HL-sXU2K+{u*%pSa0rkr&sRx>!t5KFxs2<-^zkf-rSE*Hr?aR{XcijUEbXP zo=fiV?r}|SG>Cu`cPX7GQuhHdbF zb#49<{!cw=_nhGW)XNVZ4E|5Ot*5p)OQy!m0{^GpV9%fVe|o*vyzxQsf9efye-ixP@_uQ-|Ly+cXJP(d zyzzhPo#w-s|EJz<-VOh!-ebNE|EJz%^Xl+_YS!Py|EXDj7yqZ;^WoRQ|LOW@{GVF> zFW&e+^(*H4@PF~f|LK0Po-qDTeaPnb{d`Lqzu)-07oRNc&AdMRpZ3T5efaS2JN5d~ z&369k&Gn7_>E}dG{PxG4di-JYfFD)=OQKs2{??m$eiI)1D$)2qJs;NVt^3!Hd^_{} z?y38}H}@C+r}J&I=ZF7O<2RZAr{mH1KQ-PE|EI7;&++HC!?xr9^n7XjpPKVO zaq=|peEU2e|EJ?^v$oG06K$Vgdapb7hW-1xhyD83+WMLJKMVjKaO+Di2mhyDw`ZTN z|9q$Kzi`7ETkrWs@8Q>875ty}A2wu2bauB(eS2EVmeICFL%b_?ZE5ow`+8UFn;HC{ z?q?nQ`vL!_uF<<$@PF#a<~7)CAKzZe<{vElpuTt60nPEgiN^ow`q+;DQ(T}^The> z)vW((ezCpw&$szM<{J}j*XO<2Jh{!2^JX5P`7rMdFCAmPqBo!4e`@(Z^~7gZ2LGqN=a$vM|EUM`DDr>a z*)xOxQ}=CGH2+WCBWr5#f9n1nX9oYLzH-Qf;Q!S3-#R<^KlReFV}k!vPrd%y;Qw_0 zSKiV;_&;_2y%z@mr-XN`Cxib}%m1lgJG49aKlMJFPlW$d@7Z_6=5bE;UTnVN zrwz|~FSFkt@P9f#UIPE8-e~I`;{Vhy+WQgzr=Dj%0{^GyyS3Q=sSC^(;{Vk7_WK?F zPd#JBis1j$cg~p={Ga-%%^QOMQ?J~-Iru;I=tmw2{!cyNhRcKhQ@82YIokTotA4$$ zF1(n}lf5r}sL226`P6;%>EQp=Y0th8{GU3SHb3}3-QQ@++~EJb&Bx*Yylvhd{!e|v zq$R=ssiTPtga7k>Vs7w%@y7qDPq6ud_&;4wx#!mg|EI1xeMRtp>T_-V;re?{^8KT! zi=%(7KBc6mFAM%p_v^Ij%cDh)o#xw5ow~&4NuJ>yO`aR|y|R2sPg@ZDpUxMV|C@X0 z>>OQhsp$*t{Z`St#gj9mo^vXBm%rgYzF&D)x$^qxr@N|nN7-GXo>x@!KCxp)G^clU z@2(R@u^zqm?bBxj|EKfMvh_6af9j>Xi`V}x{`s)p=BMKS^z$X(=2hbV)LYE&{!f3O?J@6(|BLs!kFWFQ-)lXw_l87Y zx%j4%w!i1vJ$_4~E8KXSH|NLy>HPfrlB~^l`}4!^Re14UZ|48v|MYsWefP*QzMX!q z?*raD&EqluPy5sOKlLv2`uIO}q4|FNpL*+oSAzdjv)(WMFW&e+HJ)#2!6SbDe4DQ~ zZQY~Zo9yS+*oBXIv;PgxJ)Y=cPdri5#s1HaZ{6(Hr+oW%yFUD%-VZzN=NtY{jrU{y zUp4FRp77E$CHLFrb2r~HDbe^py&gO4_b>dP8o!7CQy1)cDfmD2&fSND|5I<+ffBc``-z#nX zU;LkXgLy#a|Ebp%&;L`eU9&FuKegunspbFFo7Zm){!hJi<$~b<)VE)KN$`K?P0J4c zZ)lh5Vg8@GM@EI<|I}G|)uPeA=jZe|IXn2i+|D(lPyW5hyKRSR!T)J{hRy%O|EZZD z$oxNbPW#Hi|EV?qPu;Rp)o9dxJ90+d*FJbY))THVdZ%}q&1B`}gbBAUdz!8@`?S zY|Q`D{bybs^Z(R%Kj#0bHUCeY)4xIRf9l);4TJwv_2B>1+~0nKfAYo$ZW{8lH~y}w`9JL+=IhP<#m|>(-tL>Ze^2zJdH?Y4 zYVWu7`M-L1>)kM#`_->GE56UlX`MD97k~QbSHC6t=CA(g-OoJgYYTt($J6&N`nNa7 zyI}GEcym7dpT6Fh|99^lQLfI{wOj4z#=n)c{Gaykm{mDiJGitzzFk_PG`Ajr7K=;s0Ko zzaaR(&h~ixpPG4o_`i7L|J3+8{9nBBfAMDiAM5ksiI~ra|5M`!@qcRkAoKs!JRkg@ zn)z+`KY1Jc7wiA3TQ_JF{GYmW-J)g5aWt^ccLJy-l+yqW(O@A&;qou`*NAMZap zW&U64`o90IThvLuKbqA_z8_LOU8|Z&|CQ?XQrFK-J$`DZKA+U%rFz5E^>S1F;D4OI zUUFVw>iW8=zB1MSrOxkTzGVFM;{El1>D2jwsq+z2yL#p1e7_6MPtNzl)5XvKA6=zN za(hart_OTUrR4n3%9WGzLQ_3pttwTcbEZF5c=11$1mB1M`>sw&GY^pYf7;&A)?dK? zZE3SOe7%;l`GWXAb#%&!!T+hxF|UUIQ=eVz|I{{aFUFAuwQO3M+zP((X zM$v%EWBvM~hBcz9SZIW42FOP6%H(@&3vR==lYyUjb>pLMr)&C5qb zt%u*`ee>{3qJ?+f={<7b(BS_zy}m4X!%kiDg8x(F#r}HuHs8N%+cv@f>3W#2_U@qD z3bjA$&zHUBR_|O}pEvV~TfCd6w~4M>bhCF_yUb|OX}1)9UbsB?Mf}{e^=|fV-nMn{ zf7;HxJm&wY@o87zd4o6Ghdh0~H+~TRch;&EMLy8hmu3B5b?1zBVg8@Gfq5|epSn@^ zu3`OOb*nBNBi8>_H#Kj@`oHS7IoZMg>H28=pBm4G|5M}PnE$88bAOrtr|sN7=Krai zH!qt1r*74%$p5LC2Z;YuXQ#CY{!h(z{GYmm-Cz8ln(M*;squLDzj!nMPo3MY$p5MF zfd4!`$X{Q&@ecz_I@{J~Dp%6&b27vHKfQnOgZRIA$G@NE3`x_kGm;Q!QJ?DI4HpSqjP&tU$a zy5q%Z(db`4EGWFaLy`A0Plx|gP_Fy`mbY}9rw;LZ-@WW{`fQepBit7|5I~3=KsYT|EK2o_&+t* zhyPRKeei#3JP`g*&HAADzj)*S)V+%RU%c^u>YnBc@qcRe$N#AZnGeMO#k>7?d%W>V zJuci`P5V6Ps>cp*j=yN)wt_!ApBw&r z3hSSaeR8We_q%f5R^Olgsr?pj?!T?C;QM#JxE25X#XIfNmi+e_@75z)@!xN}x&L>J zS)b_gjn@0|@m2NjUF+NF=FW&e+HTyIF zPt80;{GXch;s4^@v&>>|{8jBzixQoF$pXKAyw#Z(%}?~#!{&K2-*3;5x!%n8dtuNV zZ+zX|17>?OzpwJQFZ%iDpT2q_(XW0!%e#loZ^QrT`g>iM8~mTz{?rTpPd(hcAO26x z_2B>X{^fe{f7;Ia!1zBk>jUHe)Xe9@|Eb&A{JBB*q0P21rA>Rgx+{Ga-neG7vBQ?EXJIQT#H&UfC47FX+EU^DTG=I7bx zOMNr@dh_`X{!iOkZwvpY#`kr5s=N0l^Lalk>FS+t^Y@;f`5FE%-uOQ=f5HE)vFC^XQ!g*}f9hwCycztT9{<#y zmxKS){aU(XU+{nG`I`!Y|5H!5^?dMu>KAtI3jR;8*XjbBFJSZk)U1zH=c(G>2km~b z{x6?lrjNKU_Z6G>hW}F+eDZbhfAPlusrTAEJN%y-4~YL$LWIv4*#bv{PdgP z|8#wv5C5k=Z1Vz{|EI>=;s4af?R>+YDC^Jvb@PY#Kiv=f9sW;!#Eysm)BS$MJRkl~ zebgS0|I_}gCyf8ocINlt|J2ME#Q&+8kBI-% zt`GmG-tqpY!T+hZz58*5|5G#XFMY%|@0~W!@3BdnyzzMN?pg1>-9G=u|LO63z2X1V zd_DfP)DpkGwdMsorZ4bbXTA{sr{~Z5zvb)9^5;umdGT}JeEr(zdEU(HvCjv+x4ixq zpEvsPX#4!qd)e`~`8?FGZ-K3+`Sqp;ck2DS<>jN%Jui>;UVq?V@PFFAa(7|yf9eU( zPmgZ=`VYSU^xLlp{!iO)=$0P*pSp4P2EqTSTlH%m{GYmU|Fq!$)b)Ee5B^VWAMOVK z=WU-K;Q!RD2aNxVw|)J3m$&&7Gkz_f=)B>ldY^CG@qf%f!b4WEzh^FJ{L>B{@3bMU z?fHJ5X#Ah{XFL8c-uS)OaQ+FSKWAK0K<>tf8>uuBVzTCdW{yvN% z_3FaCY;ULDZ1ddg`m)rU?DKA$cj&#%JRbf}+t=E>9{isg4~YNM`8U2)$?@3eE@OpSZaM!xv|6c0QHh9E=Jsvin)-YRrVUtP0 z|EaHNT{QnsJ-Gek;Q!PYb$l-PKlSB<#s&YU9(((o;Q!R~9vov{>@vTesdwBQ{GXmr z!Mzs+{}*rO|EV{OyC%&4)9d%nq9XsN-m-R8nE$7K<-lI^wU1}({lDwbk?6p46TNrr zI~e?*_Frn=0sp67Zu9%>_4QtD?>GFPu4nPCeZl{!pD)-G{GWQh?T`P{^WSRzh53K# z?Z@5>{!hK-@R8vE)QfDMkiCEWd{Z}Vh^}9@!~3~yo1?QQ?DAf-VPmx8l6~G&pL?G7 zoA;v8qoXs*zwEtW)Tro(Zm;_DyY!wrqFEQb;oa?uOYQ6ZE${N9ACCTVKjor^{U|EE47)Bb&u`9F28`M;jWF38dQ zee?r&GLP2#o@vvfpBL2fp1pm0bYx;3@5P1tqj~q#^Opb9@wVFf*7!g5j-&Sd#{8d} z^?~t!YTnQL}Uc9k&YWY9)R{MK^`G4w7HeZkVf9lQV`b<@qh6i^5vi${XWb*zm+cy@!os<1OEH4_s-Y;7+o^;!bESp=i*qu z6a1f!x81H6|EFd>XZ)X<*AM@vmj6@Z@9=;6`)iMVf5ZQ&cbgBz|EZbBj{j2^nxDu2 zskhnw_&@bldq3g-)Oh`G``+Q5Z~wjx|EK$f_s9RKx7m8V-;BS{oB5UaKW%5eCH_xc zSnU7wdeZnmHS_(>jK=%^_`ctMEa{#5i~OJVr}2Mk{2l%;-uOSAAK!=nQ#0QW|EJ!u zugL$YIX?bRjTh{A|C5Qv|7knx_2U2Hz2b|B{`zjRpMP(^{dA)7e|o*Q9yk>IpL&P= zyu$yf@qYL}HJ%Uur)E3z|KiR3KlQeP15x^Q(-V#V)Acg%kNJPPZ3V&qsW)xi8GU#2Y=6JW|LOgR|GV||IXPd=X_b?I z=xB1%RHs+{DHm?w!^RJCL70c!Z@7FTx+~EJzSzT%b|EF%=p>ptlYWyDlPmLeM z|HYg2f7LBI)(rFi;*I}1FgmAbo}c+b{9nBBf9lLGwSxas=k%-}{GS>Rg#T0bFb{|S zQ{%hvfARkOJM)0wX9u6e`mjg7GY=T+b>Hpx#;eWv&OBi8c6!`*<^hWvZ+7i><^f}k z|MT;ikHi0|@p0>_9rgRee8BUnzmn(&YP?#~wm<$)_m9Wp|I`=uX&SAo^Sbx2UX7zy zAA8-;mu2$+?|S?V@Aft?u<8@Xz429hpLjFT*FX7|H@=Mde>xw&jQM|R?%#-sfAszH z`ZtYEeEMB)eBg?w-}CNl>(Mg*Pmjm9;s4@||MM>PfAPlusqu37zj%*p|Cu-Q`@YQn z+?)A*_&tC4%EN*du{ON0;AG$~(u_ z1O9n(soX}FW#@c(YXO;HOOur!U`E$F*wGy4xBg~9*f z=kR~(oZ7X6|5Gzxt<29OeLKEt^Xu1n;J0pW%xfe&jWgcGYJhz%PlU^>>|E2o8 z)ay;XzMgjf;@8`?PSTgAK0ej&HLsm~zqU&Ce07uaDpThhrrwX#`;~fq-E5v%{CZR8 z|KUI5+f)5ts_#qngBdn|GXD6~*C(}WoS*b}sa>;j()Z!-;>TzH-v8EBFQ}B*{vTa6 zIX|>U$~;HjFZjRTcPtD3kH-J0YuBt7{GYnMdD%_VA1UlcRr_$#Au5UNKaK*~y!OPJX-#o75{O0Q>{Bx`~ z^A+)by1w)3R0;l1U9Qp@(RDwJ_Uk+Ogi_Hx<&*tTi~D>#&wpzFQQoJXSSFfx>%HD( z%9IKIPshhY+V?L%zm4|`{!gzD{o`Zz`0L01_&+_rCbnKX{!g9Pd0_B=>VZT55d5F| zD*N}f_&@bP^HFC{zQY?&Hh$IZ-Yso@0sc?>=bE2m{amvU*?1dG<59Xz(1^=hU zo8kY|ndz;9|5LZmY!m!nnWt6;|Hr&N{GXcjcA5XDZlB&R_`i7L|I}O`{!h(%vR#&5 z=Zz0+y=SC1-mUKY*LrvC*fBcimunJzV)>Hpl#?6Q|JCt3w9gLn|J1C9%ltoe`}Vf} zqWM2Hz778u?}aNaFKJtU7XPR1+)w5jR%Z> zf6Ov37;larZ|-lrJ7srBbdOF+-`D5=k#--@QPo@D#}D=jHn7oqZy^b3GwFqp&=Ca- zsGuNLP!SOkv4J!J0Z~Dv6G-owB=jatMbRr_R}}B{s@Hq3?cKjU^V>OR-nHImJ?nke zy6f?~&Y5%0oSB4>`LO?C-Y+{b&9i@GN|G~S{8xc>ucYewzWv36V*cNWi&NGAC1u8{ z|6?a-1^u7(h(6Blvpx-6^mvN;zO+&OoHl=cVx2j)`+Rcr^SUoBq$;@PBOjKQ??G{2v>S zhyP>4o5BCFu^s-;-SB_zhW}${if@DeW7Ge!;ep`)*zkJrf9{6=V`F|E=KryAeE2^$ z{U4kDkFE3MZru^MZ%nfKKJohHBS8>JNveH2mX%@&-mk_ z>OjG&B=voGz6TamS>t}f|8YAS{*R6K%c$qet?_=6^%JbI9sbX~Kl~p%_U69o|JZoF z;s4lpe(-hi_>T3~Sg&=%xOLW8|M#ie)>`9yV{UoN8s~%mxgY*Bm9rOF(|J;2v<|TW6@R6IN7ke81kNaa@BmAGc;s4mUzgP5{Z;!|Q{l5E) z*6@DIO6J-A@VxgI&b7w&0oz`%#&-BW9zRxI?;dTRv*V%9YyGS>=2M<(@r*U*Q&wI- z#~MC#$+b^g!>dlddbTyzw}$`Y`S5;dbLA}C4&V6OWlvhe`@#Qlf6Qxy|6^mmBm5s5 zz7PJ74Ic>q$M#JK`aiZ`=J~<@u?I{@RR8Dh)ZZrC_2Bsb{?{aH9DmG*6YcSs_t@m! zyR5qnXsPr6Hua8D|JV1HMD>5{6}#4}|6}Lv*{}YOUGdIw^?$NPuKGWG{sjNW#{9ot zMcDx{biw&~^7+xIBUzrFc_zae^ZnLelx~greuq1yT9=D2g8$?3(eQt4><|CvZumbo z=l`*>zAyYA8=vRE|FKJD-kDwUMHUq$-m9FUL~Fa^Z)qx1=YLM|M7m^ zR~=CQ=WfjZW52awqxwH~VQHEAzvmW41=s&Au2TQUE-ENj|Hpp*?T?+DwQU0Il_!5t z|A)^o)dPyp!~8!s{2Tlqd)KGI`G4#kp9JUsv9Z1_{2v?Z_1-t)Dm&l4&w}&+cz!he z9~<-e;Q!p+^ZrZh`5%$%`@Q)^cK;5^^{wrHfi=8f&hYcBu|6;SAMf`*nTPkP_&@dm z@pS3y9c%c(wl%-k@coE>=+}Q+@0RBW|HsE;z23v!{%Kt=9&g;bGqyjv;MBL)@O1S@ zzq0+|?XI}+bL*OqKbOxtKk;<&BOh5~J|O%b&yV?l@PBMJ@k{mA+fRHV>tokg*PaOaKfXSJ4}$)WU2*(l^?&ZpS+Ug~kL|C& zy~!G1pYVUYo&xcE@PF(g*c*!9B;!vFF4qT&D8`1~9G&)x8UY3BWi{vCC-6aJ6y@4{XC)c>)|cWzhz$6mEzo%%oP7oV2(oX6Pl z#tzNG`gzvTxqg|~nB!^re7~UwM~cVvSw{`(C;l?Zy0Luzf%$(t-(|8s68sUaXaP@ikGtO=#NfMv2Hgg4(lm~tK{#8@;jK&@$$r5!T+&K_q~nB$FaA_ zd@A@qcfe|WzCh+9T4Q}d_&*-6P#XS^T_pR< z^;j2(N09ZIJuSYWq1te0wCEdEcf-+IgTqcZRAtOOo^ldJ~}|0jk~y=6i1+v@+= z3t!rz{*OItS|Qd0wf%==JtgxByI7}pf6i^io(w3?J zV~-gzQ~e+N(Fb0^JViU+hNotz|Ks(noN}M~KX&P~vFiWW`45f8>ub-q;ITV`>;Hz{ z5AVJ99Oj26@cp|rZzI+hx8A!a=>NFAX4f9|f9%pgoy_B0Wc#nED0f==ms)SyzYnjk zoxf)P0r6I^S{K&VssH2kPOGR?|Hoc<%B&fpy`&L(bLz zDz;u%vt9ikk5^JttNxF@rMOi6AA8xxJoSI<*~?bq{btwu`odLC`U3~7SI&J|{U6^? z4?X^{`akxdQA5@Lv7P&8s{dnOv3QNM@{N;rJZItR;QGIz*TjfLs|5-2Er2em=*Q)=sUht;+KVFYBca{1->xFB? zn>MxUyIlO=&z-OK@%`!CH5Kc}Ter9|=>P2TF+OMNSIupE|JX?Ne|-F`*-xndV?VcS zsro;5exOGE9~dnpS$7z*zkJr ze{B3bv*xchi*UP_$fd6A} zf9HMt{msXppZ3V#fBtMV)YI^P+`e6WAp9SD$B_@z|FP@k?@RE1?CtXJGvNOkI_Uq{ z^)jCj{*R68h5vIm{2zOV+<(mfW5fH^A02PKS3KyorFVH6>;H0ptk(OF_#-!ILw4(vXx{*SL88vc(BpNI8-`Tn5)V^@mrga30k{2w2W?eKr@ zhW}%8{vR9u5dM!{Cf5u9$A$+S)@YtRKm7ZMnLl|O{*SK@)}M#}b2t1S8$R&mtc4A) zhs?V@J8n@!%Y484x-a%L{2w0=|CiZhiET$0IZLg}|M>XAkpE-D3vO8Xik+`W_P=W0D(gUHt@=OikB0x_`>j|!Am;zE z3(Kn1|0T}qr~a>`xJ>;YyR@WS*Z<}I*nVNhH|_BS`9%)a|K;{VnGXp6$1W}?avpnl zt&hhm%iH91oUqRN>Bk;%GXGQP`|Oe=^?g%s8|~!%x5(PxwS)RUZtv&2R{bA4LDtX2 z{6BU?YHI#v8uQ;78^?qH zbN7eOhzAVaKWv}%ta!js!)tYZPCQ_!2j+B9|HsDjhyP>4tHJ-Vu|6yOA3ISzAp9R2 z{_nDR?_1;fl+6^|T|8qC|9~;Mm|6>mvEIw2G9~<-k;Q!c||Ci(c(i+bP{*T+y$Cru+3|$X;#xn7M zp~if_b}x$u3^mTb|7G!jp~mxlV7Yie+aC0P?uP$kV}JNRHasN!9~-_(81jGY z?Ch>O|Buc2f9wp|4*$o-yuaaJ|8AX|)!9k-`VZ>?GXJyP*ME8%{*RC6{6BU^W_$I2 z>@@j)1OLZPmG4LJf75REd;A|eu77L!?LxzPu?aoA-YL9ux^?&LAHLox*7F_m{hj_f zBiH%{T=JP8>+9~^JKh?8tpC~xp58p`E^BzFmbcvPY4|_-8u&2yKQ??B{GYYVU+X&N zK5JYL=Ks<2M0M@1{*R6I7=NET#ZM0t+oikHbMjPcte=bdf7}jVi1~kP_(J$UHvA*} zpS!XCFB|?5{*O)n#}4;z;T`VB{ZPfp_{U5vKWfwc&r_Qnc zuR5=h`af>J?7X1=W5Wx=|FPlc;QyX1*{J^Syt8Ee-27R!^FG=T^n2pl+9Y`!{%=L2 z4eI~k-{Ak;4gcqU{IBPE8~%^yhaZIhW8--6e{9U(8-3()yFSbtg#Y99ULXzs$G%YZ zhyP<^{a*M#HrDTj|6>b>RR72Gq2d47&gIwO`YUrddEaKi}ww&?idrL{*UkH?*5?vW8-?< z-_LNp?v9N2&j0K0_j$Ja{r>-F$0vK|`^EUZUa*fp!TGG_%fOq>($)J#B>A1v%f1MV zn3JZSFEO)^bNMBoTc-|;bnZF-GwaA3qSXI!|EN*X>i^i8HwEYav9rYYEg14~;QXIc z)%y*dx-20|Hp18^V;5j>qMYxT&nuC4!8Al3f6pJ9d}EF`akXu-!=Y~Jl?bi_j!8geS59p`Fh;5#~R-6{JVF1`qMjidAe%cPHW6J zTq^#L_ZJQS$A*u4VP#$5kJTya_t1ANueF9h^eqc``kEy**6>R3e|&t5JRkT!HvA;~ zADjMr}7rXL@O@aI-Df;^(^p@{8dRjievi-51D*PWGkNJP_ ze{A|cHvJ#le`kO7e{A0!(atBIyR#`_cg&)vh?KX2!QpN0S9@zC&p?0C68_&>H!?kD^o8`ls2$Hw!6|6@mrm&|DT zly#KcPxwD>hX;iJbN9v;PguhTj=uJBYxqF;KRzF{{Jdw|vH!!DJZ#-l-XC2rm}1>) zLcH_w*$-O7^DX-8KI@bTeh2=K*Ms?y@PBOh&&~h5+dB33XjyM!f_2xd7V7_IHS4eb zFZI@J^?&RQJGQC+V{eqt<77TWfSoU&H(~ytm^t--)$;if{2#kk=Ig=#ef3k6`oBV% z4*~zjE|AZUN^>&;%g06O@2`tx{@=}$)2vHmJ>PTZrC4Kq-(ORc?eSF~oKpYC^Oe8< ziTXb_9uNP=4oGAE9~&MJ{*PTC^ETwat@GvcIr&|@^(Ogz3;vJ$uaVDd;Q!d`>vyXE zW6yf!HT8eIU-!SdPW>Od=JZcG|BwCGufM7PWB>Nkuj>D9eWbtozti7*qyCSbzjdqn zKlY}o8ufqd!>2w||A)^k;s1_)e%e|6ev5!@m-&4A|8c!_{ik0$|Ge-z>)KDgbegxj z#v1-FExwsG{2crrkGEgu(JjCC3QxoTar?egU&(q;jqUw|hX3R9-7V|g!vFF9?UD6` z;s4lJPZ<7>UHehc|FQRr$AkZ4AHw>?;{VvVe)vDW|FB*z{GYqw|F}Qa&xQYEmy0ii z|Kt7@A^*p&lKtWTxIY^Hk6kYF2jTzNmEs}c|Jd|@Z2CXzzkRCyk6ruGDVeW%&>p`- z{9(qty`EmaW2beE><|CP`(1V7r20R0t<3ww{6D^4Xw3g(mmNQ;{*PVyo_JI7e|&tY z?0+bIlbx?j<_WfZVx4u7Y`?$c4eOE*POAUo^TB$;@PF=x|FaJHKX=3bv1>y9kJl5B z&y(T**hSLtf4qJ){2#mQ=zCbN%^LHzZkzOw^_IQ6opX;&vVJ2_?QH6IhxNAguc`mz z@uoi{>m`c+V^6x#r~Z#UPP`xdA3I`1tolE8pJDyg|5*?03(sKt_s;I4{*PbZnBNEg z$G%495y1bkn@D5+9~<)k;s4lJ9~l0ReWCn*AM^j%@O|)q?#BE-tceK!=ZFu){6A~) ze(-;6cs}?)_LW0=tN&v+%MJQJ_SJ*1{_qsrzfV@Q`af>(of##^k8aqW5(TefoiHdF z>lasX|8b*7;CigLtbHBFx8AU2EB3GC{&hQd%ikv*UGovoZ=1|xlkKtGUMBuP9v{bE zCoRXf-Xxww_P5?BenGA;p8Ic>_n%z9HT<9WMo-J}t!rd{pZG{m%lt&^(tYpX{(4%j z#~SPZ%IjlYD94l6&$@cIc!gD8T9?%yQ2&?NEml3{7V&=YfA0RJ*G1M_OAf;uSR9!GGo}@(|6}J4cv}4*JG<*V^?&Tay%u3UVgh?m{6h7A54MO?4|qc==F4T; z_M3)3DeK7&vVQQM*b_rHy=58ICUUGRUr z9;|1H^?!N&8@BIO|Hm#p@~-+n_U?DyQ~$@V*?&;|AA5z&BZU8BFRk05{*S$1yyB{6 z)eYwtFOYGj*80UYZ#X~h*kL{YjW^Z*@p=PGSE~PGZ+m90(`DTudwzFLf7p3<+A-^{ zvfhKdKO1_`NT*wy53O&R{et>G9`B+TRtDGq4ZUA4eeu=c`oE!eUVJ0C{xAEb4eI~+ z_)C@s{U7_X72DMRv9Eh^O>q6+(BrRq_7(Mi+*sT|DQvb(xmTY$ZHTfLd z?#y2+^CHh{=y`8Bt5Yv%==tl^|MC7i;t{d_ue&k-uc6Fx^h%*1r&L5ip zXD#ai>-xW;=X3rGLI211pEDuo|JXf8jB#H7{W>4}YG0cAKlbpXX!U>WS6_Hi{U7_y z*I!lt$KF{NQ2)o?Eb}Yj|Jd-=;@f@v^QLm|+v@+=b@Kj)|6>3^bvOJUoBofDf4>3$ z$KENgFZ>^Sm%JYEf9!)YpAY_zeL!As_&;_{$p7)@bu|1RoBoeY|HrPDdA^wc$Hw}; z@P9o1UYWNG|Hs}f^ZMZb*mdILvOj#x9*=HY^SCwqUB8JlZGX(`ga5PFPv-4m{vSIa z-Vgqd4gdGmm$N;6^n<6ZD`cKu&4D?dhX3Q^IscDcy5oTS{p&fqo?=t+D^~#dGcXZItzWzn(qM8uM+3PJPk3Q1-7KKi|{cMlG<$diU^uy#EFD zd({82x5>Oe_&+v|_fdw zz7PJ7y-j>y{Kl2Ge`(DQ^?y8HNp;Zwv3FJ0IZw`b)%M?6QH#GH+41QAxPMW3 zwXXlmE-xXR197|Htk0f9$xB|6@mqKZ5^r zH~b$vPUg|U|FPrc-)F)9vEloCH}3T99i5~e2z}?MUDjBC7ygg?r-?_y{699l7W|*P z;s4l}PY3_!ZumdmKb;RJ{*R4$Yw&;8;<4cWc>mzf;Qy?}hr$238}t9z@PGGycg)U@ z`Fz8_d&e5*kN@snYs`0R``vri@NE}tM=gNG#+S4bjb7cM? z{GaVF4gcqE_&+v0;Od1Zt%pcwEc(QHu*@$!v*?sHu5ZcWPdy#?(r4E2XYhZ#pXle7 zd|}(+AA2qR(mF}z_rd@1dT@OBKX=3bu?NZXf&X)NuW!G#=a2iQF2XLnKm$L=TV0mJ|C{TU_K3;)N){5{P7 zW2cBOh5us@k^6=Df9zbD&x!eeZ1_FQ|8qC|pS$7z*jZVf)c>)wv)ilxbN9ebf7#b( znw&58O2^Ny-_)#*&Y{H(oh0jtkG-OiZBIyQt^SYuM<#S|_HS$Ce{6rEZ~47X`TNAQ zasKRimUX!I^Y!$4ra?V=%5Nj;X7YdG9x$$J5A}cdG+D3y554u3JN=K!`krIIJmrt; z-qmUJ$arh`K=?oI4{rwl$L`ssozr6eBtN}P|1O=JBa`m2hVO&_qrbs?Lij&6<`csI z(Z66`8|MGH8~%^}1>52O*qHYQ|7YE$z4||Q!~e12*Wmxy@N4jYY|j64H|GDjoA(y~ zKiu1e`?y%SAMX8QI(j`_ym&_U_HeHm?$yHQ&4qVXC-3^U;q&|cC%+c%*}^;g@!|6Y z!#jNcaIfbRU*>-PeOtBlbiX#<`HA74FucRh7v2NH)=$o8)6RRocCG%uxv!Xbo7DfYhvW=Z|Hn>|^%t=IFJIsI zxIXItxEW*K7G~yu`wSI^Z(fJbVtr==>Cy?9Dl3(Y0PBqkB9ppJ!WR|4vslH0BA8>@m@{V_x1fnRi=b zecRI8@3Mx^`|^ni){&8s&Q&YNTVwyUk~^(&yeUWSu#W5B&w2B^+pQB~qnvlnYiM}C zv)hid?eK$r6UJJ@?~NUGn>BnJ{9j7@eD#mX{y3fg$4*I%*ZF^Je^R{qKXzhrg8Dyp zj?B}8|6^yyMC5oYZ8DloZCrh30_iT&08v3n%Ps{dO(KSTXrOlEKOf9&KTG3x)= zDI@!;|6`}$7^(h`P5-{1Uxfc-=ZIH?|6^lb82q2R;s4l}2MGV?Zumbo9uNP= zhEFP3RUgP&o2K3m4gcqE_&+xMA^aaZOFSR^9~<);;s4lCay{^WY}`*--yksKiZu0b zX!-Y#*0}$e|L5Lcet%-yF+XzpA0^g9Zi&Y4U#$JIzOnrKOi#oA@p$lC@PF=x|6}Kf z&${ZDZT5I{-cMVt2T5oAGtW9#eAcOdY_Z1ud+hIxeChw(o$=iU+aG@G)VJ%c z;kTxJv(6em>&ma!dV0&3Z&}0trGN3JHT@sY*ZG|HtiU%>QHK^@sm+e|^2)d9G*sw2m)$8vc)u zr~hNa3&Q`gG0zYF&)x8UY`nkV|JZnb@PBMP9{!Jwd4ceMY|Mj%|8qC|9~-YH{GYp< zG=0n($A|yp_GIyT@PF(GnfC|(=Wh5vHvB03A3No)1oeOH%!x_r|J)7#$Hsg>_&;{r z^x*uzQNPEi|4X?&SN$J*{hmVgf9xWeZv_9xt_b-*F?8zxs>Juf|FJ8@_rd=Kj`vsp zw^crGga2daiw}hV`!S`z`agI)_&;~U|FNrOo*4WeA7A^yCr+zziPk&bKj~!5^jX)- z{_uaip1SuwRR71WmCyU+zioTDwEXVg8lT6(|8akK4fsFy8}fN1{2zNs-EQ@N>|5t9 zQvb*M)o;OC^?&Tuzx}2DkNxMLf2#j;_m7P_+5N`$YnykluBxh1|A)^YSFV`m&y)Fr znE%H<^2w(%U9y$+;m^KS|HtiU_&@e;@qqAu?49D%;Q!dWWPM!tKX=3bvEP$3l^Z(fJ zeei$ohW~Rn{2$*x*dP9njd_9af7~DQ1mXYKr6K>v{n42J#}0@mg#Y9IH6j1!Zumbo z_J{vt?+wlWWA6#g|6{`gV*a1I;s4mR;_2Z3+ztQ7u9JCx-~PAG8vDoet+B>>bnt(C zJ<*$bm)7w82=DjX9fj8Lx>*00`(s`v{2$L(E??j9e{A?b_&;}J{vW&Y-4E3Nv8&!Y zq4WRP0r~pH{6BZY|FP@D?_vHQueVnG3;Z9uNag{_=b_f6G7m>SU$w5n=kwzK_l^-$T_Wp`!T+%fckELC$F3|dQ2)oCKW~ouKlZ)%-l+bMJ$$%d{U1AdSe*JlcIt=( z^?&S6xk3NO?mQ?0KG?3OgLp#udbe&fFgX7YGm7AU;RE6S+ztQ7hR1{db2t2-yW#)X z&1C&v_`f5wNcDg0HiI+a@2c1%CrncR$9}7%0>`)Q>nqSdS8{vl-o5hoMaN+m>^+3- zvFuXu1Mq+B0$D#0{*R4$QSg84EeDUP|6{|?!~d~MWIaRpKX%crHbx%fW#KW?ws z4^Ozlx=b4WkK57ke{A|ccfX9}=Y`hW%EUK_ z|6A28UcKP_WqFu)Xg%Yx;QYUd8{^dj4$he)^9noL_N?}EomUt4w$AOcQ2ihG9}xMX z%$rM0U=NOaN&O%D#$hwn|FPl!WS*iO@6{QPiWj@ZdgWtN#fOczE}3zs`afR(wnuJN z|Ht0?@SW=a`1}i|-KGAIy>Q7Y^?&T*@;dc@?6=CQ)&H?Ki4TDPW4}?kL;W8+U*<)@ z|FQSTJT3S?Ue9*%Ek8%Ev0k)&kMmmNwbn1o_b-_TX&sR7e?L`iu`U;1h53KHU(3Za z!~d~gk@e1Hex&VRyL*@VKc0V6LB9Gw_VXLJssCdy*j9q?2X_5+`324s$M#znh!=$a zI?Vs$`J9*1S-f8TAKRI~M*W}llJ)BU z*yk);uk-)hjro7ayX zp7*BA`@E=OyZFHD>o4*2>hl^mw9Na1|Fg$05??6(&sydsuHJiPLoZva{*T)mhx{M! zuXF2Ue82LsI}Z!`KX%i^EcJivn9N@4|Jd_hc}o2sd(~U3)&H?8w+EbmU((*kKTo#F zeAV1vI#}cVDSy7npIyP9Z!6{d@5aO~*6Oc1b+d-o8risqH9QymA0LnJ*YJP*d7wf( z8vGx7yEObCyZ-Qd>i^i4;>%#8*jT?7|IIFuzaPN=@qESd{T=>~jrE7&|JcRy^9KAM z8|x2a{-3+Y-I`{{$KOX{(=t2_|Ht!l{a-fbufzYj8~%?!FJU|U9~-`}eDn|>f1X7z z^bPa$-EBsAI`NzvJbmrgqdfhOeK%R-eEYVH@ihD&&yRmUhWUT)hW}%8{a<&(|FQSV zJU;k8_8#%{@PBNq_lx;|e12U2mkl3^`G4$knU{-MStP-Xh5uu3m-)Q#e{A?c_&;~U|FKKO zzrp{p%XS@*zfV15*N63fr=>q@T_W@J;Qx3%rSw9Fdw`^JuW*&6Es-!AI`^Lk6_cRQ5{D{Omyb-gpb z=Su71s(R3+=D-*hY%~3pM5eel$Y-pR3OrA^wm1 zi_e1po>%^F@3{*TWmNA55DpS$7z*m%D1e{9@8_&+v|_t{IIdwSQmpWFHHdTjaj3s1lF z?U&YgzOoLZHSWjQZ@>0*=C|KiV}JNRK7aZ@cfc{N{``?oZ)2KX`iO zH-ERzmHRvEn}1kie&U30ezb;P9Q4gUJstVYPu2-?zu^CPJy;(a{*Rq0UtjQl>@4w~ z@P7^6N&O!?Q#>L39~TgtvqLWB2VS^BTqf z{VD5-{%6?de)u-{KX!unLij&=9n9}*x#)gBy-T$05C6yR-=VYmKX+sOUu&5!_|;`o zJpI8x8X6w%z>%r89S#3SFN5`F;s4l?UAn3NW5e%Z{vR7Y5dN>B+j;I^xGxKzPnRn5 z2Hp2Ne4btS`m|Xcx_S0bZ|n7Z;q&RjyGm`yq+z*`!@Gpe|U%QAKu~f`FgbSp08J!2khC}>*@Nm^giG44xiT- zzFu>yu=~}zt=Ip-+qvH_;f?uw?(N~-Ue>R6Z|@K`|FK)g*6RPhx@epFzpfoxssCeR zz9jr#le6;G|G_81|JinF_&;~U|FN%c(MLvmT;s5x28as`2{vZ2t*$)55?sk21^?z(|pG8^?qHW2=`F|HsaXm3e#O|Jd+*@PF=x|6}{& zqSgPo8~%@-78mq?Y|QIh{Lrno9UiZK{w>y6kN6)OZ?^Vlq&ls4jj>M3N_PgI8f`r+ zEyJ1l+fCLPF>%h;W(|$`dhmZde_FCn{T~}%F5#{lY&*Ol{2#aDdg1@rDKgKmXyGt> zf51m(%^70vC-lGH7;KIE1OLbO2YjRZ`&oRN*XPBhdguEkq$PXyPs~j7bolo09+m2y z|2I^gAN*f*_W|br#x(shaQfve^?tolQF&=J?hBu@gr2Q~$^IkBUB5B|^H zTlc&dczI)n`n7&CKk&I-?^;LR8uWke{o()E@Og*kAG3zP+c5X2r=NQ6h&6oLm^p_% z9r@HDYxuy+X1;BW(7Nx~p#S6f``i|x{*R60!~e12`Ci_*$DR-7{XMXLx2Ln# z?y`nIYWL<&Yxti(R`0Ne-+TYH?bZWjfA~M%KRo{Ni^cyn%}}3*ZhDdUzfi-Y!T)jp z44LN$|HsDq&G3J0ctH3+cAEH2_&**G4gcrvOh^1*=zQt&dc*&*hsycj|JcJq{*R6I zQQ`mCn3pE&H(0|*efq0-ztHi~)Blxkjpqmd$L;WV@PF(PvOoMEdzjoG_&+x8H~gQw zG5^oqnE&T)_&+wT2mX(Z z{vhW6vD4)Bh5uvY`NRLQasT1}*g4{N;s4wX|Hp=}-PLuTr{Vv&9bZrIf9{6=W8?M3 z{6BZY|G69fkB!&+qjK?nq4zWH-_$bkey;a-lTz`1p@s+DSS;Qz)QRI`oa7?$exb(e zS9<$QPs9K5eDHPff9{6=V<+96?93kZh&?`KQmRurVybo0r&^VERJ)@k=7JH;83tkWl_IA5oV{|oJpd6MtOjtXRTh*fXbDYb<&{l<~j zITJ@Y^7&5S<%(GKdRz9D$@-(i0x~mCeIM4#l=%?W@C&CN9c25%|6H&v$GTWPKZ5_W z<4HH}on`04dZ6%sydJE_3;)NikoBhE|JXIMzVDVzN!GRRopgrn^IPwb`G3EConT!j z^ZxE#6>sOSk@Cmma^`2k;E?%mu^S&&os5JmGyXEIR7f^4`hG%KVHxKC%;ht$NNG5$KEIN@ZkU0 zyT#wZ|FQRo2ZaA)!w3HJ+jH&pLSJ|OIo3Pnc**V0^0a)(Sabd#-;eZv>|^r$;Qx5O zBjWSm|JeB_K66^%{)2Ua_`e5Mp0=*}@Kg1F+`sz7DV_hvu9fZZfA0Rrz7K17{sZFs z63=-|4E9aB-#;kYC=jHH!yxwy0e(-;6%=?4?W8?c7{2!k`yw;1~J!so& zWc~9#!zX$A-Rj$|D{BMJBOS(AZ^+vMKW+WmlG*q?-g@%wL)HKBd_zYE=l`(>43nSN zW&K}v|A7%Y|BoG$(@*^$8$J;J&)wp8ty||tU_EZ@HnP6(`0p>UhR=il!y1P0g4c-$ zg#T;kK05!;-IZ(Kv+Y;P`okC8zT49yTbEg1H4y6+ueZKpKzEr>xZK)F?+Y(gy>@a! zaGqdB1pJ%z)d_vo|8e{ENx}Jl?08=cyo&8Vd(M;aYgOF7dhrtVf9%8cJ8*p4zE$Sa z$o`ewUVPw){Qc6=H63w3N~Ps~#PazEdrF+U;s5yf3i+BAG=t5 z3j7}%9uWSIU4202xrzT{SIRs;_&+x1|FP-+*xSSpV*Vd{>)vDVRn|qJ`G4G=SEu*G zwpY|1Qvb*8WiH%jxQ7T@oO#*ww&==JIu?Kd0 zQT-n~x5omkk8Jx7ik_$b&$rB{esFmFBAG9jVcTyQGDFsr9b`@a$K$>7#N+D!*snkJ zr20R0$?SX7|FQF?-+}vY&!_m|vFiW${0bhrMg1T9)tBb0|6?EBvt9ikyJX*f^?&Y$ z|6}LNdVyH~myP*B@PF(##Y0W~YL)dHGM}_{rM`|mjRuKGV- z|4x}d2>-_}k@=eNf9(8%t?K{S_e`Fs{*RqHJXif6J9+3p^?y8{bMFlGf9xhNu2TQU zcI4k*tmt^!o}V-SE%kr4UDgLa^UjYA+oj?EZ2RJM>i?`m{?A%`;NSZ?K3<=*Y!kj- z8am|vZ2x7O)&E(``7r;_T09~AANxGHe)vE3IWNBH!2hwGg~9oM)^fe@f7UYZFLT6| z4c9Y&mAv1YS~s5aqOSjI*FWNB^?&T1!-wenKXzOB{TtT*W%nMDrv8up#G5av|6?y% zzgGPpyJ+`L^?&yLQ~WCYAG>PLLG^$9^Q>&o+v@+=RhYjf{*PTL^V#74*qAp5|HsC> zU-&=%c@K{V|Hp>sga2b!hzG;`KX#dXKZgHf!w;s4n1mze+OZumd; zcJX-df9!hkc<_I0_&xYPo*#|*e{6U@_&+wb!~e120pb7H6(Rq})+pi(mG1*WVjDzkZirLoJr2B*5$I^FV_F%`>mj&+S&2xYqmYVJh=WZA75BnuKtf*P*UdX zD_UdwZ!Rr$roQ!t^@gG%^?%%dePN;cKlWSOw(0yo_7+)h0PFv<*REghto@|Nb((m;=ts(|Q&ZbH zCm$)dhTr?wnQ}Wm=JlOCQ(>JF@_)RZq@>o)-)^h&-8m{v{T=o{=eBBV_`j~V)>za3 z@$vma^Z(eGPl)+{>=>C>2LH#7llg3z|Ht-;kAnZ>`Qg9d|JYbh75=ZGdphuc?6lk- zPLcROYdIeL9~+(!{*MhG*md}RPs9K5{^R`cf9{6=W5aL3|FPl8%D+2o&jew>$jg;<9?m|_A_hDYlQ!^^M(8$ z8y*k-j}1Qx|Hn>{^TGeIF+UIfj~y+?hyP>417iN4yW#(=L;la*@PBN){_ub9hW}$@ z{viCHyW#)X@OSWkZ1_9)KXz)i%##!U$4<}bp#INV9uNP=#^d4t*ogz%ssCdq<+NA- z$M$D;a-Q$@Uwi+f;s5ycLI1~23;93xDDl4Vf9{6=V`s_N|F3uc<-2BQs`@>w|J$pt z<7X#jv~g}PXy}BL7S6KXjcj|AucHJ1$NjrST(AC*o!ZUods4c3Jz9*cuj~H29P{_w zjrDci4G)O>i_6z;Njr^ z+ztQ7_P1*7xqpeRy&fyv(}jDxZtXjG9^bW{_w@|-bK%{$mDh{)YVMsU*ZNwoPixoQ zyIycaYp>ty*T%a&+!Ka(_`JS^Fs~MVyr?jb7=Hf}!sg?JUthSd3xEDSulKH}+vB=s zp8MPFnyWnBteJOv^XA_B5q`e^>w3cOAKqW?ucz?&er?0n`)%LqTF?HS+Ir8A^>*FI z3vbNtb8ip#e&O%0o?-JK;bAfV@43VI>i_V5#r!`ud?5T^pM3@D|IqM%+zzh@|Hp>+ zga2cg0mg?zx!_7tp4u;0eA3R^?S9e*%`@#Qlf6TMP{6F@9 zn0WPn>?~Oi8UBwApNIK>YvW@M`WW9McKQ2)n57|M2;K=_y|S7v8uY_xH#2^mI?> zrh0ooqSp%!_a%7tAC?gBG`jAqK;)Wi^?q3Y7yggU^?%v^?0EHm?9{i^jO8-nxy z*omVeoSSa^Byjh|+3Ni=ZtSc6&)x8U?Bvlw|M%L|0qXzI@PF*Yn|e8I4t)^#JTEJ_ z{;c$W54>-kI;M~F?!M#J@MG|Q+<(C6DD{8t9=GEi+nzoq%89E#=IN%jN3G%Y{$72= z)9`=1KKMiUKQ{J<|6|ktvFZQVSbrGv|J;rFe{A|cHvJ!;kMGtP^?z*4yMzB@)Bm{} z{*OK2);RTl?5ta2)&H^Km*D@JU6bYUe{9Sn+;&00whs`mnRR}Rb)5Lg&(5v3j+ga? zA3vwc8uJ+8|9Ct!{GYYFp74Kc`akyIkpFWx=Kry=UNQWiyW#)XxIgfJ?uP$!H~b$P z{tNz(jrnl!e{9T$ga2dW{*AwHb0GVvO#OWjJX!6%o2=pA;QzRP3XUiKkB!H}|FQkz zJ>mb@m{=Wh5vYw?Tlf9{6=W5Ywj|FPjE;s4lpKf(X8@qUBIL&XFZaqZi`3)L9%{t@mMD>4s{D6B>)c>*J|GpXe zknNAYe((d<>67Et|8f6}dlS_EvC}7~s{dnW+?(dKd-*Q=`tnambbjA+Ltxh%ar*o4 z4)X6S-~4)n^@s;=a|WD0+%x%#Yfr=f@%dECdRg#)GBYqZ&rtjj{2v?hH{k!+nD+$#$6i%aq5h9O zZuU&|f9#%*T(AC*z39Uy)c>*nT6~-OKlb+z_|^Zho$+Ix-7DJL`I^mrMm$wp>lK@d zok@e+1n`;TbIqpt-%MPk+mC<79_&+wz2mj}8 z_&+x0{lWk7dIIA8;Q!crq(}W;QN!004gbe3mwB4qKPa&M(eQtKJm&NLQM=L3S0lbD z=f7*M%jD}(=23WBKHu`Rte0h7ar|Sfzhzw(n*Yc1q2d47JLKyd{*PTR-;dz`c>R^~ z`9J(08}t6)|JYbB6aEh~d*Eja4<1qf$L;w17XHuO@PF+3UAxu)u}dqf)c>)I^Vh5Y zV=tKd6h7a#$KQ8H2E2gv@T~6e2i9$JVlYqC(=s2_x@C5(`afQOtATNt-)YaMUC94& zd;5_8W49X|od3729y5y`^S8(e9E|FNCqe(L|G-{24Wzoel5v-b5@|Hr;m{yinu|7Blu(@6Dy>@lycgukm|uh^2W z{*PU_YoB<&DOEgw{%-WomF&`khvn~!j>E1H4+{UsE>{mYC5{abD9_irQoNt+Z(S_! zFRcH|^Owk=2 z=Krw^W!{k7Kighb7xaJJUK*PJ$1W;4qW+J)^yNZ4-vss(PnN0w%Q)j#512FP8TEhc zl%Dg||FPpcJ*)nY9oPLinK$Q8U?)c`Q2)mso)h$c?0fE9iua41f6??uo#Q{>Y`yHs z88YwiPV4H~lbxqiCR-Oh7W99-{*tM;s{dneyYEKzf9zKm%~Aiyes^!R`agEbzJ2Qd z*ju*;=l`(_Yl7?lx*PtFUA|+d`agDQ{dV<#>?dTN&w&@;vi;}Dc6mQoSIGCXc9C1G z1M>cZ|Kt6_&vWp9YANyE+jru?K%g;Qe{*Qg@n8E7**h6xY)&KGOoLeS3v-f^#$Gc+YT+FkycAkDk z{h#gs{A%@o*5c{l|E$H^!T&Y%Th23qe>WU&;aYh={NB)u)~f&G^*Q1L;s30cZg5tf zcaEp;|HruvEyqjy@cf3B^@-vCc>Y%NWnQ58KX!|GYt{d;&s!Lr|Hr;q&L&?*zarkRb!BVYzB)f& z{U5g%?+p4se*er1`9F4%%&)}!KmPes9-9BhhWCU2W0%N$@`sDM`}pT;mH0mS^U@mg z`QZP!9S#4-hKGayV^_=fTlhaV=EK4Nv9TTgkFEdSN&FwXM7$gRn~lE@!T-4%{*R6G z!~eM({*PUL;60uH$F4f`fy{f(^zrANU2h+EUcY~U^=|QkzYZU0jpM`raew+hcC|bn z{*ON|*2v@G|Jb$i_;!yD_wnynX!-YJ);OO0`!Y}WXnvD*<)P!woIgfeSIgh;;Q#FW z^5-S|pS$7z+ztQdZumcTjjX>5|L1P_KX$RK#|!_*=Tj>C!~e1I_(wACxBbzFyFF+P z-`DA~Db{uJ=k4}BQ|<8qnLqi;RgYNL$iE+Z=+{TB@&3j9Kb{XiPh$QbyGp#?@2@}M z>Gbta+WBgCA9NmEG0VC}Jlv~upR&gMKKMVrKd^o;{2v?sug$nQwm%yFkM{@b=ic(s zGj@J7{2#Bcq;9YJKfeB$2MGVi#(X{aKX=3bvCDSsRsZL1_&;{_j-dZ@H~b$PkB9$r zH~b&FQr74FY2qRuf4>3m2mi;emhHvwE%yEAk~rV_v!?pdZFaq64gdFI@e)t}_syl& z74SGHw-vS>^ZqdZkJpQNfbf6pl92y%_ccGhYTFAd zYt;X7`_|G5=l)}_H*A-A)-86d_B8w-_up1pqW+JaR~+xX$YT*qITn)&H^MlUl0(WBXFX_lf_r zPHvsdvg0O-#2yXL0>ea zyYo%mZddnE|JSg8clCelfwEpO{GYp_^r z@&3Xq!vDD&{*Mih2mi;$`nvFcZ1_X?KX=3bvEkw1|J)7#$HwvC|J)7#$L9P$HrDfn z|6}9%!2h`${*R6O1OMl4_&+v$9sC~~>m$Sev2lIye{6U~_&+x0`Cc{699%2mi;W|6|9+ajS|Ht0%^nZN+ z)Bm{}^Z(dB@qC#7$Hw{K|J=P`!k_l_NB_sK&rI=x@PF*&%(l)QgB^eKZt3Dtp7O&3 z_CMUvaf$7nOL808_I@!foKpuII<0$a`E5hpO#Uyqi`Q?3uP+O4$9?htF|W_vn1=`d zM=t~KhxLEioc~8JgL!W7e{A?P_&@p=%)`U{KX=3b(eq$ES*-ud#_{0)*z|wyUi0q< zY&-UU==}$+aenwedK!2;_&;`!c0vEg#`?wZf9{s`H?85_;Q#1ra6b4yc8@k*uhqG^ z*PnH5>GfUVeRZ3bp8MadwfFT4_if?+EPQ*o|LfMm>j8VW^&Y>M+zwi{G{;#VXZ+WAJZri?v`akYZ|Hp>^YxDOxcD$C?Ug`WgqoLb3yIlQW zY(atgz;;b9Q~!5)Nxu5OtFF3A*Z*Z-am5w7{%`AJ+kzgjX=7dgm)-1|%XR%<_7zuM zs_Xxi^i79~gJ?QG5J( z=bq*4Y1Gh87nx_=;St+@t@x`G#~-)*F(!ME^W4wVt#8a6=tN)9(0F~iE}Cxlzx(Bv zJ4+5TtC`q8PA9<{zy{4(bM@&0%3ER^{73*XV0EG|Bu_TUhkiuPO<%?`$nk$ zFY|MY#8h5WX{9cPu zlda+R=1sZBdRRoJn~Tt>Y4c{*T9pFN6PcciCAD4R6-5)dbr8?XM)TD&6s9~<-eF#nH@$3J`4D7$|6 z!e3k7V4WD6|Hu8)($bvwZWv+P$E2h>sZ)kqkMbv~|Kt6~^KF|q)V9MDF5Wl9IxZzq z{U7%apU*cW)$8>JB`12m--XW$#5_Uw_ruKSSWjm}#dsRt(!D=CCj8%%n{w3u;q{0A zW5aKjUiL*p4~S6z$L*PeW7Pk#qeeyR{6BW|js4aC^}8}h{a^BpQR@HPowfCEfz#6m zs`pE|DcYHQ?889s!ff?@siS2*)gvdY(?-jB!s7q99S#4-&XW0p@PF(9vK}n_AA6+u zKFt4PkC4a1|FPlm;Q!e0dhma2tj7!g=k9%#hdup9`627rapK!b-?oN7!~8!!-=uNT zI{%N2`F-$zY^V;=eHekDYl-fAxQCcuM#`cf_`ad?-lZF3d z)Bm{}{*R4$fbf58%nyYBW8?bZ|JXP`{2%)UdA{&}>=E*M!2hw~^)_vvYn>?b5>x75 zu-4<%K5vcrgAWIuv&MYJCN{x7+5jy2}>!T<66gYNXJ|6{{D!vC@1 z1>yhLxL=t6$4;5x*ZF_!)VmVZ|FK6-Oi};G9wGDo;Q!e0e3<{oPQEwj|JW(w_2B>9 z4gbf+{+R#gZp{BYR)pVSU4t zaq9nC%}!7sSa`U``De$W0rpn;{Puy8!2vOL>H*R4f9zVB=K%l5#(Gcie{A?b%>QF! z{vQ0FwaoX!{6BW(v5(aMu{X(jqnQ84&O08Q|Hm#8FC_nM+Y7}f$?vMIt3&>e`(vJ% ztYu@{_lZw}|6A0|ul{epJihVekpWp#SiNKA@eiG-o)Omh@_9P^ANQ}UE>Zu-e)^f9 z|6?ze-;ZPdAN$w8{;U3v{l_1FsQ+Vc+O$diAA9N}x2ykS&zv<`{U7^H+5eiOt?l@y zzW!SMAGaU>;;_YtVeT_Xo^t{iTS?@dbmHI#KzgIk9;o>Xp@rT9N zogH_%?T_v@s)_Y}nHM;8>ZP8ZzW8G6-Lf9<8{00lhDU_|^kv#J!}4BT`wLF{*T+Yi|2#?V`IHu%>Q#Y{2#kojt~FG zt`sjgWW;ARyq?MvLI20DmgB+yu`!Pi{?Fa;e{A?Z_&;~U|FNq-{6zg9yXK=)I{(l5 z#7S8%yUzBnJpPf)$E>!-`#o^H-1>lgJvF|(#2V}O-ke=vT_W@M^5*2ZI_Up+zT%Mo zYv>Qv|G69f&)x8U?uP$kZwvW9-d{BQ9~-gzJEmsyud|8n2c*5$H4{2xA( zhnKCE&!4}2>M`po@h+JE$L&?}`7!(-J0R=J!T+&$$viI1|6|wh+^hbNT~Sr4{*S$7 z>qhl|)-OD!{*QfEdX)Mi^i;>DM~&f9!rKUDf|#jY0TDtj7rd$8J6#O6UKv zTj$2={6BWTL6OeILmJuseRCqz|8YAS{*T>fU|;or=WW88hL8EL%#PIgf9xv;^n-`1 zW?z@oNBtlBl8AQd|Jbd&w^RQ&Bq>S#Uvh35=C4(=hmN^b&Nsr2H~Ynfa{OrPXI8%{ z$GgV*tw25eT@{ay`D$`K)-^%DXN~nE;s3ZlJRSazP5;NP5nm#HFpgaz4gcqE_&+v0 zAp9Sn4;ucDjrmlV|Hm#7k1o&On*NX5F|P{#j}6ZtzA~QYE7^Ax*JE8K^ZsN$qjjlx zKk=K^@PM+uvvu+QcW^(fOX}aoe8>bIzql?q|BvS{D-QZU_VT3#>i^hN9xs6hN?@lB zoFhK1v-Ni^j5UwT^oAA9~|lW_m-c-tQd&i~`~s{3zJ|Hppi`N!1%vEQjLRR70b zvSYjYKlVbI7mE3R?BbCBW0%+0GH(z5kG=Q( z6YBri`%io%_dDOV!*9d?t@>c8v;Q!dWE z+3Npz{P?@>Qvb(xrY~?#-1n{R?>zg8yxwOTTD%|pAD=(w1&V)d*e<>g{?Cpl4gcqE z%>T2Nd3^AH*5U!-|J)7#XD##p;Qy>;{-3O`ZQW_%2It4Ti>*7%UnlRUORb$nYn)ZH znl$wM*VO;)#&i;Nzb!`G=3G|6{|WV*Outzy5Yt zAOHNT3;93xPWkg2{*R6CukZfU%g3J&u>P+6{B8};2mi&*yEK zmk$5OJ|w;l{*O)n$Hw!;{6BWN_&oSO{=9{Mj|Kn7#^d4t`1dC~9{!Jw$HV`*8~%@t z=MVqqZumc*AIF3Lb2t1SyGZ`Lg#TmX-(SK1vGMa5{2v?Z`@;XROU3WO|MB@?eQ5YU zHvJ#>r~hN`mU)x#f9{6=pRQ3 zLgp32|M7aTo-h0#-ydlCdDpfV$^1R|KkkqDe(-=N;P-|U;~+SJ*YgVcM%l$q}J>c~FCOQxOP~>AjEq_12{6GFaYC_Lz)c>)2$2N63 z|4?fC$B4&k@dME;Zo-Q(%9n!VQWe=V!`c^dwY_lN$EP5;Nv8Qfj{9~<)o;s30~&%yt>8~%?CZ+Az| zF?)XScykB7V~zQKMcMCq8vc)uPZl2u|L1P_KQ??K{GYqw|JVZucGdZR>>Tlg@PBNq z&kO(O?yFKiw(G(DiBCD{>2b-QSi}FlkaWr#eyJni^Dx5n|||9E~h z{GYoYj{nND|EqCddm8iq-221-v9sY##s9H!zu^Da@P6=r?uP$k!{1^4pS$7z*l7dX zJAXy|qv3j_J4XCy4gZ(h_n+4Ae^dJWWR3N5SM~nc8lG@RuV1X`|9HOCtl;{;?7nh* z_&;`p93TFVUr+G2nE&T)%>QF!y%4*j?j-{*RsBy{+f->BNp+kCxKX>(TtzUFq4s_jTUw zk*%6LJNJ(F)3?BL^p_`kr=hpjRH z5B`td2!0X%k3Nb1j~(vI!spL*YvuJ^?XU6P|MRcA%=3CQZsUDDy0!57yYTgC!#!Mh z_X(R%7w-9bhIzm64&OiA|E0EU?YaK&4xi^2?)}31fAW9f9uV(Gx6cUohvCl${?omG z`11?z@aqZpi}0cD;3S4c3)r5F5Y>8 znBR%{e}_gDtN+9L*6@F9Jbru8v({K281w(Q9ext?|Jco&2Iv2=TV8#Q`agHW|GB&J z_NQxKeW*zNpYH$DZ0qJ%U#|Y|UsDRz1ET+a!&9|v_`rXCJe|cH|FL^SCp-7Gnpr#bh7$FYi33JBAICjmed~x(&cIPKtW#qXoT@30 zTerTxsro-Y9-b2ZkN5AQ>szS*V>cDg4gbgPBkQ-r|MBsCdj$O-xA*SdTm2t9A|mMj zxPQNX{dE0bZpZvStpCf#d_VXi^jAfbf58`ad@2 z^}+wK;kV%b+ztQ7PKb@t`G0J9t=QKm*!5$*<8Q0STf+;&|8f6;332NG*zjNQe{9T0 zd^6&9dptbk&>`cjW5o-?|8ajb{9p5tr9uDKKVJPGJ2BR${*OI8GFJT`dsx5V`oC=4 zU-&<^KeDgR|6|AWi&X!|#`?ur|CbH#2mi;$@!z7q|9JiIjPQSKcsH#7%l$Eb z5B`taN6EZB_&@g0#GwCUXZqsQ|FN_D@#_EB{Sy;B-@mY)vHSbkuyk+dCiy+vGZMVM z&)2VyXM1#?NKg0g8|CSwNU#4x!~Y#98l?WOTUmh6&hJ_0-W26L(dk`J!~gMk^nYyn zKQ{dzyT7dW3IE5Axh=|p|6{|8!T+)0ui*dqeBrgQ{x5rotXF$c{(jpZ4gbf-!dW8NS99~-X^{2v>>5&qBJ@PF(9vK})0pS$7z*tlQtf9{6=WBWt?&)x8UY`i|X z4;2KydU~LGKFrtK@L;|*Uf)I!ZnMVg3;)Ocv*hvce{4J-_&+w@Uzq>L#=J=QKQ??Q z{GYqw|JXP`{GYqw|Jb-5_&+v$BK#j4+u{G*4gbf+{66?Ucf{*Rp`eapC)?fB^OvCFJ8$ICpx zu}eKY@wO$_@N7G7eaX`;Ze46WR6O3pw=DAX;hPs)!!LHed4Z?l|9E}F{2v>B7ygfp`GD|$Z1_U>KQ`C@bvOKT5;qN0L*6g#L0(gW$`gx$K(Ih zJU;Qn<^K2~SM~}1Pw&5hw*7+7FGazOZfYzMnO{NJ+exxxR{vH5@aKlQllFA4r{ z%EY|j|JLkY7yO^P%04ff*L!F}&HNYqpRK_gJfQqvyzzf()_=nPsrmd1|EJ#i+JWHz z)SK+{C+7dD3v2zKx}?_sd7Iy}-%b1e%p1f1X?vM9^Z(+F|5LBG&%g11d?xqhu$%HW zn2*B$oiU+X@PC_X{hzvW*S_HYw13%_MDTy=#}_^w=KraSR+b0w^E&_FbQT5&WO}HCz9e`G0E7|5NXI z?_ltMx<2_o^$y#PtE*3{GVF>FW&e+HS_!M zf9ehId>H(ndYySd=KrbjfXx3>Z>sfwx?URpr)GX%cF8}gbU!&B{!iQSfcQW42HTGR zQ&-vg#fQ~7Sf%HyFkguOQzzc2@qcRkA^uN|Kg9pV8~>+HnD4{?#T);pmj6@B|HT{s zr)GX0{!hK$zCQ4O@y7qD%ka78|J0@CbMb%PuhjUzcr*V`z1TkgW&WRfxji5LPtDgW z{!d+O$HV`r3toHE-fxd2b*r%tcr)J<|EJf3#{a4De)zw5+k6#o=3C+a^!n5IKXuX0 z{lWjKi*3DD{GWP*%_GA9sn^=)xpi#)U-gFd8-xE-m)PfZ%>PrDE`2`uKlRKTE)V`s zJ!EuN@PFzKUFrt^r*56wA$s((GyHfRdv<31Ztr%zy9EFD(7*G85A4*xYw&;S76ZEm z|EF%&KP&h@^+^M|1plW#v47{_|IU86d+>k9_R9|bPyO3&9r0(C>ZnVr;QzccS_J>+ zZR`7X8+(uMfAo-^!T&XF)gySo?CYin|EK-WpZB62zq9ZE@Uo)d|Fr$Z#FpUy)JxWH z;(RL9g*M-h`G4vawf;}N(!2owQy19$9`kTnYUVlN|J2Nn#s8_9H;MmK7jE0l`E^w@ zpUTePyTl%k|I_u-_&+rsmHB`1#{a2{%=h8{bbK2Br(V6K#{b0||EFgCU;Lk%d4Tvo zb=le)|EDgkuJM0*{=&kV^?%h5J+v(NKlPNGYy6+O|G?S7|EarW{U!K6b;s5<{!iVr z<*eZU)P36A9sHkqbhlfA|5IOk_G7{Ssb@~RBlth{Q;$C#{GWR3qxS~?r(Sa7<-z}{ zOQ)P0=KraeOd1;epZclWuL=H7{r1{|;Q!Q1%SwX(Q?IP52>wsKCXtAGZ+|pL_qW96 z1KRr7-qqW7M$b)t+I!n8e~kuoo$tNDzQ6tJ4=*OQy&t@{zGm}IZT_F0Z;P$pi~mzs znXkI}oi*N-HlNStM|$H=@qgMM&x8L{ z@PFz>E0zcU=l$fv!T+hx9o8@SKRw@Z>Ft95Q#TvjH~2qwG~w#t|J27$n-lz>I=cJu zsQoG5`T755&eOsF`Sv-_2LI>%;Pb)%dEfthnE&T(J`n$>KJ1~Fg8z#*{!bmveKGhy z^=}_q9Q>cU)4dCW|5K;WSrq)Ay8S)R2LGq-G-pBZf9kv$_Xhu`u6N$0!T+g`8$B}k zKXufrNAQ2@GkfL*|EHcX-o#gqv8MJJ#Rx# zZ#>(#i+X#nt@VG}f4e;&{!hKlw&VZQ{QO}4pBlf8|5LMmFaA&e-eP_-{!h((K>VNn zdx`mg_&;^|F1x?x|Kg4RQ{x-)fAL=Mz`2KxZ`XhGwdW`Guu&7dxj!wtT$t4OKb=3@ z@qh8g|Ecl(_&;5b{GYnYd>`xosuT9_J=XtKud}}wVEx~CPJ|kM(u8-FAm}k@-CQpSG{Ge-GjR;*I}P zh}fgkN;CMUl9MN#_M%kGS{1Ve)vCa z$NS;`)ObMrpIY<()bfA&{l>al|EFGS>-FOQKIo7e{9m#Cy$JqK&3wNmt^eZ9`oH^5 zf6TkUeBZRAANMY_zb|R^ujGE?;JicIZQfs(FeeXIEIg}Kjq7nIcaKi%(wvWhVOPc8qaURGS=|I|y1)lBLo2zZ~k73+D&_r{6bCzv1fO|I|}27#sYbem~XM);DAQ zUv;aT8vm#L)BBte{GYl@&j!K&squSrCzRz58!;ewzqZ|K=KrbN<=3qLtHuj5|4)q< zWd5JJvw1)KpPKc7@qcRhKQ%rG|EFgCU;Ljs$2=VV&wEhIs9@8E+&jzr2k*x`K>VK? zUxxovr2cxy z9&hH?ojhc(H|N`R@ILPW=Fjkdx?URpr)K^f{!fih!~f~^>@lcC@PF!_<`40IYUT^# z|Kg4RQ{xL+|5uIo+tllAe?GQ<)$<+iJ_A}t_&=RbxE}L=YOWXm7jOKZTK-SX{m1{s z8~>-qTQxu;|EI?9;s4ZlIsBiR`G5Goc;o-nJpPNe|M2GVC$#;icb0j< z%r^h>&bHrQlX82ldoPtE$i_&>G$U%c^un;s|# z^Sk8#)LG412LGq-(WFK6)Q4C3@$wrriw3W~+B?0`nbBd-UgMqCuu1TLdVJdk%_97t zx?MwiznK41Gan8Ar)EAH{!hNBQ;R07&*{zeF#k_p2_G20pQ-+U_brDf0+hH%Ok}mpb3@ z*RG%UXZ(J)YnbfaQvD>aXMF$E^_o-fUze2QcWIG4PqVXmy7=)@*K=-`vOaXG|NFI0 zo&Wde=4U27-^neKpTCv)+4%V|&o8y{f7jG24*rkr_&;@XTTdMSr#`b;&HBIIHm?x> zr)GU)*8f$r{xtLd)D3Mu8FSJfAMZ;{!e|{X{QDM_hwpQ@PGI| z{GVF>FW&e+b;ILN4E|4D=a^%oKg_$`x7YdoAEJN$ZhH0PL2JVIqvofcW}bVRcVz3w zTzL4c)jwUdI(Wg~_v;ZAG@0t%t55gnm)^H{cemenu>P<1$1mgm9 z;i>h5|5KlK{K>)psau|Ka&-0gw^k?4C=Fh$^BIk!=Z-zpc+aD^-|WY0VePq&=+GhfKehayo?re?+vWe%%m*wRdyOBTzU0QMy;UE*Gv5*ar)GU%{GX0bUvbB1@1b`6Pd_^U8sBkG%SJVq5u;;QjD>2iv`snATv3d%o#y-}J_doz~_JZ}!LkY5%t7 z1@V9J#{a2#JpM13T+(&%^(zhu8W) zHS7E0|Kg4RQ#0QW{}*rO|EaUg2jc(KUCi6z|I~Ot*8f%GHJSgX?quuv;{Vj?=Hu{x z>fYzn%>Ps4=kR}O?jQb7&HcmwsYjic#qU=VX?G0{es84RKU;snoBf}@evLQB`}=jP zz43AQKRq5lhyPQvKmIS?_`i7L|Kg4RQ*(U$U%c^u>Mph(EB-Iu_&+ti3;(CivGc?K zsd+s9FW&e+HIK*tshLNI|5LLa|EI=};s4ZwFU$@8FW&e+^(dP+hyPQLuz7U&KfON8 zm&5<5nJ0(;Q;)F6GygB%M@*dO$Lo1X*Wmwj{9c#l1plWVeQAF1f9jDJ=S2^H_ekPz zUknQV3;(zDyN8o{!*>sP54HJ$2flmId$7&d`}=nfcr#xQ|EJ^AGta)?8&CW8S#!Pd zeradT@n$_`{GYCmuP6LpyzzhPOj|!1|EFeu{9nBBfAPlusqupNKQ-@X*8f%GJ@J2P zt_S}YZ~UJc|5!Y6x_2*|e~ACnc0A~T=Wp@rr5{{ylQ;7X@qfC1ea#o*|J2;SMbBL8 z&HWqy^wr*j?fdN?p1Lxr@qcRyJr5Mdd2?Ng8x&mw9lXOE*_jv^LZBY|7=EI@PK$f{GU2u9s>WT zuC~wL@PFz(=KGlcr`~DvEAW5ns#^c2t~M`dzsvUR_$2(Fw$u1Ob&+{O{GYnmj)(tK zGY|0K4;hJn_UspL)+ne~V6?G@|EHG!i#PsHz0JH`qpF{) z)LU&n-*x}|mpA^8`G2}!o8JF4_&@cQ+WCL#&2N1e6}a3!-empm zy9cWDexuveeam~T&G(x+?yuf>K>VK`ul0Y`6>q#3;s4^z`oHmJ{ac)u5T7w>&D_&;qgul0ZGDw`jO|5Gos`GNR9^$J^$82_g(wa4TC z)Frk)IQ~yvXkVZBzj)*S)TQ?IiT~5|@qh6ib#R35zh&cQK95go`+VQKDp6tUG3R)%Ub8APf8hQ6 zg2(X0-ZN+1$oB{DyDmM8uXpd8#t({Y{ci7z2HJf3?SJ&Xa6pdTpQF6_@14fS9_HuY zzI(d)$L}k3Jq>zf+Vy_q-EvTm=*R!QT6xL)J%T6fHE=-ie+9Sn3?6XssFC=yO7*dm zE)D)q-E`)R;Q!Rw^Pdg=Pd&V(2w&%qpJt!;GXGE8XV~ZA_&+tDCo}&~U1qO``Lzml z>FzKO&l^92|I_v&^G>#Zxte)X{7+qKKE$?XsqudJKQ-PI|EI3BpC7irH|wF||FnI5 zt^ZS(o42s*^X<&X#sB?$Qm^12nJXb%}Wn z{GWQ2c@g}dddU`i|6-$%) zztdKF>+FZu`|)V}pPs*D*Y4o|)P>t?{GWQYc}M2| zsaIB42mhxoC|DBwpL*J~DZ&5g`S0uBA^1P_B~6bF{!e{`{k<{s|I~Gd4G;cL9bIs3 z@PF!KuA3G7pE|np@!y$3FW$`m^SP_aW z{`H3@{`@bP$7cSYexAIztH%GSSKIq>>!;0g_4A0v|EYOD;{VkAeG&8j)JyH(6Zk*< zyr=Ph>H_=zi~m!v=KHVtKQ-@v{GX0TGyhMG$HV`r*VXzzHTyH0E#BBG9e<5|Kj;5e z7uxmU|I~c{$N$B9`d58&_3t0%9gf}GFR9zD8Q@)Qf3I-VV}rc$c<EE|_LHwUu{x9D6KOLX*!~d!AclbXw+wp&D zwjWmKV(&`pxBh!cQse)0zu1od^T#t^(dPfDnFoyji#Pu7Q11)=PmTBc-Bs87^_AM+ z3!FRjM(^U<^?$X0p{?)B{6BTkmfd0fUv)|C{6BS(&F{nid7GDI{-1iy#;x}EPBXoW z?cYE6KV9#dgnhl4|5F!Pf9jXb=i&eK`Ykb^hyPQ* zTy5Ua{9nBBfBOA^{GWQ2&G*CqsX2fAU%c^uYWY94{GVF>FW$`m)9*Jnnjd8SU-gD{ zn}h$${$sb`|0?YI@PF~f|EX7*7sUUmSD0tU|EbrQ2gLuy8~>*+DqkDj`PvgnjsMg6 z6xh5!{GWPdS&jeG^{gqa4E|5Ox}+ky|F-A+{wygkk1DR1@4cv`Bx3zvy&lVoilP$- zKkwU@tf}#TI^MEXHU3Y%Xz8-x|J2JDza0FZdS$KuQ!iV*h~F>g>i17`X5Ssw|5Z=D z_QK%*)S2xY1^=gRmwkL#|5u&czsCRR_gAd<%ltoec3zGDdv4gE;Q!j?pC0D_sXO$j z8|MG1^Yd%`U%c^uYWY94{GVFu|Ee?k)%ZVkn$1_k|EZZrhW}IJrSN~FN(Ki1hZn^E zsqsblKXqU8g7`l*^8uOvr|vVfZG`_*j~voA%>PplGw+7~)AO@lEdEd3ZFtMz|J3+0 z{9nBBfAPlusk__x z^?&hyYP=%;PtE0kTtxu376edFEM=I!DCbUq#I^~L|G``YpFf9l@-Yv%u{dzz2K z|EYToXd34Kd7Jmc|Ec+U!2hXp2h{jKH9imj=Uwan;{Dwf|M9O6)&m}U`Ake-apiM zmwM*^l5Su^!WBong;);W;iK?>>eja2G5$|psI~bg{GYmQ>obG@lTXTQnY?~- zst04fVEpx9{nL17oRr*|rzHEoHm97Fw13CC$(}QHzFq42v%lv1Qs>*H&f`niW39=Kp?eecsgVsot<@^W@j3Rhwi#*S<}%m+R0r z*^m6%>)$kGJ>ljJlf7uF_p4Vg`TnHN15DjNb^hP4t^eEJ)}xKTK6pR;-w7X<1pmkT zAOELr)}m(qpPKc4ng6G5)~Igqe`@(ZZ~J=0|HT{scj3Q^ga4~rw{Gx%YP=u*Pkn}Y zywA7HtWNw`6#QSElWP25yqW)}KKYNwhxvcr$JY42c;o-nN1gD;;Qx;QeNpg#P1?2! z^ZzbrSQxzD(C$5h|5K0Z(=Yfx^~k{kga1?K+k80upZc_>zl)CEeRH*r|9e}G8~<1K zNonwa#~yoZ@PBH2BlG{%%}zco%>Pq&w(pluEWgFKw`kQQ_&;su{fqz8{bs#i{9n9> zZoI);{!iQG|8zY1ta{h^{_=m?AJ2#Xi#PsH%{)K+pPG4p_&;^4w6+ocPu)JV#{a2V z4;cR!Z~UK{`F8j}brQ54nwHy(AU)R1i zFYNMUH~vqZWAo(je`%sV+xpkt>5Xsu`1Bp#L(j>GZaZyzQse)0 zJl5C6|HT{sryg`(&HBIbX8xa=`F%%E-;kJb_t4@p_)sG59}qFS}p(zj)*S)bf97ULX9Qn#bRHQ<*;>{qB@fZ|+y;DJ9;le{6q0 z={@v3^Uvo0bbZ6jbK?KhTp#`~-uOQ?^Y!q5YF-ST)b0B@-gsO5pY8|mFZ`e0 z?_JJI5B^Wx(YE9N;*I}P<8ASO@y7qf8~>-q590sS_(A+%yzzf(ydeHh&3r-ppSs6{ zuJ+&m)BJk6UyvQOdhymnZTAEJr|ac@;s4Zl)8Bq}gWn%I{j=-5d4Bw#_NVcGYVI%o zFW&$CY_dPT$NAmt_d%1q^Uuu<{!g!8({b&ipSO%jv}n>J_`W*!_scJQI?8*Zt*_Sq z$dTT~yEcXSf7-uj=f2?o)OZN|pPJ97KD~3GH|t;Bzp%eI^Y!q5X8M8;r15|1Ew9$B z|Ep#mApTEX_1e2({oi=w|J3q-@y7qD@qd@E&-C*tvFAJS!_M9b>vNX?I zyU4ER)8{&R6ZZK#{!hJo&wIiDssCZ~|L}k6Uw-)|_&@c6 z1q*`z<1;|~-))Ou4E|4D{K0|X|I}}P{6+A8>bK1MeR*YlKmMBszYhLS$KU_nr@{ZJ zx4rpZnE$8VZN3lxr`~Go_u~KJ{hOCh@cV%WT)O4>q#l0oIB$I4e|~$c_a^gn3mX64 z8xP3(zdAni^_c&suC~YH|KiR1zlXYJ{$ITDe`=l&|EJz)eh>eruC87GSN9JO$oxMw z=g0iNc;o-{_|n(k3;s{ddcXKTHP46t)BABlt^ZTwB#Onuw|5M|q@PF~f|EY`3_u>EIjsH^@n6H}p@O?>b^Gm!J+4rl{kDTSb%#Mfu z)9cB6K>T04@qcQ3GyYG_{1{uG&YSOlg;UP*=JRs=pY~7K`iA&Fb;X9we7^5pX+9AD zr|pH63H-62@9H%Ld_VD?_r&9Nf6w&3ch22>y?alZd@*0Y-lHd768xWz-+SDc;Q!Ro zhyiv#B7gp9yhn{Ga!j5yAiEZs`^LUv%#IQSO#amFnMIbxkz;!D8?F z)20Rgchtn*!3Q?G`)+(wrF!~{_Iaeu|5HC!u^nIM{gTbM!T)JHjsH_Gwe{rie`@A6 znqR9>ud#Wp=Ha|+yx;ZS6}!X!<=UTlX#7vjJSqI2n)$c*KQ%uO?Rv9y{rJH1C;#BR z-h3ARPy4U6pAXFcQ{z?efAO~CA8LDl+5PdZto47|zjR0NUcS9-=U;>W({|=p;s4ak zufqSS6XrGWf9mpW;eL2m*ZMzgudwxhyNx|MN4;Xj9=wtFz4tEVdc7x2S|0qLt=Stq zW3OKK1plY**6lHyN7p__-LBo8!T+f zo!(!rUm5(Lj=yWyuIQ`gbA9{%{rl~HJ?LFw^Uj$6r~66c|I}5selGq`y>{O#!T+f% z_rDVSpSogSmE4tdF^5$Qo}vvwgjIv;FYz%Dwsiw{l&=oB3k+ zKOK+8|EWuN?h5`-U1lDT`G4w_n>Gjkr(T?>@qg+KHZPI&f7Q>~_dnME)&0Hyrb~nW zQ;+YN7W|(&N^cRJTK1Vg{^;%*_IiKm9rYa?T{He$@1xJ2z}LHXbmi^Q_MiUgee~=n z?fvkRcl$g35;c0}f8HHtJ%*Rf)%kY5^NA?;x!-tqx$8-LzZ~J+`L21<->y2+JHx!8 zeSLWknekxsc(>ns54+=Gdp{lPJ^F@eQO`g9(L3+lOPKeXtM5nApaIdmD^EDo-ExEf z)A>btY0=ZGPxiG_}Ex-t?GEp561tgS#KSSrN(FTZyWvlCShJ}(J{S~8vm#5o6NK0|I{1JyW{`V zJl_63D_8%%{di!I;y}4fI|LO5G^Z&f-c%m3;9Ramt#_&;x(Ux)wm#?)bfAc z=J#0tH{STa^JaGsfA3gbJO3}<%>Vn#m-#j8|JM4yc;o-nn*SGX{GVF>PrcgK^Tq#p zmsJP<7jM@8)%mV2uL|q`#+&(n>XOom;Q!P`#bv?&saKYi1^=gJ{@-WkEbzxO{}2DC z?Mn(*hxvc%MXPJp|5ZO;LNaRq}u8tlo`-|5Io7Y82-GeLZAI@PD0p*3AD?r}u6c{GS>> z$oxNbPJV+h|4-e)9?$&0cr*V`%{;;rc2?&$DI6U9Ugm(t(JkB8#=1%L;nsEDc%Xh; z)_ddq@PB%|{GS>>hyPRe9NH}SKQ;3L@qg-WL)%1?n{Le=f9l}ik@^pA6P?gxn>X|C z?kwN#`{Vz^c8s${2kzIihIpRSk2|Eck5_&;?|^KSS*HS_ZDfAMDipIZJ; zjqiJ_|7*UTGg|Eckb_`i7L|I|D`{x9D6KehZ{yzzf(9>2-_pBfMNMds(;!|nZn z|I_{BeDHs2?%#yYU;6%o?EQF8##i3*e>y&m|5I!JpPKoW_&@a!J0AW|J;*#A^Z(R6 z?dt{qr)E82=KrZ#9~l3q?r(k&|EI?1G5=4EAH@H8+wtzX>fio;=J@zOeZA25KQ-rr z|5LMmFaA&6)8+y0TlC*UUr*-u@PGPx>udfO|EJCy&>;9fHQ&GRf9kY8jf4MFH_tvL z_&;?{hcko!Q+IBa?EQM0--&;Io!b2xC(jQ{ZTUa>mF{Pr8T?pz)Xbm5|EW9HuK%m& z!}sC;;*I~455foH|I}^GPt9t7i+8I3N}d0fI$y4N{baw_vTm~1Ozl?n3=GBQIksz< zJl`?Z_i?}D`=@s5e7r#olJ_4_KiR{zOL>2!HXbwne5sxK{HgO1Q$1ele8BXS^{hKK zPQHJs-Z6E3-_-eosU9$OJ>8b(JLA`r(K^}xb!w4(y{YpbQ?EDG@1^>_)UHz}dH&%^ z^^;%kKcDgc=L1vyW~$F*UL5|f=%upY|C%?i@qg+Dt!w80sq43F82q1_*N^#sYUVdG z|4)q%#Q&-BpZLG6<)y*@vA!|u|ElZTyi)w1n)PpI&pgy&{og+wYS!-^y$Pd!jj+xo3zUa^Z(RodA-B@KXvQ=eS`li+*%y`U&hGc!T)V}rzrTp3vK;T=Krbl z>zy9_pE~__hX?v&R3ao3?Eg{GYm6yVk+~>3(-=-#Yj|by|luVg8>wy?xF6KQ;5u zmjCZMKOejv{?E5tv;METi}^bIpPJ+2|I~Op{GU3#W82{W)Ga%;3I0#rwsVIt|4%Ld zr_So!DZ>A$@m~19c;o-n%x`1Ps4>+pZNzj!?SpPKuH|I_|7 z^Z(TB&-_2_-?e?m;Q!Q}vNEF%2haEIY1vu9|7kn(@9=+W<_F^c)IGao1^*ZCt+{9U z^W*oXoITzfzlQ(Q`StCZ8~mS|2a;c@MGQ2jc(q`~$jX zh4p{ctiOx@i#PsH$7elZ{GU24qeJk2>ZWNOqZdjC``33%^M%*EKFFJSh4Js#sf|C3 zZ_n?Xmekyz`1ah~+@$W(t9Mf84j35x-vu2<1^+jAQ1{^f)cyPAhWUT$p2OM)|EKOX zyhHSU`TL2}|1vUoKm6bC-hMYRVZ(^v`_jhR_BRfAcN^CsTHW!T#Hme31m8yw?C`dC z=2@MB|I>En`{Do8n*SGX=Krbjf%w08E4tjCQ1 zQx7uVh5u9Ye*FBK7ybNc{GYC`vw1%JpE|>ikN;D1{rEq1#yOpW|5FdJ*9-rr?q^@G z^S*t?yT5%s6@2@&cVF|p_&=Rr`|~;m{}*rkpPKuH|BE;NPtV8KAO0`i_&+ti691>p zvDdeB<|B!&gNKFRk9E8tEqdsVhrK&ZNRKAXddQpS?{VjYNnPiz2fXF~bbOu<|EI*0P}`RP<| zz8>a(db2n8bN{DPyfZJ%4*pN~C(Gt5;{Vk77v@Eme0EJzU{H;&tzZXuU~8P==i@oe%mYfzjo#+@qg-zre7cYpSpN&jsH^@*yla0{~K@o zpE_Zm|KR`BYis?Vy2$1srETi#+iCot&HM`bQ6Z(a%ir>=bCK=6O+syE+_?oYJ$?Nx6c zh%yee^{#lG^-&lzL6xqr%C_VG)Xei^{-3(a=K10O)D`9d@qcRGzo)&r zJE`%1dOmzC{x9D6KehayTK-RshsFP?nU9J8Q#0QW|EI37^?F(VSH0G}6aG)V&U_vI zPrb#yKAHcg-fCZ8%>PqY*80DAA3-=A*& zPuthn{`UE*_bT&$wqBbz>kZrd7jM?Lw9k{hnZJhr)7Kx3|5M`u@qg;dt-FH%i?@BY z>c?BNZKrw6uHFS(wg>;`=W8AY|EFG2Rv!GHn)Md(f9f@*CBgrxmldpH9;a`gzwpK2 z|8zc6UwkR}KlQB(7vWzk)ial_u7A?q1$^1j>Vqu~Ee zTG1!?z@$Yx|dLJI()e{&)%Vd|AnTUACI{2mViuf5-oM zn-{Fx_|&dyJjv__GraMoKmK>5Hy#lGr}M#Q;Q!QX&2upSPmMQa{-2uXXa1j>^&0Vi zYCItRPhGbC)!_fsCANOB-4EZsZu9;y|4-X1*X;`aPrY*G-r)b#@_*{fC#^8A)*wgS zEoY{kZ!_;cT^=!y*3P@1tp{wculLXnciX(Vyqv|K^$mXT{QSp*|5HyKeMj(r>MJj} zpZAMDe)4s7b|cLo2a^Sk}(3%UQkz3BRp!T)J{>69_S|EZTu zn;iU~`frJ)yk7qJsvX;d|I_x3`}YO^r(S8k5C5lLVIBqlr!KL1XxqPiDo5`hdP?Fs zZ+u^qIWKtQRqgA|8}B#0*-~%(YMZ~W@W$)m|MYx({ow!9CHD6p_&;^A&CA07sqruP zKXsXXz2g7W_$}7|RTtXh@qg;o8@2@hr)J)gy+3{X=E~~e|FnIhc?tZVUhj?1J`wz% z`sF*O1^=g>cImj_|Md6^2j>O{!e{$>qfl)y`#3-(XpBT^!rtR$k|c(?|$+= za?C~1q*s6OKJMJhSx-Gzuh$XhUmg6Pj(^m|>w^DNM`vFW{Ga#e3xfYspEz`U@PF~f z|EV*&^^g8G|2TiXQyaAo{!h<;YP+_<|EZhh=0sPGI?4ARG-y!pe>&b{k3AOrpZej2 zOM?GXFRoY{{GYm@Y<=*5>aum)`Fi*Bt1zF9|I_x3w%%%!IgS1Km)ZN7`F}dU<>uG$ zfBN}SVf*9%)Oa@hpPKo1_`i7L|Mc^VpU3#Wc;o-nD{Our{!hKy{+Z~w&Ce73pSsY#|KtDEtL=QTSNi$Q{6PM1HS^W&zn^mT z@59aZ^=^M(<-N(y*XFN#^YaP+r~TL4zu)kG>hSjs=Ks_@AO26x`os7?b;8y=#{a3g zzxLmkx%%%Zo^SNxao+g76|>LsX1(2a-#y14U%Y*Pl(F_aZ`M=B|LOS5`@{dmJO9Fq zyygFNe`x%ln&%&I)MVeEe&O@Wy_pyM^Y$yfnddiZ+11{BKU+Tc+N8$+>3qt!?hgJ> zT~_P=)RndVPv=u%|K6GO<5Yiq<%Vt1+ShJN>eEZ6d*j_Qci!&JJiLRIGrU)rkHi1z z_%EA3vw!b;uPR#`-Sw|Sy{xFx{(I`qL)%NLg8$Rw3rZ8g|EZVQ{5t$!yzzg!zJ(RG zzPI^5^-Gl-BmAG<536iD>;J0PBsK^Cr!KMig!n&osr`Eq|EI=KsYT|EFGEyZ&#y@qcR8^JV^@dX3#L z{GYnS?mzSY;@xrMlir18RndE^pYkp$Ped1-@r<8;nf<)mecZF&#U!d(4+YEZ{kQU2FO-W@ZJ z5B^Wvdz-(>yRalzzrW1y)g-!jVySmtj~f4{?VWlz3iJQs{m%InzCZK*@PFD)GyhNB zp?kfk=bozEA65+wzAvp;gJ|ilgm-q|hQa@7d)I!Ag8x&qeklGg-uOSY=Kra)%r7zj zPtANX{GU4C*287~pPKb?@qh8g|Gj+T(BS{@ZumcSZ(Hvd|EK-&eE2_gH}hloKehay z?g#4)H!0lh+v)pO@9}1T{Gay68{+@sjsH{Q+gSfsjUUASsXN>D!}|Z#yNk`o!~bbJ z*N6X$H~vqJN5lWc8~>-qv*G{ZjsJ@`{x9D6KQ%rR|EKOfyk`EN`YgNtSO4;X-=A@| zzHs)VAA0lr_&@DW+ffBav(@qcPO--(%jOX{pHUwE_rG5$~c^LpX` z)NE(|pPKcN@qcQ3B=i5&oX;n>ee2hU{~L7ccisbS{oBG@zW3(qrS8o?cz3gTgm+B& z(R)b$7SZ2s_`CO@zRjZH*Z;$td3)v8{xhi?Uh^;S9{n2x|EKpejsH{Q{qTSBp0VsF z|9Zg}wp{YFH@*=6r>`gGCF1|oct!l5ny-K6|Eas0C&d4$v->m&{!g8rUqARib>EIQ z@6P7`sk^sMo*$R${raT%ra^6z=hyW%9~b{TT>ejfC9hGV;QzdBz8U^col~!V@PBIN z%i;gj`8NOTj(%6<$;aUP(wklBjpxGuX*=`d@PF~f|Ebv@|EI(A}n|gkoTOpLzPS^h%)jWCq!@;(GvbOR6v%Ye?Ga4uRx77K6t(qk7 zpX&2c=M|><#Z;e|-z52bc>l%EC-w2Eo$3o)rufS`^^(6{8a7V8zo~vOb$#O0PJKT7 zTKs%dJN5Zf`=t8Gum7LVNIt(*Uzj={F!lY_wneh{#J|q??C$DTx0MHvM}IcuP&c<8 za^#_A9$@ifcOBZ_zJBU8O>X?(*vS>O>j^iCzU+CY@6Yq&|MYx(ec=Dp!3&!IQ{y%9 zf9fWuo)~>&{!h*NzxY2j>m#%N?_JlI1^+iPy-)Ce>T`03Mz=jRt-8&;lHmJ>4I371 zue!~9z<>e4|7rV>Ec^Qe^MC5PN7~vhw*IgBsKcY+|I|kwR^$KFhaGWPH0AiIem*Ch zd_wSlx<8yh{!cCcr>VMY z?acpEGaI^?%jOm&5<5@qze1HGU8O7jOJuyzzhW#{b0||EK2q@qfDi zcu4%8I;0rcu#A1wr?M1J`n$>=g-Zo@qcPOAO26>D>FOzzj)*S)VW=1{GYl{ey`yF z)PsBU4gOE(-!n5e_&+u4`{Mu9J@a#-H4l#P#t-8EbUgeZ^Z(Qxv+e$x|I^oZr>-^r zPt82R`1jWynJM%7Y<=kX_M9%s>j`uH@$G%GbCNp0d#|MK*MCs(e{HhH)U5A2FfaH& z^?(7nQR{UdCN6$zbntz7BRfP#CO+`aAKfWxec-*siY=pp_sbjGKKQ?Qk}_`i7L|J2Nrn`Z0(#vA{q z#uqXFPmSln|EY(ZogTe)*B*cV!RATQ?%M5*f17*fE^j>I!C5;GwRxYsSv$P(XY=mZ z?v1bde&#lBJRts0&yVNB|Hb>iw{Q0SnIAaj_D$ZL@2cq=y*WPqPxq7KwIxx$WxhAtAH3djUHJX%q^|n@Zf`v7 zU%$W0o9D;>`TerS|HT{sr{?3mo(82_hcfBc{JXFK!%)IH2M;{WvewHwzd z_`kP5?j8JJhRs98|EVvXd2{f8>XLn1qgK<0B~IwwJN!N!uP}W6kfgq8-5~EuTd()I z4+nTx?0G%f^qcdm$t|EJz!+wp(ub+!Iay}s7}sS|I#8~mSo-GL9H13$I) z$8UZ6{owzY*?|Y#VC%0k|4+TiJQ(Z$s`nrK3g6@X#^+xJ|EKM*e)4(ne|_fk4gT-V zTL0(U&FeA$Prd!^kE7~8*7ftDFK&Cf_gY)8_qai)datv2fA~LL&zAQOMmJ@j%%Y4nE$&Y#C@$i4zpT_^G%WR$~{!fh;#Q&*R@2i>rr!Ic2#{b0| z{}*rkpPJ9>@qcPQU&jCG>n~xS_v8QKZR_Xx{>;C!c|6`FJ9hHVPY z&wKHI@n-&?w|zc||5NjMDf9o-i*0={{Ga-z(o(xWM|#gGF2>7x&$ac#@PE3V2a3vq z|5HC~>yhFA{?w{p@PG3v)&>8kety%AXi58G-@e@D*WmxYe6(NifGalD_&@ckTK}hB zZR_QoKlwV}AOB}QE~(AWdE=4H*Ljzle=vVn;m5Q2Kj!nii){X$9p8Jst@mjAmur8T z|Ecj&_&+u4+1ul@)%aJt-fUezZR;m{;|aUGa!OZi=jZ8?_8H#zEc~C2S7rO#@x3?L z`jqA)z43qMC%y3+c7MJ3d283}&H9cupV51xc@0~?*}L4<`(2XuaZ=;|iaPZV{xY%U z)!_fsrR#PF|EDe}V4mIaIqLiFTZSLiyg!T+h} zT`__CpQG1fg=^?$D#^{98TeZR2R_fXsW`{1)r<>>uWWS;KP%bxQtGoRNz;{|WtpWhv}$h*kq zgFUxviFfhdS8RRM72Z7lt@W$@`O3``;{SBMthb8)i#PsH&H3Q};*I}P^Yx4WQ?D^E z_{4-={(LLU%k*x)&wH`Wv$FT6H}k6&?0CbwpnRRZo(KGRRYj#y^(h~CKmX)2cvkOu z_um(dJ^V9&{B@Hqj*i&-g?HY#!O@y$zVSY)(J6erdq?$84gOE>hm*V5dJg9Q)KO;7 z;Q!QzbsrS`pSsS-v!V|>|0Y*`e7~XgemTNB8ZbP1;D{p+b#`}q{~YCgM3=apl; zf0L0Noml<{@5p|CjQ`W|Bm2DNo$TXt^?r%kHi_0WJi+_;-d%(L)Bc$@AG252ll}2m zy|A3`r{0e*FN(fD`gHF_Hs5diw{^Ui+B~uOuh;WteNX(KUhe{%zcpxKL*HJ$V^8pZ zdj5hPyQ9|JgJ7a(_I}-(ujENj>_C|00;o79e|LJ&mKj#0b z@qo<#Q&-x0zsH|=i#PNB@PFD~wQ+m!fAPlusf+F3clbYbq0QsN|EX7+w|jW`Oz&l7 z>!RFe@9$j*^lK+c0{!d+E^9=ES@n-$sc;o-n@_%aizj)*S)T?bCApTFi%6uRG zPhC)vh~_MK+Pl=|foDGWj5pp7|EKF)U0fRcU%c^u>XpSs(O3N!_~Vxsu8E$^eBS#d z>psn2@LsTTMfCTRU-W)y#j0q*5evQNFJ2N2{_#++dTDX=(}yql_7|UgI`}_5|1)<^ z4gOERpBmD+P4w+WMY;O@R7U2Xqf;*`_U>)-weWx1p4+c^@PFzY^Febbl=*giUeN{R z-d%dtkB)t{Ja_%_;WhL6Y+m5?`zwh883|EI?L;s4Y;enayux&JwCc<_ES{!cCcr+U*PtCkK{9nBBfAPlusk@s8 z!~dzd9{itru+2Bb|EUL>SHu6QyW9Lb{GU4C=HKD})SCYnZ~UK{`FQw0HS-1We`?kb z#{a2%4`~zD|5c9|Qse)0f0)0A|5M{1@qgN%#{a41|Kg4RQ*(dte`@x}|Eak?{GS@1 zhyPP^{`kLmer?qlmW zx1)qbH#tW@q73`eZ4Rr5dRl% z{GWI2`oHQPeQW0bdE55`{9nBBe`>rk>;I~A@*4#Ir_S!uAnLf{@I0M=ddFlxmTmL9 z;-7DKZIkS&2DD1{TD?+yn*87RyGp}+tX%UoCHp7k$+vWBbZT_js>{4PHasP)|Eulz zG}ixBcR90R@PBIN!QubZ_$~aO8b5~ri+AsfuF9MJK(T#4`!J8~<@r~8fci5^QB%->hpI>Ilok|nELqC`GCCN z;^&jv|JU*C{TAOpb^YMfZdf>p#~!Bl&!opBF#BRKJ+&|5Ddu#^2%p9>}Y#@qgy|@PF~f|Ebv@|EK17 z_`i71D!Mb)Hc!y}pSH8!F#b>7#n$`A|EW7SvGvi-|EW85Ob`A~-8DNm_&;^Sp+kcI zQ#T(oI{3fIX%)f$jqTMp_&;@z_ML+Ndt^je@P8RCTL=HAZgldg!T+g`JpK6K|J2bj zHU3Y1%5Q4s|EcR7`Mc=rF}L~o*E{mJQRR)ddN=#ial!xn)UGP{NW3EcPmSMW{-3&G zx_Ov(wl8_x6}K3Uge$MH9ML=@k;NE9Q*yz%qzT^4~PHL^YzWm4)g!iV{@~@`oHQ? zwq7j$Po34ZbMSxaE?Mcp|HT{s7jOKZn(M*;#T);pX8m0JU;XSv@RzIyi~m#Sr`tRn zoByZ%yQSHBzvlncS?L+U|EckK_&;@8*UaeLCFgmk+x@`*X?wQ$zDo0d>YSXM2>+)( zDS17`l89#1p>FW&bb zm)x(78Rho}zli_S{p#1RU+{nG@jZG5|EJ@P%FPS@Pu(>)Gx$Hf-)QFlsd>M|zyI~N z`x)<4518r&`(-8jK)h-E@p#F2_s;Jg{NKOw$JO}1zBb=+<41{t1!IHv8#2H=%?BSO z{u25${}*rkpY|VS-i`Tx@y7qDdzrtx;htCg@${bA`;)r)?0w$&uo-vn z^&V|r4gaU-A346p|EW11{x9D6KX3Dg_&;@T{FM1Wb)R!O2mcrE0W-Jyc6`~3Gq!l+ z(eQuTf0)g)!vCq||I}O${x9D6KehZ{y!(DtooMvMsNm&>oYgtH;H!i;{_p0ms=RqU zANi^>sh56L;oaBPcgFwe`2B6Z9R5#@k7E8`yzzhPCgzox|EF$xL3)_~rw;zj{9nBB ze`-7({!iCKY5bp>?f5@6ug_iIEcWN) z^?3H1Mc&NUEB)prZ@eA;Pv;~57woIA8oX3w@qaoVz7zi!?;~gY z#h;(`uiu~Xs5j?>|BIhL{!h*PMdtsh@qYL}HS6=@|Gdr5;s4@||5M`=@qh82cF%p@ zcs=}|&Y#BrsquaIKQ%rQ|L1M*7yO@^`}fWFcX~75@2DSUc{AUy(GPccvpwsFncl1? zJmQBL-p$NEUjD=F-Yso?Ui_b)udDez=KsZ;`G0D>AO26>!~7urFW&gSc;o-n%=g3p zsquYJes-02&)WHa`g)=9f7*Ybtrv{{Q};0sjsNr4!{*bL))|xdvPs|I`EqUlce{@A zzH;WR!T*`j3qG)N@AlyTv_I=<;s4@||5LM`7XB~Z_&@b#n`eao)A4EhUA{Md2>-`t zSopuq=Iii(>P>IG7v}$|*V}wA{GS@nhyRN={!hKmd=&mqz24>t;{Vj!?C}+cW%&8f z7c@-smjBcK@_*{8cis#BPhI_PjsH{2|FK3F{*T80skguTN$`K_o$r4d{9nA8{}=D4 z(;9j2wt0KZ|I_we=KoIpuHK>RGrx!b)A?*Z@KNx8>Q&|e@qg;owe$bfYt6Ia|MdD* zn|H(ishP)z|5I-^?}z`3H~vq}{`fz&{GXl=Z-@U=SK0CKe`-7+^Z#_ct8G19{GWP_ z?T`P{{>MA+pL>5|m3Nu>r~^MO^Je{C{GUJGJT3lDU2f|KsMosW$KHIn3#(U$l@PFDLFM$7xH~vpuymL?Re`@A?nLqaHFWS5vPwdUS ztXpn8)BEM>^}+w?@h{oDEc~B(QPtYu|I{lsZVCQRyN2>hn_yNHSZngW@<(0?1 z!+f$AXD9XCFRt~*XVkfWq<5M52K?XpsRM#1EVX%l_`i7L|J3+Q{GYmJp5Jxe>+Jo4 z|I>CnIR8_xx1WFJ`LcBWHGOTi8gGUFQ{(;cfAPlu#T)0#>{^|kF$9wzUH-rDv^=z^I&2RelN?Y&u)yj{&%eU<1{Jl#z zy%IG(_OKkC@0zu{@ku#4-s-}A%p3E*Z|)La5APWlzijjB&hS1ve^&5+zppzm_`)8Y zYW$zNU*_Y%|EWiJo)hN(jjSA4JOA&o;Q!R)MotU`75{d$(%F*WKiax2|_d0LZ z+ct0NjSu|t(QV#5AO26*zucY=|EFGI+wp(i=7sTpYCJLiPp@y;x{bmAsf+CU9sW;U zT2&eRpB}%&d;|VZJ!k$?!T+fzProJjKlQYW&k6odedXvu!T+hpWONGtPd(b!D`Ebh zx?5Im@PF!dE!qVCr*7E1UGRVEMlIS0|EJDw+bQ@zbx!;A;Q!R^?e}>{j6N<`ujklv z&kz1j-TSs_!T+hRUbNWWZzuWwb5<4F?>GMJ{dh$+UfFw|`M$Ee({lCo@SORjRmBpIU!fQ*YicH%@5o zjgQ;iyQMe25C5n0qw#-g)|X}epPKb$&l%7mS3lpF2ba;dlQ%!l&EI?T^XcFZ8A*-* z)A4xx<7HXC9q(qI-@DSf&-C1+K4U^RZ+@QP|8ze1L;Roq{j=8m8~#sSZ9h-3Q2O^X z&Ht^&1LFVG{JjGHPtEz@|J2+s{9nBBe`VM&#Qr`4|EFGS&HO+0dfOlWr!F)9 zhW}F+SJn7GZ~OZT{GYn0d~NW5>XpTn(HHm6^6iUO6bApN_uC_jRtEp4esuAw;Q!RD z@BQ?!+5Y(X=7I5lI{x!(Due&i{aI2`GyhM$#^!_K|I{T_HS_<}`0i$zb943kf^wS= z{b=+1y;s`z`@>FsAgQlB@^B0&0eB_GflDga3^SxKCUK9ME&UeMCg5dwu z^Vbvv|EGR>Ps4|8ie1&3$Oe$l&{Od)AK@zEj~rk)Xe8%{$ITDe`@A~vHq```C#}zH69QDr)HiX{!fiZ!vDp4N4t%={f-&w zp6|Lgo07V2tIgi57mWYY{&a%}w&X^ajmZ7^|tw~+caJ%n6bZFaX;u$-< zhnQbGrru6({NL)+cX{_2);b!0>Td5*L)%4%pS;I=xXq9IVbxy0ovhL_&>G$U%Y!%|KRT@ zzP`Sw{L#CI%@2II{O{hZx0_Y^5AQyGn?xTK{nMN6_pbSucYpi(!~f~)Wr)q^!~ew_ z|EK2s@PF!_{hCH6e)h9}J>h+S`uM-zc;Jse_{BTFPs3>EyZ`g<*1JKN|EJ^0|EV)` z>IVO(?wZ*!%>Pq&Nv{{(z5Vb!b>}uMlRm%BwDlq5pJ#Wm^&{imv3arwWd2%K(&eYPmR~wKl{qO ztNNA(@0Veo4*#d-`1rqg; zw+0QPPnJ*dPW5Z4{;fm(WS`aM^kgqq|CAKZb!zhZw#`mX?&hZ?A1|w3@_f0>y2)NF zb>3X6|KjzCzy2*!{93De$$qiT8Oa_m)%T_Py43Bz=Jisyr{2Hz^^)&L>h@pj)bmUA zm#Lll`gUqmKk0s@dc0JBm+JePrObCso%h(-{$4Qtdi?6~n+N%pN@ZaPg_6j zs2TqFu1)GhbB4_D^J#TzgXo8MZ})C?Qr+mRD-ZSWZT@1n2dDYtqhpSY2Cur!`;SK* z9i5Rm%^!dK(Z>Y;r}L@v`#(f2%WkWF_Qyo&^4y|FoTXcg+7&Gv5yXr)Ity{!h(%s`x*3w{G2n|5Nwwkr(AGxZJnrb?p-TpRSkr zar=(B+^;_;t7iV6w&VAh{}*rO|HT{sr{?kaKQ$f>|EI>c;s4b9ehmMYclg@i|2mnc z!~dzX)6J)u|I_|iXUBXWd5HTPl*4EH~vq}`o7;TJIC)wSDRl~z2j_e{NS9w zo#j2;)(1Z8=;UtEe7tYxdjHjXoHw2m|EK%UJVN}Rn%5Kmr{?wVuzr*`>lx$!biOqH zPtE@LKiwbv9R5#@pJV=?dQ^UX@PB&z5c7_&J~70fFFU78@P9fV8vm!}{Sp6unc7_c z|7-h*l=XjynD315&%DZb=XT4EHhuC@qR-xO!T0qT*dcoEqYu4%4>8Y_`9WfO+i}77 z^&Qzh8r0=|?}20O>)HIDw#)y;d-wzIBueIt_4$2E?|(a~@qgMMKX&fiH)!jSH}e7Ue|mhM@$G~EQ};Z(LxlfRGcOSTryg`x$Ke0e z1IKp=^Z(R59{(3_{GYm)`9=Jny65;B|EI=#G5=4E2gCoV@jm!Jb#ATyQ{%1he`>rK z^Z(S$+xz*;^@;EPHYRvJ`sA{lovo8~>-~e&PS(jsNpDAGz_X za&N8||EKfAL*f6_TK`wgd^G%@x`X*F*8f$rzpby}$Hz}y_w^cYo)7=0^PxvfDo8Z% zHzxQv?pN!}RwXt5Py2I!ng18>qrX}1jsI-)%`$I}pZ(3!q{jd0eA$lwQ{&t4e>y&| zKmIS?_`i7L|J1xcSpPTP_&;4Az778uZ~UKH{x9D6KQ-PD|EFgCTl}B8pY`cepZ4bb z@qap>O!J!fKQ;5{@PBHqAO9EcQPUsy<1rtw?d^|w=h^%={GXnm`H1+xc;o-#jsH{Q z4e@_!t{?xW&M|L?|5M`^@qcRWH~vqZX0IpyFW&e+HSfnU_uiY-?e4qBoA>`wb7m*? z`*ZI0=Kht>y(_67zW+{d?#JW@W_feJdOUcCH~z2gLo<^a|EK%i&io$!Pp$cXYUcO- zxA|@U_#9i`cSXyo-fYMJY5zR)gZMvn&V-yW|4*GeF*nTrQ!~F0{}*rkpStIS+-T=# zS9r7DFaA&4wf?U<@0`r&g3mAU?dfC8gPQ*{lNbD7{>1LV|EaH@H7)o*J~Miu*Nu4< zd$tAtr|o=x^oRcpPW<$Ygp!+V?gsl7e&z400NKi0Uy3$8QIg#S~oH}ACR`E1`GAI18=IzEm6 z)BbDC1LFU*oyPyE*S+y>bX0yv?~QMN5Uo7Fz4vDGe60Vg*wPC{C-&D|J3q-YWcrI{Xv-jr{?cLTkqTFgwsK#MTF9{+}Mdpr|$IlP^pPG423%ktr z{flk>nE9(%*Z4o}Uv6H{{G302(|(S3iucBSui)1zv_G#8{_lwigMt^NZN8f~o)7=0 z?VHTA@;^0R5dWv+;o;5aWvh9A+4W}YdaL)n!TiLe#{X%5<}cy@yzS>J{!hKp{44%X z&GX^^)SM6gPhGz2_2B>1m3!U{{!hKh*864tpRR|-|7m+-`)k4fsmnL-<9dC2<%Ye% z|7m;0`aO0&N9Cwj7rzqxpN@Y|t^ZSBebM6J|I`C({oe(@9US~$&vy5R`G4v`U26QF zx?lEOTW>ZuM?EC}k>LMYyfip?z){0*we@5N`}WHxJrd^sY5zG>r$tlFJloIrfoU_C z-BMb|uenfHrVUljbGwin)TPVj%~#PmySz3kh4|HZdo5&a+1?mNn=`riNl zwj_Fuv1>%7_s-A;rkoju-iwG}!CqoF7L2{2CTheI6&t8Xkq*;fD!tfyud!oHG*^wr znBV*PIlSKU+2^kH%^$z4b=UQ|_C9;>v(GuhF!SL3`S$!9yo5yQ$^?dKj z?N6DPdeVE%GtZijTGrI|`NRL|e0VGTpBn!=^`|x7D{TK?ZmshU^Uciv>Gj1srSIR+xH0%Y zJ${XO3;dsYwXKiN{6F=Bv+oc7PksF#ZVCQRJ^i#(lh3dJ(Vu_+lTS(R8~3w!r^!bJ z|EK*A8$CGr@ta*Ux}W=$*m@|h@9v%0&+iu2|FWrzii7{t(k{9VsHEBHV4lw0o){!e}B;_Bf4)N@y@3I0#L)Yjj`|EU+5ufhN6{lCQ4E5-k* zSC~gXbI<19RrdbH|LO6o?EQP_3$1*6xq0^sD%yDC-SK}q-rAl1PtE$#_&+u4@#6o~ zcscx^nt7=BKQ-&g;{Vju=Fjkd`tywWc=*4#@qcPQ5BNVd>uuM+I>4LvJN{4GY5bp> zKkx1DCmH>DP21mJyg5GpPy2Ix{Gaw`{vG}=Zv3CVzs2Wasnqy7{#%Xrv%jBZ^!G8^ z{{5EsIy;~J`>s^m{C98G_x{E7BfWXN{rj<~U*hkVslM~asoq@Q*>4<^>LJy~c{keY z)AGLQss86BCwi~9`}5-DlfBoOA6?w%RByh&xbc9~Q;q-A^Iu}?@8bW|%gy)U|I`(m zp9}skZv3COeSd`iQr(U}G>EQp=>o#r;{x5F) zpSsSzp5g!0Yt5rE|4&_Q^Y!q5>g6k|ga1=Mu&g5ZKlRNIK4yQPn(6!B^w1N*|LOgA z^TYFl|5M-g;Jo1f^!PvA|7h@k>Pr_@2LGq~bA3g2{-1i)+Ks{gsVnNXg!zAJydC~e z?@zoP{!h*NyZAqKxy{4I|Ebs7yjc978V`v7Q!@_`{}(s@Pc8qapKr+jsq5<32mcp0 z{!d+5zb?W5wf$~H*8iD5$N#B$JpND3pFj9NHR~H3zeSe4xRzjJ;2;^ixo>JK0Fetg;T;QzG$V@sDM2R1z3 zw0-fiWYE%i-g6c_nVk3F6W+_8SeQKUhxy)5Joremb;bhk2mW|N^6hC0y+;o09oGNV z&#MZ0?-Tr=eqK0!c-!Fr)MX<&C9l3-l{s<2l;Hga4bS>N^+227hyPRO56SvJ^?)I* zg8x$w9NIegKQ-$MxO2|BETX_c70}UGELv%=^Rt zY5NG9Plo?f54ZVbaX-+w|JD@4F9L?91s7e=6v`+9S{HY`poUV z9skvM{Zrn|+r$59f940`|J38hcL@GZJz+w};Q#b|ng56XQ{&I@e{pwN@=~htf7;IV zPs4_waw}vF7QR z{}(s@PwyxBKehayn(g?%xbc5#`9Jl@Q5}N+iyQwJH~vq}{LZdB{^g$s8vm!y6YKlp z|Ki5~spbFF_`f&LO-j_6vewDCFPj<<`2N$ol<55Oe`@Cc;s4YFyL3usFWId`_ph*9 z+5;AJPJ6)qHjgX*eK%e%Zq{f0^{!`^%-f|lctGaq;s1WvrzXtP%InxB_&+uKa%#a^~N4&GCP^^W*Yt{$PB+$F@q}|DlH-p4wh= z*n$7g?%F!-4f8r4k=j4k+x<7Mm%BZ89${|hu7{i3|LuO|&OhvQM0#G{|6dQ7>l?eZ zXqCD@JzAybA?Er=)~k(QuiSZiZOyaB+uNJ}in~>t^y``1xySF^F8%&!**U%5bZ+DO z;`8!1}*N(yeshQV@|5JDC*eUowHS_wI|EDhKXn#I^e`7=6 z^7`QW@J`R%+|*@dWeNUI+gpzt75tyNzjP{ z>2=-%Z9Qw&|JD9OI(JUmH(ux0m$A<`{!iD7kHr6}JJ{zN|EJ!&^>30J{&kIavi}~* z#KW3;&%J&T{GayUXTM(s|EF$y@P5Jnm9A+F{x83?d2;iA>Si{dkNJObcYNvhe!j8x z?=`>u`ZDj4-SUF})A4)u>>2!@8c&G-Q}g=b|J2L_#Q%Bs>=pc<8V`v7Q|I@#^?c3$ zsr%WyQ2d{|pjY?c|J3+${GXb6gZMu+{*3v5>OTE?1^=h+)}wQ>cjMW&JpNBT%pQ;bQ!~#F|EC^WI3U6QspbFT#{a1Y<@XK#PhDdF{uuwK z&h*U-{x9yI-=FN;OY?dL|EK3$(yK@Cf4X0NdUZ>7j6Bls5B3n&8dIbNc=Jmz@squjE*SFkeUSPa^*oeWYo-n8+)uRg2`*Xhd@g;+bl530pQa>i| z*x>tyoBunk@I&uWJN=)wGw%=oryjb~|9RW`u0P!IPW>{6+kqp1=HG+`FH>+_&TZ-Z^`jH~ZuNbUYgW7dQS-&Fg{xi(fDNpPKo6 ztpBUVqv8Mbc)S|^PmOoO|EckK_&+sX5C5mxu5`^^;(diTc5UHO1_AA5fDuA1$QAH3@7`%{ho z)A2^1R1o}M-1tBBc-xNuiyQx^9%u9L@PF#D=Hc*vYWY7kuLu4wZv3B`{qcWlJRtrr zZv3CO`9Az#-1xt^@qcmS|Ki5~sacO0|EHG!Q_KIwjsH`#|F?Hu=RM$*!sOYzu1)or zj@Nk0|LO5G{!cyVwBqE%Zol^~J3W&e&|`)-zHdX%OHzGt-bLQyPR%48`dsKe{T#d zWbX@SUXwJGPx8k9o&MScZ+<_8|I_37{S^LB&HOFns;OzO#>agZZsBtMa^=SNHx)J-u1KcgnRr z{QS&^`}dq~-pt#>|22LyCOhBI8vmz$#v1<@H~vq()#l0J|J2)Tz20rBTYGObuZREB zcCN4A!_EEtthbB*)BRg-UT*10&HVc5m#_bgH{K5ar~T>Hn+{BEAO6Yy-puPeZ;$;_ zeNU%-ytV$Xj>mep_&@bCcK!H2^;Wxo_&+@#t`GmG#%E?8+0DD*wXFa1?XQ0j{GX18 zzr+8<-Q~0I>hylY|IO&~k5q3w=WpJ4(fyb2@NP7ZhyT;@@OEc^@sT&zi~rO0$p6KS z|5IYy{!fpW|I_s_FA)FdZQc+6r)E80{GT4r zd_Vl3y4LnTsdc&UkLO!{;tFrP-@oT9@vb!QH2S@Tsh-{9iKaG>_u27}rn=w54>z?v z{)V?_dso@<@qfCW)i$pW|EDfDkB9$LGk*~Or{?Ps{!hKdj)(tKGk+BSr(SEm5dWvH zF<*%PQ*(U$pSs%o8U9a==feNRjsH_?{@DH`@WrdSvIfKd!?<9i2u{$ zS8RPM_&@c^ZBGaPr>?ANVBV+izhq@a@P9fVzYk>nUv*V2>$~mY{czoe;QzG!e*1kS z{!hKy=8rJ{PrcdJXT<-F8#pfbzsJpMF#k`z=v7;<+5De+mCeI5kL115{N%~U-sg=k z$Ny=6d?5Z$jpsP(lOw(P`v2D4e%?>p`t$g|d*2=xeBt(I!@Ry4HD1m|=Ksab{6F>j?Ju!DbE@t2E7J8V;Q!PYpL?IpkDKhrzx#@7g8$R?-gWua!T;&`FT3Kr z;Q!Q*oquxhf9jfxvh)Aco31)7_&@dh8!id{PyNEOxxxRbSJkdfj@;$8Vs)eWzumUq z;a$6VTe9k|yS>+&kFw8)H}muGe|kLg`S5@0di(wi|EJzypD+BMn&aXB)a%R-;{Viq zKiBQ`m8rJ(vv;kXAOENO$NBJoYTm!)cdtvez2Cg?Is13r=8Yd}`0i=%Rpy1yUH^Ql z&8K>=HvhM6+UuzvKl^Qeeameg-A|{#?_FUY2mhz{*P6{+ga1>n-LftCKXt>F?ZN-4 z@f@uGt6s5YO;T9(ou7Zvs#U@N>G|KiWO49+>f4@}7yO?dfA=Gg1pnvT@4GMfKlPP= zelYmIxb5?mQUC6ddG`0Gy}W<_#A5TLdwZW}K7;vx+W#_J51I9U)pxI{PmW!-e@3tO z?1qi@eml^cc~*PPIM{ogtzUZbvA^-Iwfm3%)8p5gzr_EkE6t?X22mVjZ`wjo6=Ibf`FK+ywy2AFy|HaMvziQ_D;s5mK z8}kM6e`?mp#{b2Q|5Nk#BmAG5&y)Rmp3$GrH2zP`{`fyN$H)Ka@jJgi@a>zJS7`oE z`!i1$|EKTgSnn49r)C}>wo1);0Uv2Ma{GYnY z=Ii1A)RpD|ng6G*Fz<)|^S1Xt{!d+Q^OF1i^&;;Q!Qj z-TtTG|J1kMeQz@Of}8yKxBvP6;Q#b~yzlP&g8$S0H(YZ=@PF#t?wpl;+xw6H_{SE^ z59|NxepN1B5&WNetIfk>{a-cSuJp;~?`oG#vv;MCd--rLx>s@Ug5dWvHT9@^I zYWY8Pg?;_Q|Ebs5`EM`3C)KR~tDkSIxAl#g|EFGO*N^{GbA4U^+0^*G*FU-6x7XV1 zkN>;+#Zkcr()d4hRdsFfe{tjg)bfAo71cGt|EZY=i2qYBTvd@w|K(iol`B>U|EKLM zmahu_Pd#td%H)&hAM^d^E?XM>pSCmq5C5m0vtUv1f9gdx{}2DCp7YQn$@hPspXuLo zRHp9Yi%K56{g&j^cNcgMx8L`%{;z&MH6-s>!T+hJ4sDs7_hw~AKaXYp7XDAo{4M7H zsadZV|EJdazv{fQ=E48P&HO(#J_rA&E*sW9_&+uNhxvbMd=T^h)Wx=b?92VvWj;%$ z2Jc7X|I~Ob{9oMoKQ;3K@qcmS|K=Wlbnt)76U6_;jsH{Q5AlC$_Q(Il$HV_=JLkjy zsqtwGuX);=^Q*(Xzzqs*#YW(MUAAaOL()P#yX}kQNn&)@gTc7%N zo*({C*F)p~)XYmf?&U9hfBF|M?(k+kUi_c-=ly~IQ?oz*Pd(1&U*iAN%+DLW`R{%_ z`X3v<_MU8h_rZ1FcuyMEA;JIY`N;pN<^R<3e`@?K{!fkfWBy;<7ya))o8HfMJ;#3i zgE#a227mRVH@+7Cr_Te8|5NjM$N#B|?CTN!PtDgO=KrbX|GbB^4gODEJSe;VudcUm zk$K6{yOyXs_WVuof9m1pg^nA!n{OY{zNP(iqVXF2U;nlpQjO=)HvWHJ`~TbczmW}f zS^w9rL-2pox7TLQ1}bN$@^X**tgKXbj{DDzeE_H##% zN%h5}$EW)2vSF$2mdT|0SIyJjtf*z$%ayiGd$Zi@$?cJC(_W0%Bfj3;`GMVR9%Q^d z*8}Eut|!c$-}m3<=jHmp+%7yKJufl0bNA0Z|9|s`x!ZGnW6PH5*S~qr>(j1zi`4zf zU9UOU6Xwou?AS5=`Rvpw?RS}P8NVKVyQE*weqFQvZ_Q2Xg8yUwC-eW*-P?5u{!iVl zZRg^E z{lovM4?g(d;Q!PI9=uQRf9k#W$@)L_ulCzB_&@bN2WI`By6b^i|M!=x)(8Jr(lP7* z)NQ(VOs1A!?&oi3-VOh!$K$o}f9j&{U4#Eq=XL8I{GS@HiT_jM0r7uo))&VAsr&Tk z8T_9b@5lPTy1wE*y@LPK_QJd#!T+i8U(EkgXL@!I{!fkH!vCr9e)vCi@4h{Q|5MBV zsoVAK9{iuKr_+GE;Q!RD$BX|{Ge3{{f8OS|@PBdR|8AVMA^1PM9R5$uda?LFb??Hg z|5N7`^bPa>)Xe9@|LOQN>;HP&d_w%6o=-u(`5E(napV8gcs=}|nt62iKlM19Cy4)3 z%m2mA`oB6q>)EpYuNqH?|I_~XNap{kIY0hSjSpo0pBf*C|5I~3=KtyVWqtCJ;%<|@ zd42JJ+Rpm{|EC_%FE44cbdulif&F`j^?$X!N58(o|LJ_a2WIF0sYe#se7Nt%`1On^ zOwa4f^?&%i`0L@=OuEMu7pArsm-bISy!$WplkPY!_`H&`0ZHNAA9|OK?v>ng*9YDs zC*>!9z4Lu<{NM09-}9FLYu5L8U;h{Xr{m-K@PBIj9R4qE{GXcnfz1Dl8~>-~c=$gx zJ`n$>W;^~*&GGPm>VdW$|EC^c+wp(u-gbTXzqs*#YCIYKPtEc0e`>bl|I~Oj{Ga!6 z`N99ijsH^*Id(wse{tjg)XbNg{pIF*`^>oSTlwWCZ~PhlPuuB3j@eMZY3Q-R_uZ*nqKeCcKlzw9sj4s%e{SKjW@oJ`G2}TJS6^4jSt2D zsYls*&iFqy9uWT*xBdLYkB>Lpc6zxt_y5r|R(s?Bt~hg5s_}oiUgjGz|1WO*pL(3# zfBc`Cd61RoEcNE`cbvP#oAr&)IB&5x*MH>So=jc;xqn;ajW=WdpPt{Klk=197cTI} zKmIRn{GXcZ!T-gL|5MBVsafw8{}(s@ zFK+x_Q}+x0Pd)aO?EF79*T?)nHP?gxQ}cZAe{tjg)Ob4lpBjIM|5J~cJ|OtNxbc5+ z`d0Wq^#=1V_&@cUmtG70PmQ0! z|EU{no)-R3U1xp=|EIk0qz+wOk84fc5aA8Tyk z74dEOzh*Cw3;yrvx3m6Fz5SgJga3;g|EI?9;s4Z|%>&~9)az{hUi_cB@y)FN)A{jv zH`BL;>Q2!dU^ja z|4+^JOj-Db@4v;?o5ug?@yxfx|Ea6&{e}Ni^ZvyD>3AD$-X-(@v>pG7|5G#X5C0eU zrpIc$@qY(?Se0u0pZ3So;s4^s|Ea6Y=i&e2#{a2#JpNBzW%JDNf9h2>j}8B)E;lcR z|I_oU*y;b`#{a2n?D+UUb**_l{GWQgeSO0J#f|?{*Vy^+f9hI0pZ)&VuV*bDVey&X zYwUXQf7*YIJsd9zQ*;z|Ecd>TO0hJdRBF1@PFz> zFJ#yMo!@*y@P8{`cs}?)b=7OH2LGq7ekJSw)KxEM{ht~if&Wu;zwm!*-XHisHSY)f zpPKa=@qg#8pAh^XZT_xC+wqy^nY@|TXUF%(gWLXVwLgE}@IUqDtmi9GZw>SPepjew zo*@2DjbFk4sn^;5=4p!54dHtFd2h7&x%fX_|7M$qiT_jM|Lp$w{Ap#p)Fo9~0*P zsq3yg!#*$97VGn{_|_{~U)=k}RgVY%r~Q|iAH)BtYqx9({!hJj8G1-Zh)H2LGqyRj=O^{GWQ&x(&hq>HIYF|I|;ctq%S# zZu7Dk^&{mgg8x%Lv}#%Kf9gA*d@}ey^{hpU_-4|5MBVspbFFRrdPh z|I~Oj{GVF>Pc8qa=IcHFPtA7xpL&U{hmHS>8~>+f{c8N5KF@f3{GS@1cmK)#Gy3zD zw)x?y9@)Mi)%d@7fBawE_&;y+lK4NJZ>{-%=KpCs>-*yW)U0<~Ic~UjwXN5V|I_zR zYqq`+{GYngwqu?2{cFwBuLS?6=6>P-)ck!9|EI?5;s4aU9{4|XrTIMkpPG4#_&+s| z$N#B$JpM0k{GXcr@qcRO590sg#{a41|Kgth^%=e$f1LmPZ@uw<`!7G+oB5(&+@ zoqc~cs^>M{@_+vN+dROZXI$so8_c71J@b0+70XuJ-;ZwazUi^K$&Dj!^uA}svf%%8 zydA5mg8x(h!>-@HfA;s+&*sZm|5w}pX7k@z|5v?r_ASBxskhvJbMSw9zB3mt5B^U* zXZ^O||I{_+`S5>gd?WM!^m>-tJW}TWsVf?@^Z(R!HeYeW^|Lbm^8`EI1sC4w%{;;8 zC*GCn?c?tD*8D#`Ui1Idn*XP+ty>rTpBn$i{6GDCW%b(Z{697G8S#H{;Jr$ zWas~>A6xija`+)nWcJ%@Oz?e+&Hw#jxB1?WKQcG?KW%?#)~&(+smI#yZ|1yHp3%=w zi~H@L?D2Mm_n0BAg8$R@;UlvCPd&osi{by&%-_QQsY}ccW`?iL2kJJk(HlR7|I_(s{GS?+h5w5i|EJdc zKegunU2ycY)ciknq4_ZUpL(Fp3&j7a@k{tW9j|mu+c5u6+wpGrzqs*#>LE7YZ`PI1 zcr)J*|EJ^8_&@cS@m+)eQ{x5kf9jFr+Xnxq`%RDB>t)|Q-n``B_jo1M_y6KmZ`SX{ z|LJ%%{x9xXKc}1de||o@|M)-c&+CEzQ*-}&e*3mJ{_eGJ-if+nnE$8a;TxI%*VNsE z|7$v4*Wmxucs=}I-1xt^@qg-}6FLX~r{;b$|1WO*pPJ|M>o-30#y6I~`gzptga6b1 zJYW1@+)JMOGS!ox`K$M+QJs>1ZU4%9#E1^bysdxp#>e9Sbi5KfKmJcWZe-T~smI!U z&0Y8Shrhq@f?w?Rzo~vP`PMsl)_*s3#=PI-KYr)i@qze19Uni4|MT~=ZO8w`jsH^@ zjcgPApE_foC;Xq9`GWXAHR})K|J1{VXZ>H?%>PqQw0VEb|BHM5S-W_b6t_zHf8Nx2 zJr4-}PtRwl%@@P}sfV;qd#GIRh1ZLJKi+l%Ug_v8HdKQ;6DnEw|y{!cCcr!HyJCVAj5=a>9&MQ!G!kKZq0`&acB zcxPI-4*pN)$5-M1)LqO+;{VimN&KIBnC*}MQ|I2l-mTOAt#`}x{J6fY+okU3L|gwf zzQ5-TN&CJtC#C)08575)_Mci(n(Cg1q`hD6e8FD-#pm_RnLpUCP1=j)deNRaKCnld z^z+L-Uaxj(563*k`1u#-c(~m4cys+=uD8qWp*iap=XS35%k_Y5TBheK=60@6?3^n)!FE{~I^+|8)H= z%sb-$)W16TfZ+esEo`12^Z(SX4)}GL|EE6apo5ZUuezpTX4%Hz`|yKTJ$SWu(SBL~ zr|skI>k;$+)a|=<4gOEZ>(ISh@PF!F-8(1vKXqP@F2Vn)yZ7u8{GYm$`A+;_Q@0KN zPu;y|r{Mq8tOv~czj5RLbbUp=dI$ff?X368{694w4F9KQUL5oP)ObJqU)=aVb-&&{ zg8x%9ACCEd>i&It2LGq)!G|&bPu-`$);Bc&r|w%=5d5E-_bdJ{Zv5X9M{f%LkM(r% zf9jHg!m$2ty#KI&p6ZVuXzT5={;&4u@%TUO&w97`KlP-d!r=e(e8!t!!~dx>h52Fr zpSrB1F!(?9RQvl5{!cxnB)k5vdPJr$%>Pr5EGY`}|J3+4{GYC8bWuU@f7;G^x%fXd z=g0r42W1L^|BD;{r{?(hKOG-GhyPRK@9=->f};H3|Kk4F%SSeBI%jj3r^x)ie?B&$ zX@7hD7Br6cE-ESt^Z#`IBa4fI|5Hz}_e1>kFLxebZV$5cQsVt{yR@`V@PBh>O%MKW z@ZkQz|EbHybPxVdJ@UxD!T+iIPwN}}U)*zNy<4xw+u{Gz@_%vT|Ki5~#f|?{b3FW? zdZ2kL{GYnOJQn`1sk7_*p07Xli{pc@>odJqQoZ9j zZ|38@u;W?pLYp7=#g1p1+Pv9rUq0=P2R!1-r@Z@`|LXVU_EeAia+~+yWAc+TzTE0v zHm!fMddimigN7U*{2o5;_MJRNKGb z^B!;B&i;L0s%`$iH~!E5eV}*neb3i=PqF8B@ryOyN15-#|LOYKzv85|-W>1tlh>r$ z{(YlAp6&MUADi0dciGQJQf)s!@y6E;cyD#8UwD6&H$LyTAFlMq=k4;*3U7Sh?2ngw zG{e3spbE??fI0R|D^BF^E>o{Mc&Ml`{sg$smA~5 z@$!FhQy+DLJsd_|_1^=fWIlUnGKX3DZ%>RoU|EC_ibNyfS81t<7KXo6Q z_lN&e=bu^>{GWQvNyWkcskt8fpPKb|@qcR8-^Kr_S+AG*e`>rR{!d+E^8s1^SB>|> z|EY^lFAnqn)R{A~^Z(TNJ?8(#jsH_0eOg)Ye{tjg)c8K;|EckW_&;@tZD;8h5# zUH(t!tAF#O;Qw@eH2zOrxzqottKa@O_&@dY<_GbA>SxW*;s4Z{|EICH@qw@1_wPEr zK6tw}@BHB1xYPgX{P;%Z|EV|H_2K{2t6qLL_&;^UYab-jzy8#>GmjAer~A!3zO|h{ zNcA4SeaD;q@qgN%>&O48nRki*Q`g)38~>-~{raaTwtH{2^Bpj3vtJK=!Y%8)<^S|} zK7aT>HJ`s>K|EpfQ!G0fV{!jZau=RTJf9jRyZSa5U zDw{`#|5MkQC$2dA5bup|zGL@mAMf?Azh(Dl5AQ~M{9#r9srAR3&pv9&-@Pked^Pw# zT_4T-zn^!R6#QT9>u(4Dr(XBY2lyf1j`wE%pSI&G%{O^-fAN3XUK#w}@4Oe9m&5;Q z`=T&!ub(%*&%BCv*7to=qy3r3hyPR8W&NHv^ZoFD+P?mk?EF9V)As(b?FH)Xc6|q& zb77(G2mWNA{VTj#KiK9cddvUm@%85S%r6$HnOA7f&-*F!facGyOQ$``dZ6CZif#=4uf=bU3_fsdzdM8fQ%^3sKlnfO^g(wdf9aYjR-ZX~ zwyiHa)ce$_*O@093SY8|5rZa*kV1u`*-?3bgp$$pXB>5u3eK{ao4Th)!Q})|EKfeOWtaJ zw{OS)-1e7yy(`TF_ z{!h*EZ~g5WZ@e!4PxrUVycYg1Zv3CRX6O9Bxbc5#<{RSw;+B^~dPtAIq@3s7!_i~#TX77LRRW@Ic`G4A<#{a2T z+j_XH|EpeM{sjN0Ua)Rs@PBc${;ztW&7)%dU-bf;H--OGKW^TI`G4vKc7FVydbO=L zivLqr+WMrsZQnPe*Ke(PBmAGb*5;ex|I`)s=L_@y)N9Q{;s4Z?_U9G;FK+ywn)zz@ zKQ-Qp`G0XU|4+@lSLXkzdH>-5)Ob+*pSsbS`G0CWHuL|y&0pjH)EjM{AO250_xTrt z|5HC|>%-&!)D_RY82q0;Pvz!Y@qcRGzxY4>`G`-$|HXaI`hgjJf57%lj}?03U0dEz zoND}^9?$(+^5mdY2YwdpH|Ki5~>HO@^{6BTQ-9P-FzJG1B`;DDa^XCKq z9XI|@z1I98{!hKej)(tKvmO5zH~vq}`SE{oU%$t38GV1wJioU-IzH9-Kkd)^3;(Ca z@8SQ{e7>3gr{?pG|5I1m=Ntd0E;lcR|5LB9RS8yf&Yse|EFgC-xqGa*1O*J$Ny=2jcv#OsTZxN z4E|3&Yvt15|J3ELypSv(Fw^({kNti2?M^o}wf+6!f12Ig)b{;KzyG<#`zQPQaqT>&fduj1K-pmJN{-3s2*yEZ1r!Keoun$zJ zZC3oQWZ@%^CLPY2?>+bKJCm2EEbu;Z*pT4=^z+gI`3D65rygnEkNJPr)bf97`M2y9EEI9&hv2u6b}nX3)fAgYRR#-ZSps=sn2h_c8xZ+xwW0V*X#;FMq!|^W&4p zWR?xTt_1J*(?7O&;{pGE%QoMi>t+6*9*@t$|EZZDi2sWl|EI>U&G`MZ-uSc=E`82> z(1b3*|LOVB_&+s%?a{qoN;UpZ+o#(6LHwWkXj>l_|EHG!Q?tG<{!e|hc}x7C`Y7(# zPj7hh`r!YxoyPygjsH{Q(eQt2?$0%Uf7g4Ey^T*fW|J3+8{GYmLMEl_X)c9HapPJ(_|1WO*pWa{c ze{tjg)WNfw|BD;{r)ECrt>1s|J;Xk*_&;su`1rrL@qcQ3A@l###peC+e`@?O{!fiR z#{a2D+1D55|Eb3eYZKQ0RZkhxDfmD2#FDlN{!d+)$@)KaUf)B4|I_^%)9%pV|I}mK zH%tA#8?P7t{yVq3c4(E_o;!a`>;HBc)R^*rYWY7k^Y-w6apV8?>edkaAKUSNYUcUj z|Kk2fxARIK?Oh*yAM@yj?|FWz@qgNm2gLuWi)kkTIbLu`i&m-Q<@&+g>&xBV zJLmnJd;I@1zc9x;=6XZkAMx|gy?<@mrM+jn4(a=q>-}>3zxlr|ZPT7I_x`dTZ+v}S zJEZ3UcDD6!(f8@KW)e7G5=59**qfi|I}UE zbV~lwvZ2L=D9?%Mp&u>P-lVAl@8|EXEumid1= z9?kqeb&p|vY?)%?7&5wuo!~f~= z^tT5$b@71g`oG#P|EC^SG%)x-JzwVa;s4ak+hhKpTK-QxIa3_`pBnFGv#xyqF{Nd} z|7rWEOlk0cYCPaShfVYS@q*0%)AqroMZy26@qqY0Z}W`I|BD;{ryiUs3I0#dx2!l5 z{GXcpi~my>78VBo7dP|&;`@Kswu!0U<&z2Cg9Z&sj(T^TA8$-qNwWJ-W4)Q*7=OKE z9%S5HPu#qoakG8X=YOg1{KW~uvkffjoxJ<`hu%Ym7bo9;{(*PV_`Kl%{(9$$!3UNd zm7V{mE}fPa{GS@1hyU|7ABg``4>qsG{694w5dRl9{!cyBd>j5xJ;Zz!{!cyj7+Y_3 z$E$w5qo>+>(>q@A9(-)Cq-e*>-h-y~NG9)i$vgj;9?5w-Ui2MDi zxViq}2c`$l$Me5-{iakOx^bg7^Yrk4+8+;x|5M`u@qcPOApTE{N5lWcjsJ@q|EHG! zQ{xBmf9eUx_fLNP@>=hr6Z-P+6TLI$-R$2ldQZ0f@qcQ1}d4Bl6xbc5#j*tI~8~>-~`QiWKKIMxg-rUcB?O2@Zd;a>QH|sNZvw44dJiY1f z3%yytcltLAyzzeD{bRm2^XUHc?GxT?@9_P+R5$$dac_=?|I_)H=ZF7O;{ox1YP=Wz zPmKq||EUMte7M3}AFhAxo8!aJpXj@9f5;o}hyT<5lgzsvzQ=>!c)QhmKHxpdeAbw~ zW_vTg?&DwG@6GYA{Plg_n*XQI8;$>q8~+zK{!cCc7dQS-E&mrc{!h*MnEw|y{!h*G zVg6s-%>VN~p)mNrxbc5#=JhfEFK+ywn)!VAKXrkvm&^P=HTR48e`@aM>D_Pe`-lJg zxySXX#{X%5d>{T#ojJK6_&;^2c|-i4dhi(~!T+htPAd)mFK*WVRcroV-1tBBB=d;O z|BD;{r{?kaKlO0)r}#hhfSvwN-E(?=@PFzy$My*R@Afk$1pk+rF)H{!^+kWYA^1Oa z)w5fI|FboKga2D^zb~?%eb=kEn7_dPsVnUF&GT2^A_`kUEf9f^n_3(e{ z>KETi@PBGNU*W!`ss11@yS_J_`S*$FrUJe{nx}O#ga4U%Xc7)qTD3d7s)3 z8??Q~{2259^!T;r%kY0{JXh6kyQdoe$M4XBSA64x;QzkqFe&&y=F8##;>Q1}nMa5J zQ!{T5{}=aX$G7&z`{Dnzoj$2$b3gxjYv%vyde+(TUjO7!zuuZRKC*cRzwxep^JDw{ z$HCs5fBU!tQ+>gO`+MX44!&n!Z@gV?<*&WDKPSKOt5om#)BkugA8%=kJ-r*v=N&od zm);xg_5b0N-Mu&2>xuu1??3)e&FhE%Q_KIUIp2A0zVq$uUvtJcsmA~5ewDxae(-;B zFMpZ2Hme`-Fz_&@DmWuJfM|Ebx|{69555dWvf*Wv%- z#{a4LdV&8_SDMFq;qZIC@x?8Vy(`uDKQng0zjA*3pPKXA?=O9Se4x!kNj3gY=VLqm zPtE$i_WR%H`M<{RlfCh3_&@EB_nWeCTB`AXx*j|M{x5Fk|Ea5%Zdv)Xa;-|EV|G>y7_Y*Sv(6+{e3dr~lLTP3HITf9j2|y%qeQn)RS< zo~3VZFt0o-^HS}s%#pz_Zh!q9^Nbt4x0xq259hsZr~fnK7QA4iz24@Vd^`8wyi}^q zUwPyA@PB%IcD>zx-grO!pKrI{SDV+XQM3Ls{!g9te!ok#dA+rIK3p&VQ*X2Dwe1D! z&E`$;e`?l`#Q&-5v-^9mxA%)(Uy;twye0gfnt4n1-`?zx|I_w5d%f|0YUT&x|J2#_ zGUt2moJZ)*JSJP8*_-tm@qcq{V(@?Jx}E+{y`cPsF#k_| z+04g+|5KkbZBFoi>fyyVm{;sr>^<<#WbEu7-lL2E%=*aQ@_)9bZ}5U=jJiMgKlSm` zt_}WA$GiN}hlBr9KXUzz!T;&`-FL-R=2=fJ*6USu_4&!l_kZiX?2^-i|I_w)mrW1; zPrY*H*}?y*SIoLD_&@dQ)r*4vQ!lNr3I0!w|LZ#S4nJSb*6qRnX?y)s&jkOc#>e6R z)XclW|9P9g!T+i8RAYa9qN&aA{kvh2H;-RBbE!9;?)cFwQ;q-A{bC*<{!d+H@ArYd z>%5oS`9J@$(R-!+dl7rTc~{!@;kRu~_4kvXZfd)p`OTkCHU3ZM<9hLbapV8=`c~R} zLj0e)!qzv&|EX8ldYkw^HS<;Re`@9h;{Vk6AN-%1^@Q<%YStUZ|EZU6cq;fm^^(S| z!T+fjHf{_4FK+ywdYSnk{GWQMc^CYjdY-K>ivLs3H}8l4Q!lq({PC|dx<4!I`tX11 zm9`!Kr)GUq{GWQE`6c|Hda2zX{GXcph5w5i|EHG!Q_KIUncs&0Q_KIUSs;{Viq zp7DQb*8j!-#f|?{Gv5#Yr>@(%{;%$Dy?vgT|EFGK->>2S)NAeYkN;CQYd`8ddd8G$!G80;M;2|RtNv5 z$N#;uKKMWNH`R^7|EYIWGz9;r{-V4-_&@bu7S9R(PrdFBSB3e1>g(^iEBHV4>J1x$ z|5L9sZ`X0)?S6e5Z2ey5|LK0OH6O_QKQ-PF|EFd<{!i~88vm!pV>16QZv3BG{x9y* zx9`d5@BjF|bGQFF)%ZVc=kfSIHQo>Zr!KF_`oFmGf8MrU@RcV#=)JnSKKMW1zH|Pc zdbQ2}Tk+(>navI3gWoH!tV){S|A_bMitPM9?Z0f*>g0#t&Gqd|R;&#EPmf=`VtMd? z>P5ExFaA%xVDXaR|J0AoUywXCYhGs8L&pd2xA@U{!T+fjJUllUy5Iavr-kD(`*#0b z$z%8bIl1Vkrk*@%c<_Jvd8z!LdQj=%$s-dgGx~Weo(BIH_alu}nf*r}AN(Ba|K3zr zooeR)Y5#%4vh)Ac`9qo~_&+t<@qg;#QEh|&Q{(CIf9fLhR_`rn@blrrw#;kvF0=V} z%O73mjo-TOk@eopkHi1z`sM%PzTrO`Gov0qF8IDen|HVPUz<{m|I>E)KlK2+e*B+~ z$9yyVU)=b=xbc5#=AYsJ)J5j)@PF!(30;H#^Pbox8FA6`P1~(|UGRc8>*XGL?u*`| z#&u7UvtII^G_Gs%+37EP<0YRz3;Bf;{W2t|Ebv@|EFeu{9oMo zKQ-PD{}(s@PtD`;e{tjg;>Q2QjsH`RF+Ym`Q;)Lu&t1*_>W#0%|LOVC_&+u4-!lJC zJ=DA@{!cxARGZ-c;>Q2!eDZ&BHZDq+C1sCb+;0AuJ_CBT<@3LtpCdVzga)63;wT9 z=XS|m1!t9f{ZV7^d_%jmO@8s4v%QCRYoA>9kESl}-XX#NY5zh68}1plXIeOmmVx}a<4;Qw^|fn7QU z|EKQLu1)ZNYCI$UPu;0?*8i!wU-&Q1}nU{zEiyQx^?$x_{nEw|y z>;J0peLsJ2al`hfwgkUObpD>U{w)44Zv3CRf4>32|HaMvzv|xR?U?@;cfp)9ym^0rUVD0~@qgN% z?f5@+ul)YO|Ecj~%>Pp}pN{!|>b^VupPnz*ga1?Wc>G`7tpBTKz994e)ObVupSrYf z|KR`B%xCP}=@{S6d`JABw)g7QEBHS(^BbA}r^e6W|J2OO!~eyN|5Nv~`G(K@=SXkv z7xVx0{OPlbC;4{P@6A7MqIaJn^Hwt_HtlcC{69UOC$-ZB_@B6nq%I^Oc?|Ju| z);lTt;@wo^{|fIuIe5YRWBLXE7dQS-jc=R(#hd-qE8_puTo3+FjSo9y{PXoIOHT@(Z-njt)%fSU z@qJq+Jez9#pZ1skiyQwJH~uef{GXcne&ZXq)Sq+TiNX8P_&@bH^L_X~H69TEr{@0Q z|Ki5~sd>KmKQ;FQ|EJC~KZ*ZS_qX+E@qcQ39R5$u{j&7~yzy-KKW(S+f9e4z^bh_| zU0{9<|EHchePHl^>M6EfGX76J*0$sS;>Q1}Szi_Zr)K?B{GWP+oge=fH~uef{9oMo zKlMcOMEE~7z7hYY=K13P)SM6hr)E7^{9oMoKQ;6J@PBI7|Hc2Q<^STw|EckO_`kUE ze`Q zkB9$L7ntwE|EXDj7yqZm+u{G>#{a2{?0T607dQSdZv0=|_&;^tDOvv)cfT$({rPkJ zXS&{)YW$z>AFn_DPtEIpZ?EgTdA;#}IzAqd`G0EW`{Do8%=csdpStMutp8IN+IqhD zKlKp1{u^do?B}D)FaMqQSnH3kx**kuTz8%~^9J#MIv&?M> zKYUuRWL)uS{`i42#s&XpYyJigcV?RdSm)3z3j zxBQ>>uQor?_PY_j9j~#q*>LZ*<}=PO9_n5F{2R$ZCk;;Zni~gs*S+*sa>BxrRR7}X zVsCuklYcAp#{W$?upsJplJEKt@MeA={!h<`d4Tx8xbc5#{MT)pdU-SdE${Ol-t{)$ z4*#d;PvifXnSuYS#k1viN%iGZJ9*>N=Kj8eH=b_G1MR$-hxgZ-Hr~&^`*Cv6JFUF& zeg!|bNHzXX=V!fL{GXb6g7`mOFXzMm#f|?{H`@8}e{tjg)O9=kpPJ{3|5M``@qcR0 zkN;EGS>ylI4Ys~9{!h)kzyq4^?)RInF5T4||2F;9B-Ov%@85NL{p!r$O+5Ms?^>I$ z_wXa%dh`Cl|LJ_Ze}1|2D{uKf-M`hZycg#GsaZdIai5Rs;>Q1t+GBF?o|Wda@PBdN z`Qz)pf1PcAx9Ambyj9n0Uhrm~CjL*4r}2Mko)7*{=cn<1>Z+Hs{!d+DKJJITYka%> zpSH{YshPj`{!7b!f7WB|e#jDUyxiqe7kaav@RkSWHMM!AgWj2&YW$zBpX1~I)U5A{ z|5MBV#eMDrfAa14znVAxm}>l=_QxOM|J2L_yz`W+{d)NN)aA2FQ;q-A^JiWm{!h*E z?Dx~&eEqZEccL+bI zP5hsFh4~5mpL&`7J|F+5o^R_5;{VhOY@QbL|J2L_!vCqa+B`_+|EZZriT_h?x353= zzu&e#D)_(W-gr0oKlOI|`j7upH`@Bk=8;m3|I_w5d;Rf$>IQo}{!fiJH=E(j{3q7` zU9$bC;0d$y@P6ZsFEOuIqsMQsKX2@Myf@qX#g6aIJV5-P_OG|k2me#!1@V9CT6_KQ zf9mR;^Z(S$*R=h8d*e?37hf;_PtAN?vnk#@U;Ll8;|1}5YJ3a+PmR~Jd2gvUzvaDb zr~lLbH2zPG55)h)ZGO_bVe^a0umwr6wpZ3|v+LQ@`;nE;T@T|wt0p_y-zy+#^n3SWBhzq z{eCX@(|gv9HwFKv>%V!Y|I_QW@`|&9|5Goy^fX@IV)cT{P6+-_z52$p?elU?u|5wg z@4TM*qTX-UE)D)q`!8##4gOEPX8V@l|I}-@YzzKRUAO(|;Q!Qk7W|)@`BwNpHS^N& ze{tjg)c7L&U)=aV^$Pp?fd7lzJ}=(P8^!(AM+B|EU+-`xXDEUT*Ji z{GWQIeID_DYUUH-|I~av#Q&+ee*9nD_&>cLs_gple{tjg)XcBL|Ebv@|EK2u;{Vk0 zf9eMFLD&56w|;)QN8JzJtIZR=JM-V(xwH|MRx%!T+h5KZgHPg9I-@qcRk zDgIB5$Hf1s@o3EdQ{%aq|EHG!Q}gxtp}uW0dcWb#F8)osROA1&Kl9_-z0=XRue1IC z-O#zI&6mCMSXb|j_UGZ!nccmaSBd}A@t9|c|I_&!?a${==k(6#^UQkI_&+tC7XPR3 zAFA#A_&+u4^Wy*1Trczg)c8F7U)=aVHNFu4r{?p3|5M`~Z`ggPcktsM4fC$qnqB`_ z`_s(-Q{(mUfBOD~#{a2VPaOZJuC&(&Tcs|y_bcBU>-%HA{^0-AydN$)e~LHv_t`O1 zo7(ON{!hol+u{H8cswNjPtE(K-})20>+JnIYtBjDwf1?#|LJ(EY&-r>&GWl=grQ?K8&E%-lO-#S|l8ULro`{Do8_&)rfn)QS6e|rDW_&+u42jlX`uz2#x|XC8ZC zV(@ttYwMHS_n4jPfBkP$m)rcmGd_I4x6`jY_n`MGThD!P-9z5XtFr#jk8j=+|EDgu z^?s-Sa&FW0tS%4!Puu1H)SCaNUbuXD@PF$0PcBZH&wD&`{MQqL_j~k-`N99G7e4+( za!9);GB;j3A$Y&J4?dh+^oJ)hC9jRoTy*AzC9`e*-v<}Z_ntg%Oz?mDd0bwf?EF7< z-~I;&|EHg?4lO+_soYSR`C!Ni!TXII(jvkCsad}l{}=apYu9-99-5v1r{nb++#<=8 z*Z6iG-(h8~cfqi>$v(^KyzzzjKRq5Fi2u|1@Ok(@HC_(?r^aXD|Ki5~so9_Te`=10 z|9kMk=_&sgH~vqJ?_>U7-1t8o58sIYQ}cZAe{tjg)Ep20r|xY&3je3>YuCs8KQ;5y z@PBIN-qzv2JX_(}Yqn)!hEzqs*#YOW9er^ajI z|I~Os{GXcZ#s9_q!|->#+5dwf?|E~4{Gayc`1n6HuRs1TZv0=|_`kUEe`@)^xbc5# zt{4BO=KkXU)Me%?@qg+;wjKYc#!KS=)Z<2X2>wrvkGuSkuY7x%&BHtSz`uF3ebjz` z_a17G@BQnqy(f?8lpMC#H{O$mbqMSK>iC04wF>M1#*P0|bA0??+|2(|GoKItr)EAM z{;#RC{x5F)pBm4H|5M}r@PBGPFZjQ>=ePRVKX0WrkMy}C{^MOXtbKCj-bsl*k3)yH zOYZn%Q({z>O0Q4Kys7y2>&)}Q|GoC``r!Y@_2?Y@pL$HUj=}$_^SgHm{!d+)*CY5p^+cOb zh5u8J>()JC{a^Kf9$k~QgD&vqc->oE=snif1D*S0Q;)QHY52eIsx}0#$ow$;pSpXe z&cXkw@r=y>iyQyv-LZ4(`Se|D#qX^)uO&2rX@Zr!UaaX^+xK6`uc_t#w7qki?E1gzwzgjGKg|EB z@qPF|ouB!K_&;?Q^Mv?6b^DI3!u&rq-VgsbeAd?B{|-82-{Ak$2ON~0|L1+c0m1*N zS??GBr*75ku;BmH_(lAmnt6=)KQ;69@PFRs_n7~u?wi*=dGvzI{QCKNxNO#pROA1& zzx-d^_&+t?tH-&Qq#FOH?S(zF{_osb+cKx@_gM*z|5M}rnE$8!<^R;o1H}KujsH`# zKlA_8?2rFb_v@RVyz%Z?zMWq9@833czkbQ3M>KVQett5v@XXZq z1CBW()gN4Tx_9UNe#!FtPD?fZPtU)f9UuP}H}n70ea#=@|I~#=CBgrxnO8S+!ij!- z<{#q!^!&Q@v3YFf|I|JE_Y3R)stfuK2>wsqzgOSj|J0>Ddk6og&UEh;{GYm@d+)IR zudat~fB7`OUcO$ueBV^>VFg9W^%X}qwfV)om!^0#zYzcD$G3TT_&+uGAOGj)%eVDr z&Hrh8(ZGJe|EUKQ^b7t^`_uS8HU2UF^K58odfsi>pdqR4%qxxe=k<-d%Yd|}#{+iE zd{m#5oD%$6@PQ?N@y7qXQSzbph!Hjqwe$n;u2cF2|F`M$Q-UAtJ~co1KXu8`S^uXl zo!Tck_KSDwy=^|=#b3PbT{5+oy}oaG_dhl-_&@ERZ|kw*|J3+2{GS>hi2qaL-F6xE zs$cJzX?>D6N4?^W|64u!WpDf({!fo*{b2l`n)QS6e`@?3{!jOh#{a2V&lmrv#{1#_ z;{I#(Q}u=SoE-cf+h?xb?#=b!|Fl2Xi~oxo|EI^Z9sd_M{!h*E@PBIgKQ;3c@qg;! z<~Q+wapV8g%y-29sfXD0Q1}N7=kb{9oMoKQ;G*`G4wSTkjPAryhT7 ze(-;BrQ{!fkP!~dz-AO9CO z{!cCc7dQS-&GWm;Jdts+4b)Gn>)Sb z|MYp}`Q!i8CFTL&IQ&n(f2nQ%UGv+$d4B)X^0rhz*6LPod}BeIKc@Pnwtw*E^*X2h zEveqUOTC#_i2u|1@PYV0HSaI{pL&?Rp7=jC^96_BcuuPE zf7*^e#Q&*#+x*ivZ$I6;y?y=O>&{cXOJ|HvuDs;Pdi%fd^XVCP+?v?WdcCWke>$;$ zJ6=Di)#Tsg@jzFn;K}$|Ecj__&+rs4F9LDwe?@|f9g8(U-&-mH(i>+;UtjppMPzR=NI{*N`a@Pcf||EafFuW?mWo zPt80#{GYnk<|X3))XYo7|LK0?{qTQrN?!SCTo$hC?y+4@$rjVBT?vq+R?7iI9KV5p#Z0{Aeo+(v(xViTe zHt*_%!w>O((7Xu#PsgM2f9g5r1@M3BCHDTu|EZbZiT_Kr`M=WLj}HECt9_oC|EJz; z{tf@9#>3(N;>Q1}@pbq=HS_H7e`@?3{x5D@pV6E3e{cKCA*sgyrT4E$HU3ZAnLma9 zQ`eeL;(zK!^L6+?^*VdM;{VjlC$#75jUUASY5UIgiHmk$esu7PH2zPGFTww*IUfE` z&7ZgUKQ;aZ|EI<~;Q!RTKkQ1}ng4|UiyQx^u3z_b@PF#shV8-sspl-u z`akvAS3DH_pZZMmf98RT)nm;6neXu)*8ldz=5=|GExw2Q<9+`?h0>^?KZX^_5}%pL*%@_co&Tq<-n1q7Kehayn)Ph)e{tjg z)c70xpBk@)|MT9wJ@`NM8uM@XKQ-&?;{Vjl1H}KS%gqDTzgq2GVPEggd#JXl?R+gy zZuI7Q?CXIy*MH4lw|MjQ5dWvw2k(dfQ{(;ce`?m}#Q&-BNcg{P)20SbiWkEFsqsYk zKQ-Iez3_=Yp1$ybFTC-StxoyM8y{!ye{Xyq{!iy;{Zag%dWFpc!~eyN|5KNnZ^8em ztIZ?g|J1DijQ>+tZVBsaXLSAYe`@^Sk-O~e`^*37@%TghpBn#&|5I1n>y7_YED>f1vSyapV8g zyg%@NapV8u#{b2Q|5Nk+!T+iGyx{-TwKk6s{}=aL=Ks`OKlA_8Trd7lU1iS~|L5PI z*!{r&sWtykU2WU(f9jQXe5{pvmAyasZ#CW!|EKSlSc=KpCs>jC5cbUkZqeR1ahsaLKsZ*KGd)U{P>g8x&0{Qif@QP1A!+yC?NTgie+ zGyQ&i`^Izj_ph70|FhP-lz0E_!|LJ;}kBI+^8~>-SZrBw3pWYu;^&5l#Q!lUIlC0VPu8jV^ zx2$e+^2vXiy1aH%@PFD) z82q1lmCgIZ|EX8odcXKTwfvvD%8rNsQ?Ii1f0_TMt|-sW|5I01R42F2oa5V9l~*LE ze?2Ety?s*fdn;@n;DPVX^S9lN193K3i_Ae}L9{is=e{jp-|J1Dai~m#iHt#p3YOQx(S@Yokv^{@N z^Wgu~1MPVDKQ$ik`zPzYS>F`@=i6<58vaksd_er48V|PDuhwV2y!*u9`RLwzZ183t z+_AfDOf~*b`cG5=4E z@5BG8<^R<3e`@)^xbc5#&X507 zZ2q4bABX=_1BkcW+ z|5KNlFU0@FjsH_?{$JeqKQ-s?-tAxh{%8K*lukc+;|s58_iu0J{o()gc^f>WW$=G$ zw&VZQqwMPu{x5F)pL$S9^Wgt1^=g>(4|}Of9m1gx&{BI9@e#M@PFz-?b-$Z7dQUzxQjLg|Hpcw_&;@z_FaSj zQ|Ikm|5x3!ZFc@&+Zz!pZR(@o~>K6gH!wG&JWD>ZJl!F;dO3vMC$Q*x&E(Bi_~`3XO6Eg zcOGEwyujS<-7@X_dNoh`JJw%~kDu%HdL5Sbd%2zK{c^k2;pzL;u4VfC2OgN7$9VYR z>Fdp%KiIcL`hFZ>{w}`$R>KCTdi?OTe;JpvJ%3=@19mfy%lyBNd0T`38``By@PFze zThE&Lf4BG97W`k2R&9d+Q}cdi{a-cf6XXB%csw8e&%0yR|EZa;iT_jM_n7~u#^193 zubTOO_&;@5`+Vd7bpHO`vh)Acy*jiF{!h*PK<59c_dH;~;Qtm++8+F0>jU=*{!iWM zu!F<=KlNdU9Txnbx>>Vk!T+hdAKWbXKXu-rJ0u|_ zA<0QX2)&6QA|fhcFWAdiu`3qrir5fEdM`;x=p9rn*vmLGmT_hr%hmBt`M#f@!|Tmw zpS#v?{`k#WcU_-r@3YU|`;;Jg`2Ga{r|#IHbMSxau3d6cw|BeV&nLHYm((M}uJdL+ zUi_cVw<5P&@PF#^oUSSSpN_}8KIZ?a@rC$5Z}WxtKXs41uBl<`uc|+M7d{;wMEhW}GDj}HH*&d==<{GXchJ7o2RzCAZL zH~2qo=Xm%(HS+=Se{tjg)I~jVQ}{nM&xik0x5(`n{GYmYewWlu%g*-gg|@!&z_-VH zbAI?g-5;(8|EI>kG5;@a{GX1G$Hf1s+nevi|EXE;nE8Kd=J_%IPtDIq=KraAe~dY3 zZ}a|O{-3tf*PM2$pAU`y)A{wv%L)EZ-LI%1_&@bX^L_X~^>DksPrn`M-J?g3u>P;M z^LfSpsrmVj|I_(Y*gRh5|Eb&A_5*%5EYWX0HPpM}>h*~?>+P0Q ze(XJ9R8H`Jk9;*DctN}${x9wgRUi2N_`m1+yzgB&HZOHe-}k)nf5ZB{o9K4^cYEXE z@P9gA8vm!}@%X>E?;G@{H+~QQr}Hba{Y!?t;oI}f1LFVm`0lozEB;R{|EHG!iyQxE z#w6kY)B|mvU6a}^zP+E#FI>KAvo}5u|EK+F{GU4i)NWz^pBg`j|5LL+^Z(+;|EV?q zFK+yw8c&G-QxCNHcKAQ_DduVLf9g>-j}ZT-mj8Gw|5Nk% z?;q-RRl`ekqY*Y(%V z@GcrxnA&yyOMCmw{8alJrzaZ!r~8Kw#Q&*F&D-Js)c7>~pPKo5_&+ti5C0c8{!fj+ z!~eyN|I_ud9sj4s-{Jq%Y{&np`=3)5{GWQnIqBg4)WglE;s4a^kN=DN6Z3!SKIYT# ze{tjg)I9&p;~w(n{K^|X=#B5g|7m|3|EFgCWBi|*^^fs?YJ4C5FK+x_-1t8=uNVGL zjqk(%#f|@qoB4lnr!1^*W}{!cCc7dQSdZv3CR$i8p!f9j6*^TPhwyZ^N(2LE@; zu#v(4T|4F8;Q!PscWn#)@0ov&4E_&~f&Wvpz99Zjz0f=j{!hKw))&S9sh61l!2iXK z|5ML1|F?BruR1;d0`pDZep&9l!5aUk{nwih#Q&+6@9}?X)=S0zsqtOR|BHL7`9C!t z4F9K=|5LNxEdDQU{GWRDp80?L4h;WC>m;Y1a=Qh24pzpujuJ_`9?C;I>C>3qWD&Ht%+{qcXgpR7lW|5M}ZnEw|y{!cyM?iciW z&HESs7dQS-&Hfwq-RfPl$Ny(s(H8dzgq0g z{JkUk&iCf^$N%a0OKd(T{!fkH!~d!Ad-y-~(p~S{`*WK2BJ)l7KW(S+fB)PxDlQ1}@m=^oHU0qqr|ZEV*zfnfH<-u4|7rVr^BU$4yqQ0O|I_wY z?DvKEKlMHJYlHt&-*3M!#s8^aw)rs^KYgh8Z2SE+{_m}xrvzX4puJxBKlPLEej5Cr zn$IKtPtE6*`G3cMaZ2!it8Kks{9oMoKlMu6j{j5F*t|gepIZJ;E&r$H=MDZ(&362s z8gGjKQ{z$be`@9f+WC0n3Gsj0ju*lIshJnZ|J0l9^~C?Fci8(M|EFf2B>qp$`r7zE zHS-0{)0CX{$mop!v&R3a@$>jUHS;j>e`@9xnvX2e@iPqgc=eOP|EVwP_eAi2>Y*L4 z5B^U*Fz3GD|I{OTX8fOeT-D^@|J0X^m>T?__u2P^`G0EspS@p7b-(Vq&;Q!Rjm&5<5@x{#liyQx^#^d4t)U5Z5|5Goq z^-=ME>ZPx}8T_Aml|3K+PmSln|Ecj|_`kTjF5c#iFZ=Y`*Ai{tFWz{?^8I#u*V*$g zx#ojXz211X@#UX*FEvkR?`Q8Co3Dod)Bd$~KKMWNLi>Kk|EXEu9{;DtJK_J-3+#U5 z|I~}@`1n6H_Y?o8X1*K#Prbyv7yd79{GXcrZN6rr|JmqZ@1>h}1pgQB&-_0%>z(8O z)OfNn=Ktcx|EXEu7ylPG{!cCcr)K^s{!h)kH~gQP_0aKuYQC@Ve`>y;@PB$gFfR}P zr(R|La_}#$y_vU&|I>En`!WAdy~e)Z@qhaKv3@%KPtCkO{Gaxh|5M||@PEF)HU3XO zKlyy&|J3Y{|5GnEABO)^<45s-YFbhl{~R~#|Ef72{!d-KDdYe2 z=WAYX=KsZQf4=hl*W3Na|7kn@^$p{_t8IQB{!iO!{GS@HhyRNk|EFHDVMl7tYZoQ@ zfVr1=SKIb8?wy$EYdT!v=eNv`&-%Z*->eVL`oHShwcEn{zqs*#>SZ?H6aS}Px^7E~ z^?%j!e`@(Z-OpOvAOELbY4h*!f9mD+Yl8n%fBNOuseg>W-LL0AfBkFlf4U$4`O9B| z|J&PN1^=hVubn?TW$QKg@$Y%|@!wsKbM5-z|J1u}efy)TC;Ro`p;`Y| z$6vH=Q}BQ4TJwSD&v?Mkw{GK>)X|SV=#Bq7J^!J!{(TPrcVEjX-t%kM2mhz-3s!9i z{!cCc7x(#RKbqFxM=ZB_in~vIEYbKsZLc#Ai2qa9+Wc<(pBgX7{6F;q+m8QJGvDu| z2~VewdTB)PdHBs=4WH`0Xn9TWf7*Zkk`<}39jEzr{NHbmd)9mTvX!Y7`#tBqV2}UP z@mUWT|EHcie?jnn>KQgK691=u)x2NL!0GAYoDsqM&3wt`Nt*vtzw*+{!T&%zwGU_&C8h6dvUsS@>#*dwaYmy^>+CZ?;hr1 z@PCsE#|IynUv@&Ob?** z@r1{5caeFfR^M*+{kz%u z4*q6~ckaLz!TZcp@IKiuKX{KI43+ZlDMRN33FCHmYqUiZdd;s12M z2AGe-|Eck3_`kUEe`>A&8#nX+;%5Gz8V`v7Q?tG;{!cyF{38BOE&r!xz90TiU2a|u z|EI1nZ-@U=S`>4ylO7txkf9=inwJ|FWx*J z|EKpqkH`P1@r(FB^+1~!ivLshv+p0~|Ec@i_YeM0J-jmG|I{bi_Y3|{&G*fUJNI@$ z$??Je>HLejpAh_?x?`K)2LGpS-K=5ifY0|WQ+I6B%>MRbujl(e-YRSUTlV&XHZ4+( zAGok=ZI?~K*Htvn_`jD9vo*)f1C}?-_&;@zmYMZ`oEUM+jE{Wv}O3-ZPzeeBX+yM4!?->HmhOll$j) zPx{Hee|kLY6XXBX z9c|tv^Z(Rc%=_X0)ObJqpSo*@j=}$_JK6f-Uu~M?&qw3`^!&^dWd5JJ^$EuW|EF$v z^kKpOsgFJKkl_CgJ$ifaerbiVjO{GXcR;s4^s|EbxZ z`G4N#>sbGH@$ox?2gKLm|J2>PWY+)H{&}5q!ur2zzK@vyr!MN;HO2ftb%&g8!T+f{ z=4Sk#n)!yz|BD;{r_Sx(HTXX@>kZ@o)Xe9@|Eck4_&;^JN9W-G)P>#J2LGpS+p%fz zf9jn4_QC(D<^R<3f4V^!)g@vj^`= zH2zQ9@qqY0HNLOalAV4${MxFeI}$x|`F3xPkN?x_!Tdtz|EckH_&;@@Q*wg;iyQx^ zmj6?8zpm)Kq3-BUCj<{iZ|l0=oBdnmu1hrjPmjk-GXGCK!2DUKqSd}X{>|q5CmR2! z{qc+Vzqs*#YP=ou|I~Or{GYnYd?o%*&GX^^)cwsf;{VkB%!}gxbiHiH|EULdj8_m^TPbUxbc7LQd=Jx|EFgCUi_cB z%(kz-XqF!ze|Y?*uX^JT@qap>9%GAw|5F!^D-Qlo&HBOkKXr-SZ~UKnpm{<3pL&qZ z3&j7a@n85qHS_iGe`@CS;s4b5HvFG@u&s}a|BD;{7dQSdZv3C_2am`9#r?zMPx}4? z&+U~O_|y~L{mg^CH1%m+Zsf4cqFL>InxOQP|AIzId3|I~Ov{9oMoKQ&$w z{}(s@Pu;`3AO25WU|tjdrr(S2j|HJ>O@i_QDHS@y8jObUV ze{tjg)Ofrh zKeSHtkH@s~UTNp|bWscM8arP3Y0bQsn78}WO-;O)n)jRhLL+bazxes^e`?Mb|EI?D z;s4Zl#6SJ#NWWhCzLrOLueRsM|LK14c>JGwgB|~d2Y%zd&R*ZG|e&WshYtn%qCVJ)v?Jg^hN2 zb3OP!e#eRz)%-v83Y(9K|5Gzx6aS~{;e7Ca>e=QU@PFz#=8f=w>P6Nu zz43-K-+0BF^}K&P<|Xg>_W8&E#pi?nQ_r^T_`kS+nf{nJ-!J$-ZD(Fz?Xvs*`1pfg z|MMPi*88*hCEobJ=kJ{4jnBgW>3GX*J}LA6;>Q1}@mu&mHS+-Rf9h)cKD2-K#y{Zy zw0*IyuZRCTdFJTg8JVYp|5M{-@PBdR|J2LYZ3yfCc5ZZP@Oraso(t>$s&8AkDEL3^ ze}7GF@PFzjs@DYnr=GTYldbP|pdbI0*FLb{H~*(r+vmOW`_!aP-+Hfm*Sw$kKRw@C z^L+R}o2eH3-}?7I3jR;M_T3NgL%yB$eDQzUPUHX7wf1^4|1WOyb>7@x{GYb7UNHVo zz1n`>;Q!*r|EcjX<+m=W(fQ+7%y)V3SueO+`_uf-duL|-Uo}5J@PF!zM_ig{{9nA? z&aXtx`P%t=ue5oac75K}Z?PWnW#00CdOUsx|EFd>V7tHGtPg4T-y45p9xKuI`gyO| z^tySt-+KoSc+uaz>sIefT~LuK)$^^Y-(j!Uf!@>S>@d%EnD+%&JR1Dpl555U?>N5S zQ?_1h6W`vi^G*03@5f z>5qT%j=O{Z)A>Ji<1NAespnsRMwtJne&*c4!T;&~^1_6H!T+giZk~Y8DAng>=0kU~ zzPR^WwTsNx-c_pomsQuKUTArr_u7q{Y#!$W-m5lkP3`;Y!``d6?y&W{ANOXS-Z@>K z_Qq=+_xEYui_DYZ|8)NBkN;Cw+xH>CQ?tJ2uTJ>W-p5-n{PZht*6%&*<-d4`d6*ad-J5x>Yjb||#?xK#)6d@X zZT@PDRsZys|I_p1AMt-`JQ)5@z0~e6{!h*NsQ5oMJ_`S*W_}s-|J2M6#Q&*lY+f zz90TiU1MGu|EKd|ejol%jVHtZsjF=}{!d+N??3#X8vl&{)8~!G|Eck*JwEE<&Cgrr z|LO63p74L#A5X{nziQTl#sBH^PUHX7n*SF!{!h(%&iFqy`_I{$PV3JH_})8TE%(Oz zjk~*7qKnS$ooM`@j>r28{}=a$eFymdJRkG_^n5h_&)e3o#s9^P|5Gnqzccth^^#4Q z`G4wKd;eg?^ykA>=Kc6*HQo>Zr~T#sw4KM}|Keu;pL&hG|M7on=JDbG)U5A||BD;{ zr{?pI|BD;{r3>L05UNwEgYRlisVW_uX`@ zcdgC$`*_Cn-b?oQKfQi5{!h(%x6J=jXa7Bp z_r~>GQbSI?&wHzR*P8y5z1P~jQ~aNfS7-ju{(SGxx6=N57W|*ir`kLq{!fi}#Q*8v z@8ti~3vE5$=Fdz?>+cg5*?PYZ-t(~cvQ_I+|GfGU@1?bCQ;&S}NP6OpCkKy5SG@OV zqW`wxG4C4lf%rcizq+PAHQ>1?eEZ^>y4272J?V}2d->X@yqW)p|I_o)_&@d1W!0%c zUr$XxanQ-Z-z_%(cl|rhM7=yUbM3T5zdi3+?}dvOhxvax-hxGog8x&`nm0fAKlO}P zXQl2R_o6>u{!h<8$L0Y(v1oew%`qc`_nS2%$QM`|b(;Pu&~9)IH4O;Q!R!Y`snV zU)=aVbxB2&;Q!(-Z?ej_=h=L(^BUH9hh5u9Iqws&~67x~`zqs*#YW9C<#~a>#2DM48*s{yJpPdi>Z+Py6%=*se^YDLa z`9C$j5C5kgYCaPG7dQS-jrYU<#f|?{;}4ntr)J(9{!h*Q!vCq6e>ipO$A132p7=jq zul!%!_`kUEe{tjg;>Q2QjsH_KKM?faK5`N`jU5488+)5HIs=(R(>^R61yD)r|9-zU03-ygh( z*u2W(${)Q4_iL6qyX=3wS#Ni8@lT0fTJW=XAKQ-q^Xs+7|EbISGzKfN{oPy3fuW#<3IjsH_KACUQf>RvXF6#wVlt6A`W>hkg?sqOpi-_h(`DpR^993DK=;2wuZ&3H7XQ?zF6FN8YSP4+4qn43-kXjpR;X` z|7#rlU);?9J9+W;;Q#P`_&+u4^Wy*1N3?1l{GT4*z~=Aa|J0rK%>PrfUNHVo&Ac%D zpSq3B2m5`&ZGL>bDE?2+*QrJ0;Q!P|H9I!=KlOnP4i5fL&3r%R|EXIYb42iem+juM z$NwFjIzhueI_fA_iGyQpL5;Q#da z&U^fyx=WWXsr&MIK(jhh8JfE(g_0#cx+P{O%XT<-hIUfE`=U-sYhyPRO*?Q#o zKQ+h0|EW8*Zyo%fx><*I!T*i?cxUi`ZEZf>Q(G?g{h3$C`oG$r^Y3xs-ex^${GYb7 z{yP3o-KJ~%;Q!R^b329ke`@(ZHS+}Ve`@?2>;J0pX81pKdG{W{|EYTy_6+_{J;XdC z^Z(QXx^@lzPtA7L|5cw{TpawLx~I**WB#AIsHiB_@Q1U!^D4^1{6F2l5?eo;`G4w@ zs`>{1r^olP^JD&>y0ow;_`kUEe`?mh#s8^$m8OILQ+MxG9{iuWsBcy9f9k5Ls?^VY zM*HJSN=i~2CY<73R#KRH^!8ES<)uZbv!x=uu($YkiRg@&UqB5Pr|CxCR z{;#r^t>0|^PhHi!XYhaO(!sf@w;ubU7-1xt}-7WY(H9qa%&%f`-r}2L}AG{p?FK+ywnt6iwKlOl7-Gcv%8~+zK{!cy7 zeBIi)yS(N9bbd7cFYfymy_VP?|EJ@zzApYx&HB3dKQ(?3|EFeNApS4zBU^2$oAAN8 z!SAvEg>5!_bAQ&g+mz@=9XER8`|y8yJdOWTGoKOvr)ECm4c*szv;SK?)_CI)@qgMs ztXFLQFYb>@>%5tdm|woioB4G3KV4smt&fZUi#y%7+V{ufJ>Gw1qVa#)AD@T+iyQx^ z^I<#wPd(6l5B^Whd_MeN-1tAW{GVF>Pn|b5Cw1VN^L_vPae1jT#?SLEI-^Hw#e}(u zKK#5ni9YXw*@?#g>G=3A{9oMoKQ&&9`G0XU|4%)@JQ@B^jrYUZobnLu@_Ql4GCo=K1k|Iv&qo z`S8=;9PgP&pYq1j;s3Nh>%Zdv)T}Rz|5MBV#f|?{bNsn4KH|;1!u@AF?9KTx|4;8P z&JX{m9%=Iq@qg+O=I`)-YVIHYPmRyR|EckO_&+t?5C5m`aaP9v#eGff-F|-f!Pn~U zN_5*bcX~5V@aA=QBpUyx>t}u9htIyvUk|+KtaB%Mb3XV#?a%q*|J1xcn@_*lo9lby zl^eYa?f&5ZbpAzlKk$EQ)(gh}saYQw{}(s@FK+yw_n!HGapV8I_xL}x{GXcjp6#D~ z|8n!T_&;q=kF@{(*!-V*^u+Qo|L@QPMhE|Q+5NYN`G4wVySAh@)(@>y;|;#~!(eaL zBRu@zLEiJs$Monrz#DIb|I_1_nODO9#f|?{SMQnsr>-%dg#S~oF)xDuiyQyvZQkkh zQ;HLP`;A53%xin~#RBiOd;H(9rK5vyoM9df|EHd5ehvSp#-ri?;>Q1}Yt5hG|Jrpp zHTXXo{}*?Q5$%0{{NCnk+IlbE{b}%j+JDKrpP8R(<&VdI;s3Oqd42dl^<49J_&@c$ zJ^oL<^4(9v{695b?Z-!t^XF$?;nORQNp$&#M|s!V`QiU`y)^#M+wK?sPmL$U|EckN z_&+t*ga6yx9|!-Z#@FHh)a=jvKlNI>9{iu0^^oy@YWY7kUJd^jH}n70)%N;-@yEX> z8vm#J#e7KoU)=aV^)g%k6#u7QzB}Xp)Oc3>U)=aVH69WFr{;R`e`@9t;{Vk3d;A~2 zQ^o)B`C|Rwxbc5#d?Ef%kH-fNYf$ai%Y4GAr!Gr0{!ja}9x47WZv3Bm$s6wl|EFf& zAO26x_e1$<&nJ5F3(t7ZwE1c8{^?2Yxpx0rb$ZMj?>F(XDc-CnjQ`W|S>F`@r>-_1 zfd5nDQ}BOk=FQ>%{Qj87x}?R`z8!C9zyI}SzMTC&*?Xm(ul;`7d$FCL{qE9_H_yBX z{!hoBXCA?RAMd@;zEAD<``-9P{NKF0#{?fpX&Uh^Z(Q{Y&-r>J$q$c@PF!M_WN4=pL)IdiR$*BdGCDt1AI>HmN};d|F_({ zAM^jzOW%19Kjh8#H~vrCGhXlUMC1RoeeK)9*Lm02e8#Ph53jxBUt@xQ#K)P>@RtA6 z<9U5;{o)$!&-_39pPKo9_&;@>y&krIwHjZ-|J1MU$jtxK@n^pld|t7dd5?CziN^nF z`v&u(_&@a)`@G@*)ObexU)*+nC3^lkd%SrvZ{|;$5A&A))8p&RN8$g}tL*c!|KxSP zKfU$wUEX*M{Gac?)z$+x|EHG!Q!iPzKKMWNbFXX<{!e}GrH^vGrRoa`9uEFbJ+{Lg z!T+gCawiA>r>-cN!u|2bkFC7Nyjh9&6{DZC_gio8QRe@;E*|K8@gD!D<2`o!UBUmU z@45DO!T+h}U2|sYyEf;S>VD6-i5&WNe)%9lv|EJH#OZVRz{GWPP&3yZO z-BqeywQ3dfki55S*&<82|J2L2zm~e~!>4?II)B#Q&*R z*z1q~Q{&mkZ#>SM>o0k=q4#ua{GXnGhCSZAuW!dktv|7uH=c3J;^t|+-|&4c9&72n z((Z@(c5mLVZ;oo4=z*WKOY8H+e7=|JJ9y(sZC-Ao@qcX_te_fI5`}2Nc z{-2J&&b%D{PrcT>8U9br^)dfX&3d!{IHWkOpa1x@H~(DX&HA$VKW%6J9{x|g%D#W` ze`dEuGm)rLZ{x9DD-C-B`cIFl4b-u*A&h~%cpo!l2yP9(^-}`v;d`DMZnP~i< z?ibz<|EI25yCwKP^#beVx8LB~@yPb)Q|}e_`26O#cr)J+|EI^VFn^5yQ!n4Jl|S$L z`P8l1kQ#K=ZQk{3H`>2X-R{>@y=G0S{5N-auUfx8_&?pBb(=N^|EJzyzItwxyZv~Z z?E4-6r{|~fe`?lm#{a47?e)O_sn?tTJ8bi0Ki-=4n}h$;^Wp#Y9sPix--@*x?B6#Z z+}nHR|LOI{|1F;PP+EUKu%s^I|J2J?ZwUTR&Hng5^^%%3!T)VL`IO-QnE!|WQ?uSL z{!h*R(-uAM&3eE1KW$%FvpV=c^}H1s|EFHEye9SS5l^ST|7=w7eM{}n=S}{-x0f%? z_&;r5w#5GXAM=0eg-bL3PrYEtvK0PLy~w=ZzEhv`Ubt{!D(9}}z30u%_&=QwjsMf* zXT6e{|EHd7{uBQxv&H|Z<^R<9tuHQLn|@};gy8oEng1Jh$vW?W=Kofnzup_) z_1Mn!=~J6bNH@6cmNL9nddr4HWaS2 zga3;g|EFeu{GYnS<_qHg)M@iz_&+s%?9&ZzCiH!0qr|^Gj z=11cH)P4H44E|4zzr+8jd4J;n)Vv?@e`-7`{!cCc7dQS-pC^uo|BIXXf7)OEPo3`F zB+UO)bZ|1+@|1Q6EOYnhs zCg%UC@pt&Yxcf}F)H}abv#|cJw)be=Jk`0$WxgHX_xvw=8&Aagzw$fse`U$&R)Wj-rDpKR}!-5s;$J+^I; zeE#fthS}@u_G*~izp8Q4%Vqns?Biv3_Wt;y-K|H`^A(hqCAJSLPA9soOVSHAZJNBF+4B~&{bjqX*CX3+ z=Gf=qh`%@N2vuZrpx{H=hUmU(YLcX8fPc+r$5<+jnf0daL6d^~YSWBly7% zo!SQf7dQS--LbQ+UvKmO)a?J(vA6s2x^!%t`rwt@yzy!HKRsV_^R@Utb%Uc14gOEP z-?6_9{!jg@qcZ+a-QduJga1=EvGuJd552Yit*2hgtp97T7yeJ%dHwKzYP=u*PvW51V)P{+#Q5|E@Wm!u&rSFDEbK|8zXoqs9NJyLE0K{Gay6&*A^n_&NNa z&c7tLYw&++JRbf}o!hlz@PBIgKXn`P-P>kev3LLOorC|=cINHj|Ki5~smpA=TKu1y z^_cO0>UQ@2Vf|lq*PIT)|EXEOmHB__;vNOT|Eck1_`kUEe`@CaG5=4EZ)5(Sx?j3D z_&;^u(w@Qpsr%dK5&suA>;I}NipzrkQPR`m-0Pd&)|9R5$;yJyD# z?d^i#|J0Q>4-o&S=KSz~YR(V;=e@`Osf!D{hxvc%(w;q1M>IIm-@o|6rg_7>i%Sbr zolY9+o$d9?%97ugy|d<>_N(lj`2OVn#NWT^ta+$3{?BG01^+jwv^e-b^}v#h|5H~E z$_f5YUA4#msY^z73jVKW;f2Bfm7d%=_&;@-tq+XSOm_Iw`xevT^Y#tl_ zPshin;s4^s|Eck5_&;@(c|ZJL+|2(|Gd~air{?(hzqs*#YJA<8`EMlp`vtEj8vm#L z@qze1wfvu2{!h*N#`r%q>+{w$-&(iio%4hD<9PT#HRpr>iyQwJH~uef{9oMoKXqSQ z9~l3q?lZb;@PFz-qw|9QQxCD%2mhzW=P~~;Zv3Ab--rK;`~F_FiT-2nnndIOw7>kH znt6eL9k{}`Rp<`G4xtaRtHuskvVK zpPKo8_&+uC{qTS4B3pkK|EDfIqkEYDrygv_$N$BR|5KNn|HA*NgU2%er^a(l_}`c6 zzH5Dc@OgNz8~;7sdx-hL$9|RUx%<87+k2f^oLYb23*NoW^L=>m^NGg)>G*8N|EY(J zFAx4t%{)E)pBjHRqT$p;XXceG5=3Je0(~E|5M`! z@qcmS|J3+J{GUFbH2zP``QiW6_(c4ln)Q(Je{tjg)Ob1kpPJVb|EI>^HL1SG&j){p z|I_)&|HX~}^WNkC)C27Gzy8eI{eH{;>GhERQ+GeJDEL1;zQDX5{!d*t-sVl3|BD;{ zr|xO5$E|aI=UseGX)1T&b>4VC{GYBDpZ9R}Rf+AD^;abN`*oLj;|E{bd}*Rb?6}yQ z@|2Lm`dglMs z3(b?^|I{nY+u{Gz_&NNant5^fKYphb=Kt+k|5uHF!~bc2d>8&tz1;R^{-5@z8`QV- z?VSIL-#7POWB#t({Gav@^ZCsG#m)Rbb*&wb^?%jOm&5<*`Dy%L-1t8=J`n#GH~vqJ zN5ucBxnBIAnt65jzqs*#YWyAZ|Ki5~sl$9b^M7j27yqZ`e&YY)X8xa=`GWYrxbc5# z9*_T1?t33uQvaK|I_iA zFNpt(8~>-~eDHs2p8sEGZt-TGAO5fRiqnDzr15`hK5zSPU**p)|EKF+Zr%$2r)C}= z{!h=xdb;>Ob+vgo{GWQceSVq$r(R^f2>+*^zx}P?|I`b2zGL$#pYiRi7mWY&?dAvZ zf8OQ^@PBH&9sWKgM~_WN${<>n>M**(mg^)vB*dOcV_6aS~iZKB(T4*pMllg{G|I_uYxA!0ZPhIooJ6vChjz{DF)Vx3N ze`c{+P7MlX#AfZUv2aMY`&v+?Ur4fzjytb*H|Cg8~dT_g2ga1>Pw7N6+KXp~-2f06`>eKt&75tz2 z@>8b<|EC^t-W|dJsV}%`D)-aRZ|bB;DVycx{m?bn*!7<2J?rYzga6a@yfpC?dp}Gp z)%}})@hH{{@~*x9?BM^jefH$rg8x&0P|N4*F5kay_3GgNw0*;-O~L=ES?{pvn1_A; zYMYm5>z{iwKM((>{b~H48qb3N)A=*s%-#>)%kBM%|I>CF|EHd7{tEx6o^SpY|EK%O zyi)w1n)Pt;e`@>~{!fj+!~c12-4^_xda3yl{GWQE`4;@2dWrcd{GVF>PmTZkcFX&| z9S@2B)AkiR-w6Isz1n;f{!d+J-)9TW|Ecjt_&+uN4F9*cGyYG_{6YMmTK-SX`QZQ5 zydLM*a-{9oMoKQ-r%|5L9qpN9WaFE!6N{Hovj^D+Mq|L4zd=ZpVS z%YXlPnKSIj5p_p|I_|>Lj0e4uD#wzO>X2p&wl>l|Fj(+H*r@} zKOXb_@PB$f`M6m4d)M0gr_ay=Z`Lnu+NCJb_&+_Kd4c#pH69TEr)J(I{!fiheC(Tw zwEld-=i_f%D!uu9^nazwoAr#R-`>|7FZr)C`+Lt_w=MWT9e=)gxrL1e`}Sq#`wsbK zNTTh}FNv;SGTfVavG_loA6^ds7dQS-&Gliq)XX2`pX0{=#f|^-#si!GiyQyvZPzpL zle5$M^D7<@|EIue|mjr{GWQ|nvDNbSKE5R_&@cswVP7kJ#niakH-J$ zeCAu@|J1BMj{np3Fn<>Rr>?bmg7)9f`2MTy{xJVfkKbtD7x+K*Hv7Ig^|$wUZ?&IK z_UCbL)@xq!^}XI}?Eaqh-hJL{H`x3_^M5*?{GWQ|y3N7=>HP3}_&+u4|Mpq)U|Rov z&pbc;pBjI6Z<{G;{e1?HFKqCzcTL?|`}fv3 z9`ly})A1LrtWTXg_zB;>a7A6}v7#pvy|(pJ-iwy63jR;ew{Tg;|EckQ%>RoU|EFGT z>;E$UPrYby#{a43FIgP?U)=aV?|BPSp`YlR#z3RN+{Z8&z8T_BRvg>by|5Kk> zdP4Aj>b~VoQ%}rWn!aTHxxvfPsaeas@iXVoSngevJ|XqS^D7cv^vudczxYJ8H-7Lp zkJKa@|EK3?z994e)TQQ;@PBIN>*4?6KIVqiemwlsP1mgP#$)0C{Cdpy;s4^s|Ec?% zC&d5FZg6h!fBnoG;{VhYgIlGTjiv52B(wgn&WCw`_&+uC0`Y%p&IkXe=6sp|rn?6ug#b{Gayc{^0-A%+tgFsqu;Uzqs*#apV8g%-b7X{f_rA^Kz4x?M^iQ zPy6?^=g0r4nKy|4QxCOyg7`nR{GXcjd+~p9GyhM``nSygQ&*WE#Q%BQ{lx#N<^R-W z1Dgf^7dQS-&3s1upSs-M5BNVd{to}A#>?UV;>Q1}*&qKGH~vqJ-^2f@c|YL))VyCl zoB0=iy*b{1m;Rb){Gaxh|BD;{r)GU!{9oMoKehayTK-S1`G0Za|I~f^wM?CH_0N8O z%=6oP*+0B_|FZtC_Q(6N{%_o@|EtCe;{Vk0e{nPaPhHrjaqxd}zb-{*T80sViEw zO8xxwh2A`V(A5`tvz{>iZ*U= zpE|c)%i#aK+q4V*Pu=~ zGV%EKwjOMJJ=yaUJ2y;j&pv+kJizREf!Urgdmdo+`o1|$lJ`G*K4OO^%@XI^GHd;2 z=HtcJ!+N{_U){EC+r)O}?cx7MH`*EeAM@Jqf9mcX+6MpEH1GA`{~CAc82q2QsrfSe zUv1mhg8ySZTGszn=XL2C=KrbNb}>(8{!iV$Ti4+KbUb_<{!iV$V`l!Jx?!8f!T+iE zJN&@l|J3^&x_|J0>O&hI5$6A?k8XZk@PF!KTQ&^-ui&&dg8#$w;s3Oq^_%g3YJ4C5 zPv_72#S3lzpY9j)_3(e{g6rN{!iyWte_zHKlKn>KNkO|&M(Lf{!iU4w{w{Pr{?+af9mocdBOjwJM}CK{!iW2 zycGUVjhDjzsaYQu|EKOzm>2w?x_ghz`oC(fAOEMWDCi#ipPKo8_&;@V*PJl_PhD>F z3h{qx)~m(;sY}vD!T+h5NB7ya=lJ$M=Hc*v+Rpqy{GYm)`CaD!#m)Rbbzwoz)R#x@ z?V`fs)bgA&6Wi|?c1EI^|EI^}>F|GQ<^eMQPtA7xpSov$kKq5*ygsb|tL|d22kZZ; zxgPwVx+1?I%>PsKdNcn|&Fg{xQ?vdt{!gv>e`5W%g)NqG4>&+hAc)K@`AK!FaqVa!veTv592LBf~{!gv>e{tjg z;>Q1}@r3xlxbc5+GyhLL#LkcTf9j#O{x1GcE&mrc{!cCc7dQS-&ExTZYVH^QPmQl* z{$JeqKQ(?2{}(s@Pc8o!H~vp8{}(s@Pu=hI!r=en#{a1YjV%oRPtAJA_&;^}jKbjm z)Lak#PhB*wF!(<;^Zc0qrygwE@qcmS|J2O)!~exS_~#jQYnxseydUey;{VimG5ntz z--rKGSDs}a&itPmUx)vT8~>+fULO80Zv3B`d4J6RiyQwJH~vpObV6B}|EKHeXY0Q* z|1WO*U)+n^JmHUL|84Cb_a15f>+?>Jd5p^~QfS$a};aFV?Zg!-*dI$`pS- z_FwwyL*9jF7o`rJ^I)PU%zMC_{qcYLzDS?dGtB=})I2})|I}UW{MKG@t9Pz>zV|P_ z#hdkc|M1yOiN^ow{J5X^zqs*#aeuz_nndIOv>gwK|BD;{r)GX1{!h*8kN;Eic>Cu> zc~lV7?y_`h{Erv?AF;-%@Sv40;{H|e0$(k&KT zUiQ(JjQ>;D?eTwV<|hr9Fwpm3Z1a)+c3=NQKf0)|H|v4o|MYko|EFGQJ_-M)#`EF- z{QS%V;{W2t|EXDjl=**g^&HB0cKQ$f@{}(s@PmKrM zeMo0-)_=XRTSsqv8U9cEg|mGQ`f!oY4CqK-b&k!|5I1ncKn}utz94fPtEz@|Ki5~sX0IVpPKuR z|5Gos*B}3<#-ri?)Yax4@qcRO_c8xZjkm-9scX&G;s4^s|HX~}Q!`%@|EK2l!2hXv zz4AK$)qB0|kN?y5b@qP5|EX)uE8+j*#{a1|?D2nUj)(u#>#@eJAO9CO{!fjE#s8`C zviLvs+&4b3-v@8-p112m`~C46Z}~qxzxfmR5`x5iQKR)_oqRT&g)O(?M!~0rJ@m^~8`<)B! z_h$ZD^F{Y0`r?1w;m!KLE6OK%v;HssPv^6A&-_3261yJe|EZV1@pkZkapV8g%qPVE zshLlR|5LM`to=UT8$V*d-}hc;eggm3^oi4h-=xhScr(8c|958palr$!el7k_z1hwe z|EGTKy^n+cQ_p()-7x=8{fzy-m-&C{#Wr6M|EI38`D6G$HNFi0r{4blr@{aASUoP` z|J3q->P_bN@PF4`en#+rH2zP$$~>R>wp#69XWQ|AYPRG5)NIH9squmMKb_wi^M~s% z`df|e=UVf2k4#ydX#Ah{-)!%H{GWQ0y}$XNnx9AbKRqAb+s?08jW5LishM|(|5Ml6 z`^!8{iMrbM$N%a2Y5bqIvp@b%&HO_1WFzIob2`WuG#zs=kL#7YwQ2w|8zc!_V_CjTO{GYB*{!iVn!*9yhk0r*`1RxC@PE2K=E>pz z)U0od|5GnAzk&Z#FEqb_|I_`&N8$g}%zwlGspbFT#{a1~-(^EK`SI!Vj@agnpE~}n zo!kB0wKGf(k= zOMmd^r&r|s?2Q*={a@|R`QZQ5`0ZY;_VLEAH9T-XZ{{<8_tpN1w)M5WnGg5k{DZvt zJpbl51c|U#nW>;@KG$pPKhC{!gv>e`Oik>bZOTpPKgz{!i!6 z{6PGln)!kD=Vx!c9{x{{=ktUAQ*W{Ri~mz^vd829)XYyD`ux3qJo<(Q?(<${>lNew zv_EZszW41bHf#$1Pv^II_1fV7)bf9Ny)^$XZv3DAeu4FZ@qg<2RT=-MUS(bo|2O;L zF~R@g`|y8p>x2JO&$oHo_&+s1kokY=`Fs4IdhxQ% z{6F=gr7KgdM?I51&;I+(E6%&DY`)F^d$iXy@41VYhWUTme~zvH%lyB%@qga--~ZtM z)U)T#OVxbvf*Ul3^*8f${eD?X^|J2Vv`e5qE)eF;QHRlJv zH)>#?)Y#fZ-ov^cW`AF}*n3RRhN&)#mw5NDXc7FM9^bFre*bR%Pc8qamj6?iryHg4 ze{tjg;>Q1}d)fTKD<7!!=J@!(TQ0sJ_{EAoErb74VEw)^Z(S$OJn_CHC_t;r}LHni~IT9*L{0|`7r#S9$#p_4F9Lbx8eWd#{b2Q z|5Gz>5C5m;{PBP4{{78AnEzAv9@sMYKXsqM8ULroQ{w;PX8xZVZ;1a>Grtl4r{?+b ze{tjg)U1Dt|BIXXe`>CW`G0Ee2mVi;Z}af*f9e98KZyTR;}7wFapV8g_&NMv-1tBB z$o}oa`oHQC{n`cpr^ff;|Ki5~>GdAczg_Tu>OpU)=aVwftY)_&;?o zJ0Ir%smrQbhxvbM*7tqz=Kt~Yp?|*qC+|UhS_J>6^BY*zJorB~9uWWM$Fs)&sVk~l zrSO01^4=|j|5I01wn)9!=s&)l#{X%1QB{lJ|I~%On}_*-YPJ`*`c;|Er-yyt{OyIk z-8J1hbx!TC%JlheU)VHNQ?!qFkF0rrc^z9Met-Vo=KJCC;@`J3FE4KV9rOP_`eIw~ ze>DCtZv3B``G5F7H9ighSN{F>;Q#P>%>Pptwr&^Z|EY`Gv=8(D)C1bt`jh7W)O}iI z{GYsz{9oM6|5M}TnE$74*RpZ&f9ftR8Yiwdd)`{NhDp!X_4uSWYji*s*bP{$I8)%=UrV^8wp7N`BtjH))kP zzij`P?fJ6%zj;9XAnX60`N!9T-z#j}A*}zaF0juJ^Z)kw{*B=Onzic?{GYmAH(L+U z{GawO%;h5wt{wrPpl=~ou~U)=aV^|-2v)cPaN@%wp7x@T%v&IE7P6UP5(e|#JMPmMps z|Ebft-NXDpH9iyn7dQSdZv3Abzlr}-b3ORKxbc5#t^cboFD?oGPtE$d_`kUEe`@C8 z;s4ZlLe~FP<1_JpYP=}^Pt82P_Z}YM_Y3d$#iEnEncs*1)Bbo%{GXcjgYkcQ|5n)j zXa1kMvb-etzqs*#dOX|X@9Tc{dd6MVw^yRG=Lhz#C{10E|A)GVkH0v0AdWYw@N@4$ z<@v$?nVAS4a9Ho6)YV^oR;Ml-V&7M`{;#d67(8I_lQRBKjgP?pshRhO|MNEAhyPQj zM|BDQPu=O1&cXkwyN>A={GXcjc=3O6-sPv{rCx3Dx;H)#|EI^(_&+tr$N#B0U;LlC;8gqmGykW~x8vjg)U0RB z{6BTM&8NcuspbFFY{&npnJ9K5GZjrTid@nmm2CjL+R<2CVrYUc6b|I`)c zGx2|FUO)Vw&X>mjsR!8m3I7*2{!h*M;Q!*r|EUY@`Cj_zJRts0&3vx0msHgqaN*eS_vy8^{a24ydgB4{f7&0< z*Jg0JH+~HN_w3`RXS||$4E&#(?fAdA@qgatt?+;973Mv5Zp!z@cYOa%o_C$iyF2d4 zTyNI%EiLGl=(A4i;=R(2kN@L$R-=oqETi#%YStgd|Ebs6^Wp#0t9E@9{9oMoKehay z8eez%0nL2-M)N59b!g(ffq9368+qgZhF;dtyMDK=FKqMwbi5Vj2l0P#rR{!h((J^Y`V^>^`q zapV8I?eX}(xbc79_Wr~Fsqu&SKQ;5n@PBdR|J2Lv^~V3HS??GBr{?j@|BD;{$BdIO zFVe0T{}=cD=f3Xy*3)hIKb!Zqoj?9hkLUA*|5M{@ng6Hf=l#z5zv?>k zM)*H9>ydu(!Xob#Ht#Oyt9jllZC>7u-DZ0;4-fyR$1k#ZclbZ`5}QAE`T@^-FEg)) z|I_xRww@~fPmK@7|EZVmdO!F-HR}!I|J3*>{GS@1jQ>;1|HX~})BRz6U*`X*nGcBn zQ{%Ik|EFesMEhs&YHR$Tw$u1OHR~tZ@8iAkGx$H>Zr%d__w!X}1pkNk!~dzniJgL>xci-{%5uQhyT<5tmljWi~GAa z!~OYLAK2z2dNW_}m+43Q`L8qIiT~5}thM(m{x9zJ7hUSjjTg1;J(E4L z*xNj-c{}fV`+Va6bpCii{GXcZHNWVMr?BfQ(eYT%+I*rn^ZW3B+P=n)kN@+w_dotm zjn~BgsrmWM{J*&Ie`@AG;s4akce3mCUbT8VKGb`8^+xVX*p{P{1v`AP1l_lvjP8vLKm=aDNf=e70ibFVuq_&;6G%qz!o|9$)HD@OPjjr(U^vYpU;`ruhD=%-{Yp z{V{Jm8valF)A&Diz4e!4U-0wAKiT`iJ2NkBrgvtZ=p1jn9R5%D2hV1o-@R=f@$Z!@ z68+)4oDzrUZqu8lYM1OKP(_&EHZn$HLRPmLeM|Ebs7=L7$z#((1f;>Q1}xjy`#n)`wO zQ?s4T66cr^Y`jTglK#f|?{FSO^!|Ecky_&+t?82_iPvp-+_ z^zJC{d8;?2SesSbnPQ1}SJ?XN_`kUEfBN^uwd=PB|EFGUzK{8T+JAoiwp6dRS0sAcvsZbqGT-;p_1AdU zn(sSt)OFr9^_znK)BB^&j&FZH_4fno4R^ch=0xNFv_D=B|EI3q8Hct@$=f|_g z|EW3OS8te{=zsk@+3)`{^M4oq>3;7;Yu2USd-DNr{9o6>52p3^2l&5_iXQS_TE9Nk z`rU`p`uhj^r1ew0t8400w=Q@%(fB{@FaH-e{!fkXD?0OWZ+su~|FoTXfXx3>ZQx;QXf3}RJv;UX~FX?URs;#f6LR}c)t}FPE9oaPy5fa^?vbxaqrXRS#Re5U3UC) ziT-%M=e_66o0l5=?cSa{cW&^1I^N8=bAtaf-Xo zVg8@GXIaMosqumMzqs*#YL18hQy2Dbmiq9XRo=z6{%F-5b>6IRi~rO9tZ#da`9C%5 z%`*Q_&HA;>|5KOR`m?>?TbmyG?+b$WD?hPQ@PF#wgERh5T{$S@|J3+D*8kP<2AC(r z|LO0?Szj3cr)GU&{GXb~RqeuhG8hhPxBP(|7v@l?a%tZabGmJe*v$uP6OM0lBj>&m*+4JJEJKOtZH|zW2|89SFNAQ0%{x5F)U)-$!+h)$r z;Qg3qhyPRK4ZrVniSLj9>-+0Vy^Gs*Og;Vi-e%t5U+X6N_9|PSm-&D4I`~57|Hb{w zgID_VvHjwUuJZ0=-jDfz+CO{VUA8~V_F&ob=(2rSo2Jd|Z;$r+zwCK}*_}NvutTHd z{K0Im);`OtwQ8L7iLIL?JzKVK>)bTy1G9Z%_Wj5{zpl-bUNqbPWuI?$XPz~~nS|)v9Dv@3;yqb>AQme!#5s&{hjq{UJv}=7mMBu{;zrS=Bf15JA8Y)cI|@y z^Zjie9`pa=X8qr|ng6Hm*rsi&>m_@;L7SGr|LOVmJ*GkMf9jS;9v%Fjy7}P^g8x$= zee}`6|EU`_Y83pRx>eKTga1>vX?{ZRe`@A0;{SAhIj!3U|EJEk_0REttsZ$JGcU1Y z=ivX;-EF;J{GXb6h^+ss$9J*$YWP2Ow?gv@HvdmOG`}eI$gu1Dehrd-v|a|Eck9_&+ti4gaU^Z}a2ue`@CU9e&wmem;3U?f36f zCMFvHr~SK^6b1hmH}n6zOACVkQ|G4(ga1?G(eQt2?&l$^FZ9kymj(Z)?I({vJNQ5K zg_lkY{!e}JWtWHff9eUBToU}B?qAQ!%HaRhg+23w|I_~XHT<7CU0e|SpPKv0{696G z5C0c8{x5F)pSrNHF!(>U{9oMoKehayy3+2)Ymp4zqs*#>S9|Tm-TpC6rGQsXWEr~NhmPt80%{9oMoKehayn)AW`shP)!|5F#3x5EFa@rn4qxbc79 zcD$;07Wnz{d}H66?|rh(FTCo*d5OONleyk_y_bJK#~aUw|I_;e--Z8EvmPt{FK+x_ z-1xt^U$FIl_4(%U*Iqv((ZgvS1-~W7~@qgMM zpNIcbXEkoF8)uA2gLuWnGcBn)Ai8!KehZ{-1xt^@qcmS|J0lh^Z(Qw5C0c8 z^Z(*z{-2upf%rf5N#@(|e`@B>U0(K}H{R{OUJrQVC#P54pXi!?lf7Ag`OSg%c{A_v z&qMC@#$)a~{2uQ?XO^Z;7GM`}epy)mSDil3{GiSM zQ-JQ;nM1r+nm^e7+8}S{ zfld5rfH&)T;{OV3#|2-w$kt25|EXF35dWw1q49reJQMy;`!mlC|EFd>Q~cj`mz@#( z-vaYc_&@a$^JMtHxbc5#=AGgH;>Q1}*P4&Q|EbrQKf?d1Ywhv)zqs*#YW&+>w|4So zJ=ZxeckteBp6rcn?Yy_{@qheI3olr2^V*pIr(XT$N2!Y9mcBnd;f&_qYu@@e_&@E> zd_Mf28Xt)NQ`g%5_&+rs5dWvf*Wv%-#{a3AZ}{LnNBZ+K-*EA~!@cpB@4b1bH}@O= zr~5PCUcaq#5BArSzVxkMd$a$==N;(#Gq3L9`}g-=V4i6CqJ0yM|I_&~zY+fzH~vq} z`p)=2^#b#ppS}CTDxDwC-?8Q2y}2IzpY~sBJ`ew==KY5MQ!lXhEB-HT{GS@1i2qYB z-~EyOess4t>mOG%d&?U?ivQF8_4a1G1i`d4@#e z|BgI(e8vNsFTww*`TairPd(eb1pZGw!{*80|NQti9|r%YUTuEE{G2yl5&x&h;~UM7 zc{5+ne3|zK^RDL4yw~i`_`feFjSpUs#{a3;@9}?eo4@kMbA0@to*&iW z=fBa8hyPRae#ZaBjsH{gd9eMf)%EuCh5xDfeAxD$$-cB$y~*ZX;s10#o9*Wt{!iC~ zuf_kV_pD#+z0KaQ_&+_K#{a4DtoT1Q_XGc@X8tAqFK)Zu5}hBO#?}M(#us+H`3>*o zo5Sntk6*emn$5xgsi)ceKm4Ei)U)s5{pWpA`^mxo>H5!VIw|-+ zbw!Iim~ZL(_i1}Cudnx*{F{RR)Be|wm}c*{O5c9g9{;E3zjD%4?x$~m_KrJJC(j)1 zJ^6|&g8$S0^RLbLKlPle#s&YUo^j2X;Q!Q1@47JfKiyyXKlShH7Y6^QUcP7kpSphY z=HUO-t8M-t{!hK$ydC~ejo-un#f|?{Gf(ZPkDgC7{!i!2_JN?{qTQkd=>sr&H3T~ z)C=wV4*#cKYV+>w`^vA6^^Pz6`VZbK%)>UB{pH@a^MCEaZ@ih0X#Ulk@B8k5`QCf6 z`KCY4{mJ_koA-wQ)APS--|sdr(;F{^|LahAcJP2S{!cy6`iYzOPwVmX?fGndZEyTq zzg`D1JAA&(|LJ-;AO26x^Y}+i`y73qd4KSKYL18hQ*%E2U$plw z?3$xrPnlPK=3U*J+Kyi_y{9*y&%=hNdh_e$j1IkGjsMf}@p1S+HNXDh|I}PR{!h(3 zJ^S_Ck5_7*3je3;U#5n_&+s16aS~?^Mn6W z;~DXP(Z+_UHUCeI2gLuWxu4X|Q~mns1NT1PoAt3j-90VV4HeU4z3_nxy;s?KwD>3VAR%>PqYn(xE^MH~O8 zu3NJy_&+uGga1?4tbIB7zi8wC)D^bAFaA%>_2U2Zyo+o*{!d-7=B42O)ObJqpMG8- z|EFG6zb^Pc{k(z3|EVjgRtNtVZTz2_^@ExJ7j68Xx?qq0Q?K0P|I`JQb;19sS60*p z|EFHHswViqcK1vU{;#B@D)>Kjkv0BLU0hn7*uHaN&WF3s48CrKt^a$&+9$l1mzF2+ zf7-vGWL5Bg>J>#L3H+bBU}a(Of9e&>8~va9h2@R@PyNiI#lion3!Yn)`2Ofce*PC0 zJ{kOBYhSEhsN)iY+rH`DdvyE6vKDW}8vm!`vp(-Nhwt?51MU7kJ$RQl*E{C-Z^yc9 z-*>!Ew&#cc)AgS)vQzMXYUVk9{mijaS>d`Ct6~ACliDvAo%5-uO2B zpRNZV_sao)_3iZHeg5W+4;=SvQ{xNqe|kNQ|BE*3|Eh=B>r0>h%A5Be|EKK(&G+H| z)P0Ay3I0!w_r(9H@um2`XygCX%%{9>-4A~K`L=&%{Xf0=`un)@NAC$XKk&}dpS*d# zeG2~N&HBE(m;T$k%kZ{|o1g#LyX%N{iIk^)@y7G*c=SKsct8A~uCM!$R>A+Ndk$?A z{GS@%jQ`Wu?^yGG_&+t@AMt;ab1n-0FDK)u;Q!QFDfay^;?4SWj?Xu1+v3RB_I54f z^Xsx&#y!}e_VMH4_3(c^PTU&&-+-=->;I~U*nBVipBf*?{J&^FJ>g<+*6+ptX?sS8 z&cXkw`yJOQ_&@b<^Je%z^%Pd+>SNf-l57-C8=woB4J4KW&%)Q_KI!`y{W= z+q+%dqb2*c-gs* z+2#s8^~Xx$?Czb&)h3f}N{e>^Do zKlL#O9Fq91&5gc)r=waX?kKv!8{gP&P*dX@D__6fw=*Ae?3AWvJ?zb&Ugz7H|B3(8 z^)O$wqs{+QvpzEZ?~bu=1pk-SD<$|p^}yb#iGn+?_Wjw8|MS<|JUiC^)%|3q_eso8 zyUKfLpN!!Dw0($qzs_%5*)Zk#9l`hY>(x8)!#7vNx~}MQe?9(h%eJ}R@_%|gUhOZ3 zUgq1G-}Zgl9Pe@F*Y=(;+k1>15C5m@!MEZ6)Of7!#g}+9&#nLKGrgJjHsYI$z43j| zoIBI6pLu_m+<37!o(un{>m4&@Oz?l|QzwiI{!e|4{rhX?|EX`8dqwbn>iKgn5B^Vm z)2umR{a^LT`NPBdziRnEHS^=}f9grY@`L|V59^;1{GWPA|9*+1x1a6zJJ@_@$8XQ_ zW8UN7n)}87>3seB^o@Q0>SCXl==ZbEN!xk8(e3GJJ^rWhf3r`T z75pFbIq`q$^u8^E|1(n&{NJzEO z|5G!+5C5kgwP*cbb?%<^f7N;B>+pZ-5vQdG|EFfX-_H}f>UDk0&%^&k8~>-q%i;gj zcsl%_8lQ*%Q?niar^ff;|I`_0^bY<{-QVWt&Aalo`rZd$8oVEk|5I~3{GXcZ!T+i8 zllJFJe?R)!{o0>Dy@%QJ`{lchv3~Q%m%KUt@}D=vdfdYs{P;Y-X^*at^>qu^dE@^U zJhj%F=TZ3V8gK3g|EK%K*M0CpgKx*r{kW{&d*E4p5{DGjd5smGt$=>MXP|5J}PZ}{L@EByUoz1|DYUG9z78$4}UtdG6$ z#aMqcb7`zM&3?ffKZyU+*E93s@PBIj82(Q^a`J%S|I}kAXNCEHYCItRPtE$k_&;^N z&425C%+vLyPhZmb^C#;~EuZpc{ou3PJ?YK*!9R9=O?u&I|>%HDw|E}%#cys;uKY#!C_`hi5|J3q-YWY7ko)7;Q zZTz2__m}y9YWY7k$HV_c8~>;Gllg!6zi8wC)XXo$|Ebv@|EJD054oi6pS-hdz1@?# zT;t92+%N5_SmXb6Jvlb-@A-dU?mftce{4_8^~Uqz|MdL_?`Qw*&33bevHfipq4((N zc?ny~*n5l}AOENG%m1mfPv{=}Uww;ng8xgOoE`k1`j+DRg8x&mEH4lKPrYXI=HUO- zcme#M8gGFAQ;IlGW=imW ztapn4i#GmG%{)2$pPG4L_&+tC4F9Lbd*T1oHQU||{!d-|`tIQW)K%MdC%#&m>eoj< zw6&)<^9nQn**(_yKfQjfc`p2)dYyT%AHVM8U2i_H#Zet&jsMgBtWS&oQ!{^$`G5Q! zSnz|^_`hi5|J2O0!~aDa|EI?D;s4ZlKm4D!oge?F^E00h|EI1opNRj9HvUgtXYUXG zPwy{{|5G!M5&x(CS$`J)r!KU{|EWvt`R(4hmp49ipMU?iF1me8{x9Ck%>OO8=cicX z|Fl1z5C5me`^~-hAKrYv8Y=$k&FAaDz5n8kM?GQ8$FY9uk@vlM{pTOP3|(Z>HZb))}N z^Yw=RQ}cTKU$pUmYWcrth!~dy^%-iAr)OZd2 zpPKJ4_&;^2c@X@cn)M0yJM>y_d>{UgHRbStbb8O3zI~O=Q?q$8vBv*tf6j;hi#GHB z)OZH`U$mM3r)J(C{x912zvbyuga51A{95pTYW_YO|99cvrUw7_xOoBmpZX#D`%wI! z`YxM~g8x(Bz51o#|8%?;>(&SVr^d_R|GZz_miTGzhu+oO-U$9r$J_M!o5BC7U$ymy z@qg+KJ9gpIyw|@K*01$mXWr3#TdeVadcFK#wDEsx{2=~M*GuF7)U2nA|5Mk5?U#6$ zo7cntX*=^D`JZ}^4;&EhOS05>cKn~Nhk1(dIFMEHz>&=^Xzixsz zzrLDJ^yc_BPtKd;n-BA5`^Lu?d9xk=r}N=q@PE<9|Ea6Dyvh6PU1sY6+w<^lShJPS zhj&#?@T1v!{bNgCG0%30_etm7&i#5%?qQy?F1`Eq#Qpz1#rx6OGwpuQ_Aaz}f989$ z_4T)M_UZUv??qQk=KF(p;Z4(n|I_`K-g|SH|EK<_t~B^Rb>*5hVg8?*-(Ru*uUh_3 zz1HS0& zeSZ0VYM*CsykE1AD`LIjxf*ZgNIIo6o}ksqujLKXsjX zF#Mmo*48)0|Ecj^%>PsKJn?^O)*r_I>GNA)zaHZM)Ob()pPKg%|EFfXUHqTEe(TNK z2|)T?aXF8)uAZ^QqoS>G1_r{AxXnAhLDZg7r%f6BbSB~Rshv;Xy14)ew{o_@jz zZ@gH))KRg<|LJ(Fmy7?4_Dc=pym|kgdwha7^9Zk*JITAj=Et5g{zUKk^{?9RZ%_8- z_=oIwsy80+b6dMq=PR`PXRX#~Giy)H{b9Y-_&@&apg%v<+Wmb!^IUH{+i3eolG?t? z{MnLr)4a>=_e*>Ie1SLK^2|49#JXzbMc$S8%Ufr9B5|EI39`Hsy0Q&+EP^nXpg zG5Eh|-`Sv`Mme?XB+*WpZ}TXga1=M^WFRq9+{!iNn4QdnC|5fMN z`o8!-wfvtNAISVab?>2#^Z%la|5Gy`jQM}+{^re&viW~%JQ)5@jTd|T{WUq?em*mJ zKfD_LPn|Qa(f_IQ&6_>^+IrtU*yab~|Fj)Hi2qX$vGr+BKlx=pAHHwh#7(hg{-1vS zi66xO>H0?4`oj1>HS-7Yf7*YrT|fR$+wp7oKQ(@h`G0EGpT+;FhuJ(f{GS?sh5w88 zReyTJ?}zz-?XP^(yPtW$W=HSv{qbe^KfONB<{RSw)c8dFpBfK{|5G!M5&x%VejoGy z)Vv=5r)K?M{GXcV$NIl|J~aMM+sBzl!~dz7|A+rm%m1n6|I~Op{9m+BYyGJ|kHMo_ z2mhz{f6&NQ!T+g8jBK4a;gHXL|B<8G1pn8xy<_ly(Z>I&Gi*KOpMLtgcRyPn`kC*( z@Mb`X+X~N8b3>oBi>B+MnZn_VV|>9UqAQ z)Ah2R@>P5NGpBd&nZe7kzVNv}H}&zuJ0!;Z@S|_%_VZoB4n0;dyO>|I_Pf{GWQrz!t&(>3-z@)O~x!eNtMF z!(xAb-l{`GFVJ>J&W#Q#Mb|EIPOsRy=c6a3%zt+ogM$GkfHpSs_1ZG!((r*>=`=Krbj zfXx4s|LK$D{eElyT}s=y?@IQ2smI0rR*ubIi#|`TKibLb^)l})x;@$Bb#4)VKa+iD z`{a3mZR387`DxMPCwso%>SXVj{JfGsPs!Vp`?vQ0t?Nmi*O+{~fi2^nGkN}E^6`_s zWAb{x$=ts8Ta1k`ybJ|W$=G`{jnX|2mhyTZ|jBQ|I}^UwoT0LetpyZnCDHq@;dL{ zo!TX?UHB*O9(KQ*>#p@?z2c)kyvCdLXYqe}UUYGXtGx%>ddT=coj)tJasHpWZ|{`g z|8#%&BmAGY&AVg%U$j~OSDl(_zVN&v|RrKbk}r|ozt z{GWPcN=jmD^Gp5uhjs6s_+`K>Z?3o78JBpoelY$|ug~b;C-^^gpMJf9|5M{5@qZi6 z+Z8-xpKhIl|5Nv{^>p!n>Qg449sHmAifI=H|EHcmXI}7s>Z|6?3;s_%XXdQn|I|}w zUKISFI)Ch#;Q!P;v-^elf9lQ|X~F-gN89se{a-cDhxvc%;XQf;|EK#M+O1pge`=l| z{!h*G$N#Cb)6){;CZ6eyAI1Oa_;|?%^M7i*9P|Iw{WEPIldb=&W_@VZ|5dX;>;I~= z`eg+FryejcBltgE59|Np|J1A>jsMf@PDI6qy_({?l-Y<{okABT^9Ub<_T%R|EckQ%>Prf zJ}&eB)Z?x3f9i3zKlA_8_&VnQshLlQ|5G1-TA##yzwWBn^^88H(f_IOYWP1j9uEJf z#?RsZ)c8UCpIZJe+W5a{1U+#=R1GCw9S9_=J+-r-kaCkpC7%sfBc`` z5AGlTr{@0ge`@X@|EK2u@PBI7>%Hl}>%C7fpN9Y2d;dAXCr-5O_&+sX4*wTz{GS>> zw{g*G?}3y11^=h*18n_Y{GS>RnAf__&p&B$M&g+EwcZoX=o|c>_QwO_|J3q->M>_# z2LGpK9w7ctE&ms7{9m;3f6>POsqudJzi8wC)cwzC^ncMl=!8PQpFHz@pPXFaJ?Naw zM9t|dz43kcKfOPAJ^Y`V`GEMpXygB)jsJ@_{!h(3LHu8|@qgZSefYmu-AG z(%|=wxBI{Fz~^GU_aC42W_{wvn?2*5Wu6WHr`O}b@PBHa2mVjp%X}REPn~W)5C5mm zpOO>&pRSL_|3w@BryhE)c`);T>cQvb1^*Xq{GXb6fA~N3V7njupPKn~_&+uC>+pZ- z33mPXzi8wC)bf97{9ns#Ns%bR(8XT5)?H}e5AKE5N?fBehs-aOyW{(4)i z8~$;tH{S1&Z*K9%1J3;6W^Z0U>|gV}`F!I4biG+qGK2q9547ij|5MBVsd+vAPu*`y zM(}^?0q180|EFgCUi@FQ%QCL;W_{kNxtDtno!;pG^!0}Cv;X$5NBo~zJ@4T*-w*%i z`&--E34XkZ7Ys^VfAI|ONz(@>Qs-XaeX8yM{x#=&=TGXHxO@Io@6^+?!}`Dc9ZCD5 z*}3zJ9ti%g`S(+T4_sDJ8T_BRZu6Gl|J2OS!vCo?|4%Ldr)FMP)v)2Q{qcX=&g=1i zYUckft{dcCZ}Zuh|EKF^z0%Eda=cm3^peL1dgJ@>f6RcWyKGJ_jsH{QweWw@#{a1+ zx4n~Ca(cQSuj=)86QghJ*kimk|4*-{ zr%ye?xAXk*f4V*z{}*liU$pUm>X*&GvHq`mqrD%j|Et#gKegunsaM+jf&Wt%+x$ZO zpSsAd2mhxowD;qoD}Jui`?19O{S7~QFSY00soD45_`z9ce;w44jmO0Qsqu#RKQ$f`|EK2jh5u8tzAyeyU0`27_&+sX z^6Sr6dzaYt4M?x^F0%Pz^RKP)UTR;D%>UE-|Dt&${GYnQ8vmzeJ!1Ty8o$f@KQ*2T z{}*liU$o!ay3o&$?`w1Hqp_Yo^&#&fJAP@wecpw3e47vAU2XG6@qapgo!u|~PtEru z{9m;3e`>DR=Cyd^{qTR&d-TcGP4}Nf7!&-cn z_cgZO+N44I`TkYr3wAE}Pp!`Xiuv08R(|QtdcJ+ve&D@s*L%#5tJU$h?|c_u=Dp3< z_ced!&HA_Ik-Y28`ejR!o>DNcw_1EZr z@UiRnD)p|j^?l8Ed9Sk1AO27GgJ(P$qjqk(% zX@5LC{!d+G^DFUxYUbzK^$pbZnz+FoxS z7XPPSvE_~6|I{y-7sCIkOIN=Z{GWPxW$>ff>W7vv&+ZWK6VAVl`}LmP`>x>swEvv+ zyYW4~eMI`5!T)Ld$Ucq!PknOUO~L=EXPx>)@PF!QGj9w2PkqB}&+$C{_>1njJNQ3s zzh%}X%#=AIh-pSCZ*@qFep`Sy~#u4mqo_eV8_ykFkT z|2yE9+r8Ir*^;O&zuOz1H0#p)z3XiLa)%xdd)M2%H2j~=zs|m1@PBI7Q^o)3{%HF= zcyF@xVDW$2PWL=&g*WrmK76CloAq$PhN`kJ&QMcm)bnE-1A@a#{1#_bUfyz;{VjEY<+V4pL)%vSAzdj<0Py0VnY>^)W!CB z!T+i8g!n&wJ%oR6Wd2Xh`@i#`o;mvUo9^}36mR_AT^rK8@o1kt+uNIYb$Ng4$Ul7_&@#rj(LChKehay z8Xt%MQ}h1WeD)muewZG0-sq;b&)1Ti<72(|G2@!r{M(t|jE{BY=84{XKJkA#Uyc3x zf&Wui*!|)E)c8C6pZZ0cH;4aIvz|9=x$1hkKW4e9<^R+?5B^)tygK}!y4*Y({!d+D zzu&?CsqvKfKQ&(;_&+uN68{%%{GYCud4TvoHS_-Pe`@(ZwfvtNuZRDOHvUgtZvL%v zn?J>RpMPH$>r4K2eXQ|+`ur4`-y5~zM&HiotD@v4Z|3je|FnOZ&DX>KscY=@|GnxK z-@n%U-^CZ)>W%+<_r%-0YwUTA7;?LJnQbpiyTf}`!%Oz(!8>D(|I_`lz2mKSH9c>; z|2O8`?Okl%?}oGQi8b^8^!~8@$G_j3qn|Ix|EXEe7yqX&HQ&ejztP73sSC{eG5=4! zva%ugKXs9<-^=>H(Z>J1lQpH$|Jio@pL%6^U1H{ok9sfLK98Z z!~DO;Z#pOVzZXl(ga1>%P`oPmKXuWHqTv73h06;Q_&;@l`M#`+pYdL~Y(?;Y+P=gZ z|EGR#$~hce%uGq`1@y0seo-@AD|7kmo|BE*MFWUG&JwN%sX!jVq*|&%Jg699UoyPyE2aWC# z{GWdQnLDyu@PFE_`G3*g@!(d!9{l5vUvACWx6`cPu|}95`{46!-uSCcAHN>!;@#V0 zz0m&dQLktJ`P<&~W}e{1o8R)r1D?Eohj*^cGt8~u8SAcz|junlF)6YqSR zPl*51`;D(;{$I42|EE6Dd>;N!eS&#A=KraAp3MJ?HvUh|{7d|wx|hxO!~d!Adn3R6 zhd2K3+t0uB=KAn|xI&2Muo*{9m-&{PkbHJXj;Yqtk4 zIH*I1;Q!Rj3&j7a2X}6q|EC^g+wp&D{2=~M&3eMj|I_u*_&+u47c>7)&3ebI|EuoS zu}$Km5tn=OdOZvNe|r14=lUP-m*oGFy;pK4d%$Eb$h@=Y`P;US`@H1+lbiWy(bsc- z(N4aebF2>p4gFPfOaK(!N7%d-C-quSc9b zzcKm!8`e60{=vt_{bus-MUqR z^?%igmPZ8t=Y7;6Vg8@`kV6hhy!7jhzCX_k|EKNDFZ^}h4SxRi9a<$ijJv*J&Ao30 zPekunb6u?Qf4Uz&ulT=c3VZg zdxrUcYJ48+|Ekk^b`AdTp>KBu|JW(DYw&;3#{a2%q;w7bPo0w1J@`L$@6_(W|EW12 z{x90h|5M`wpZ)1lzn%eUJ%j(#^)c@d|EEst-RS?+cq{y$j)w}M*{);Z25!V0J^$Z^|G_3!t&d3{(_;A8h-ybjbk4w+>#&hETbo~B3QxgZ4oa5VR z=KuNe?AJ5q|EbecQiK0f^ZCL5safwB{}=5uW}o5Byh!|?&M*I`&dA6J{x912KQ(?3 z|EK2l8_qk$dq_tA#6$B>_Rj0mFZe%QPv5?Mga6a}&pb%{pSt;g?BM_O_0T47NbrAZ z<`v@q^!1vPIWYJ?@BRZ~-=DbN==ZCx8S#05-E4j8=yv>RwEJboePCMu^x*%R4Zke- zKbrY}>YPE{ga3P=dT#K4Bgga${!g7TDK+uh-#@HZ4>+lJ@P898yF7TnA=dc6XygCX z_%!@qwDEuH6!UEOKXsaUw~Sxj_VeNO@P9f#$7BAVTK+HE_&+tT$N#DEari$q^Y57d z7j68Xy8jtzVg8?bz?qHyPtA7xpPnb%@qg;!r=$(FRMTC?m59@ z(e~$0??I6%_B;s4YeAOEKwY3nWH|I`D`zv2JX+2-l+e`@9l zGXGEa!~8(}pPKFXzi8wC)bfAP#{a41|J0iQr`G(xXygCX_&)rf8sCTiQ#0R?`G0D> z9R5#@_rw218~>-4|5J~$^?>nzYJ4L8PtE$f_&+tz3;!2w{GXcVkN=A{{?FTv&-}k= zfA#DQ{{C=3w=B6n*4Zar=iT4#|Dv<5^&VjJ9Us5oYH$4C%a>m1jrYU<>3qYc4GR8G zjpwuf_U*L&?97|}?ca)ev)$IR@E$oMKlnc#@A&EY!T+hpTrec~KlO=rJ@`L0KOe;Z zsXLvPWxrld@xHF~q2T{6e`RW;|EsDA{!d+FfB!rsF}A+!@TuYF*UTfjrR$hjFPk{Z z8-Mfa)gxm4&7xu6y#9#S^1bm8nLiHpt}x$qM%zK&m9`%4bt7}V+5Y80IrX}}a`So* z^cm<~ylq$Fh&2Q1`8ywcBi^a%vrKQi)|rQ7#Cos3ePfOP)9cH&?h5`-&HBcF9F^+l z!)L6zw5K=wpYm9DZ_fA2>aN~+x*LXc@#Ew3I?d?hjR)LvUx!%Z|8)L3TR#^6r>?d6 zh`|mn$<|lSKesxpxydSUi=6b3=t8D7m zcG^75GCyCr^)ZK+c;o-3oKX;K{GZLl3;vX^fBc`i$~+VPPtE+XJ8yp4Uteb)3IC`2 zDK^i7|5KOR-~Z$PyltKj{!hJX+nd4vsqszr_l>?C-}J!UH+z?F-fmv>hFIhObba_f z{9m;3e`?lawEy-lviVr}KW#5FKZXBOSJ?gI|I~Ou{GYngj)(tKvmPS;&t{MX|HnKc z{GYn&Wt&f9{!d-;QltM<-(KGk{Ga-chShjD-~VZw|596iu=jKJ_v!dQ?O$f|-|&BG z);q`lsad}k|EHG!oBYkR;0w3x+->U_ukr0KoA)zs=goS^_&@DmYwxf5Cf{CV+s#XP zSKD^{pY~^-CH_y{==supfB8RMAM5qv|J3+H{GYmU`%G`J5ARpSsZtrVmutyz*AU=0y(F_0_(*1Aped(L5jiPun-x=gFR* zH~#O3qZWDN|LlIfU)tmUbiVcGyYPSNRW`qg`G3*I|Ea6%SPe!NxY|LpUVt?PMU z(Mx>3yzzhb`SYGUGK0dS2|Eb6JZ}flaaU*UH{!cya?8fN98E z#(Ygb-<5YQ;(2;kK5!57IlUj7)9C+n{Y7)m2>wsKeCEkKf8YO^S*Hd6r|pH;O%MK0 zU3~jB!T+g0u3pLe<*zTVZ}flKzQ(*C{!d-EadYs0>V{2?{!h*C$MApZx>w9Ang3Jc z{qoLuCf4?O@Mb;lrLVu>&HiWJwcNYR=6mA*^gL<%JbPEzyg>Y)wpZG`HT<7?)vK>2 zR&1`1wRuzTV%z`lVK2pc!#DDg#(UZ4)0^vgf8bl*t89H_{9o(k7X+VJ zwrO+lf9i7k_bd26HOI&QMH~O8W_}_5Pp$cXYQ8_u>-JsK`E5R2x6l9SjsL>`X@463 zr!Ka}|EV?qPmOQF|EZY=hyPRKo$!BZw&VZQ_@$bW2j%$tVQn7QoB3@s_dhh&!~b%a zH|x8$+t4i5=6Ah${hK!)?Tv3+c}{chD!aa0^ICZ01Mz>l9_|nSr{?Gk0Mw125J{x912KQ+$>|EI49n)!d;tfy-J&wstO#{a4DUid#X-Vgt$uHEDR z)T}SN@U(uu9q)<%)A@LR@qgOC!sh?s|J2Oy#s7KR^TGeA<^R;of5ZRj_d9qx{GXcV z$^5@)Sx)Xcxb|3w@Br>?T+dBma-pmU)SCaN`@_58|DuimQ?It|%>Pr@+x0O2PhDZ&4*#cS9v}Ws%{;uXCS2?1 z$LEdeew}x5?Yad1Py6HT?DxCgrRMeUf7;IbjsH_~zK+k#kG1{&*}HblhT#9SKaKxW z;{)-3>S~)ejsH_uTI2tsjsH^@+xEl9-I=35-_v z_&*)5tafc!|5q*lr!J{#2>wr9Tv?yM|21_(@PE-}{-3(2ydiPiXAkG-=Or}$PhD8n z=>OCOs~Y{EcUj~7zi8wC)GJn%2mhyDX6yMf|L@0B&TU-(x410$KlRFz^5Fl}MTL#? z|J1Dai~mzEU)JdV)GL-Z&i_-h{xAMd{p{k#`G4vc%>%OjuX?eq2aNwyFIo6_@PF#d zFPstl-y?6#4*u`FlP3iKr_SuwA~e-Z`_zyVu}WiPaa>diNRHHnD6Tll6 zzq>sD@3Eeo^MyD5Z$#!lyjlMm|EKc}8P(Q2*H_+yN45$6PuqF_zG(A}zn=GRNAqtZ z-68nDru`e||Ealt{GZ-08vo}#ta1KdwDEt@X8xag(9jME{GXcp!~dyS?;HQ8&b9S? z@qg-^{ML!<9{kns7ysAgp8v-Bk@f#=+JA7n;Q#dc+#$9evH3qW->+EzH`=XsH1&Y2 zxR**vje9cuT=ehPlbd;d(e24S!2A&YPk-M((0mR4Pd&P8w=n;Y8J*{R`eE*{4jqI4 zQ?ni?^Z(T8T{{H-rykL%(f_IQ+c(btQ_KIU@n!fwoj=t)8U9a=AH)B7+q^&gU$pUm z>SVu`y#8;pmrL$spVm9cv!&U*vgq?o?%(o(%q#r=dp*7}x;?pn%hx5}&;N9iFHH7- zX-Qr$y<_Lt_2jjUcTVfLZ|l=8{`u|II_Z8|w~ZaIM^g808Q-4XD*pQH7V#cd&~c6JH8bEr^c_I`{|!z{q+G&&Hng5-OpjRelqj_)W_KU zG5=59tyfy`f9lkJeS`l~Pqg)Yng6HjA7`G6^?%j9(o=%}Q};~m7X058CGQ0PcXY2V z!T+g`>D@Jf|5JBP>lXZHX|5J|{J2Ln`oj-5nkl_E+nS-)||5K;fygK}! zx}#k`{!h(%v_IcJ#T$=@|I>En)#3lty?gf#{!fj!Wd5I;=Z*jKw&UUd)I1OTpPKXI z|8#%yf9lN4%;5jj_&ofdTK-R+o!LM5KlKP(zZd_f&hKmMN!$ECouA_||4;8f=fnT0 zyW8=Y|EI49n)!d~-kFW-|Ehas^bhO*s(TN}h<$%fv*#cE^(fi%C3`ofnSPBDMR`oHZiy`s_o+4{Zs zKlR{~Q^Nc|HS62r|I~fV@8SQ{J#9VQ5C8R!A3xRR<>CKyKIY}&|DuimQ};i;asHor zfO$3ipBfK`|BE*MPp$cX(Z>I&d)x6x%-L3NYg7gg$9%uDF5l|S`SE{xo}3^5r=GB9 z{-1iB-7oY1)Xe|G|8<%_H~2pq|EKPCdRpS!(>KQY_OoB|=K9;6w;|T}KOH~+3_G6r zzi8wC)IDr{UHqTAr_CSy=#Vwuc)qH`SI7GPqZ(q3|I_R7fHwc%uZQFR;lUd3l*xU9 z|I_~Re`@(Z?>+ucJ<@z6{!iWK%sz>Z{mZ@knm_x`z%uV4r)4DG%3I}~e|lzOMSiI_ z-Vgt$I& z@oV@$HGT~Lr^d_S|GfA3KRsXhKQ-(7;{T$J|5M}3SpPTL_`hhEjC#n=$Nr1|S=$ZF;fJn(@hhvap|pRd(SUl5d7cvMdt_q_q@%Int%QHdUc7-o5KG+@YnN# z|6|?|{!h(3BK)5kzkvT!vz{RSPhD&N;nkk`^(Um97k*w%&pKtWcd7Y3{Gay6f8qbs zcq#m!t`EP2|5NjN{2zbEga708_&;^&8;$-?U2HxB|EDf7pLpf;-hRG9^A%4%kmg-# z_k;h_`S4NrKQ;54@PE<9|Ecj^_&=Qw4~YL$SJ^x|{9m;3f9hKEefYm<(Jzt*YQ zzV7RPd*clc%KOoK!;TLUlkWY_oB4xJy#JLq_w#AbFTC+~_&;551wPdLpPG4j_&@bB zJl@CedCULl{h{%HYJ4UBFWUG&wfvu2{!iy)ekT4;&HBCgKQ&(u_`hi5|J3Wvv+mWm z%zK@AKK!4~hwsDxMSI1PW!}u&`SI%|vBv*(c=Uqc12@=q{GVRG&c43ze`@CG;s4ak z6U6_i*^d8HGp~>Ne`-7w{!hKmd>#HzU2cv4Q4 ztnq)^USjk7@PF!3^NjdEb(#4Q{GXb6SNK0QKES+yH$DLW_tO#6g9pSH;Q!Qk66XJ@ zAGUcp%>PqAY1f1QQ`g)5;Q!P$cE9*P^@}gR9{ivB1zS%N|EFGLz7hYYe$l?)GXF1Q z+w|c7s_lO9f7(vt|J3+C^GM!x=JD`<+P?g)ckoi)E6o#{zw$1({mpZEufpT)mF|rP zWd5IyS8Lzz@qcR8561sR+m7$euSd3jwYJmzPxpsc$N#DMyyO4W{CbH0Q?KWI=Ks{M z*snLt|5Id`kWG z>~HUn_eS%I=kMI+UB2;k-rrc;^YE7c)AbaW+4_0r|I`mZ+vxw)Cr!CE_&@b2J@4T2 z>HD9Wa%b>=dLEPeHTpmG1$hrMA2C}!ZQ||0|EaG!uW|mL`o!6{2mhz@&3)j-;Q!Ps z9(g$UKlMFV%nS4X)J1bo4gOEP;?fiO{Q31Ropo~Xf7)Jo{j}i!)a7^H82q35ld7WN z|J0QY4PpMDdi|dHf9iUhSI7K6wfvu2{!d-I<<;Q-)T|GT|BE*MPhD;E?C^hT{5Aeh zU0^=&u;GQ?g*LC$zFxe`w!CKZ&dOumb6$0f34ie0p>K<`29XYy98kcg_g@kM&kr|5wd=!}vdSvGwxwPyBp%@5$eM=FR?x z75+We_Vw$H=feN__1gDe{GS?+^#0<1d*hXCy=-rM({qRJm81QcH+S_{dwb*0@PE2q zJYUMn{d_y$?+>`^0B?Rh!2d<}$N%a0ydM9j#`od>qK*Gkudw6e|DuimQy1;=e`>A= z|EI>=;s4Zp-td2F-XHv*n&*AQdu_e(?)X35PnrGt$oxO;&+GAj>N5NOh5u9Izb0jL z^TvPS|MdB;w8sDG`zMY6Q?J^vDfmA%zaHcN)T{USKXt<%|EFgD<3Ial`u_a>0{^G& zctQN1n)!72KQ&$y|EFf2BkTXFnOBGZ)9+t+J^oLP*Tes*%hqiQ^Z&f<^T_(YYThsA z|LOOC)f~_KpSs50Z~ULS+B_WoPtAI__&;^2y&nG;?OE5J^F6-T@O}FU0nZC@PF!6wjMA3PrZ6g+!E_% zKQ}erZ_Q`7`u1|0uXo9tw|Q6Atx2?6bGvtS!#ex(;2qw)KlnfW`K_p~(f_FnZN1)^ zo$vPT1?Ktif7-sn*6+ptMH~O8#{1nf<-Q#KJOK~*%klSn%5bL|5Nu*vGp}eSLNvE zZ9Ov&3;xfy=eG*}Pu#s}j6)cppx4*pL+ACv!!HvUh|{`fyN$HV`r z``A1){9m;3e`@>?{!cx~Jl@z*YrM0^bx!olU+c}k-^KrF|8Zlx2LGoXYwHDn+iQbw z$M@m?bboljd+RrPGtV!x>SgadTc7sh(oNoYKm4DbxBQ=4{!c%z%o)`wk+s*Wet!H} zho9qp@DH!~c03>cPuHJs>$T$l)c8F7pBkTs|5G1tUJd`J9%G&j|EFgCSNxxPpq&r@ zr)C~pf6>POMH~O8=J@zOHC_<^r^fHC+x8!C{NIYrzs4H>r~TQ^{6BSO ze!JlR)O>%!|EZZzTGM~;Ts^;@+3gd5tZ3?XN$Uak?-ut@$&Js8{{4HOZgHQ52i$hy zMY;O>ej5KLufzO4*8km{x+D0%99zG)U*3hee?RK2oO$&h^MATt8vmzG_HLcpw2eKFj;-TfD|vhJ{J3Nfm+bq}l00AX`oLMO*;5)(p@&4lf)cw13 z2>wsa{5j_TsXKOVAN*hL$?pdLcSMVWga1?i;qZME_&;^xklzLWr#|wyW5fJEHTS>$ zu^Srh-Rte({W^4N6a1gLW9PQP|3#bmf9m5pwhsPJ&Hng5HS7E0|I|IZbPfJb_j7c& z#`%BhmgXJtf9jrndk6ogPR;0(xPHbpet)^P9sj5MVZB@YpBkUX{697G`B?w=jM=+` z|LfALd+>j1ydVBgjrU{yUp4EO{(a6|KVDwH^hEQAFZ1SlhLz9p#;eWQIolgwhX2#` zu>LImPo2}JSD62&#$WaAJky^?|EzwAn?_#jJ#s*!|I_~Xv66<1{CIe`6A!!CuOE+v z|NDByd%*+pdih7IvKJNQ7ynA+OAN-%TvmW#1EvNf-n)!cvUIT2s*!71s zHRs>n>pb6%&%^&|f36q*rygSK+v5M!JYW2un&*rEQ{xwz|EEsv)gw{y-I@M8()*?* zJ~^VP@q_q3?T@#^|EckNGafkITmDb?PqY57n(M*;MVtA5YCIwH|I~bb@PBIFfBc`$ z&-1|l>HWo*;{Viqee_vB!MlgO{+v(8dv~|b*Fpat>z^04pW3pilh^M}Zr;D>_b>cj zwDXhvAn(^JJN{g6#v*t!);G5K*s;d{*$k%O0S6E7k$5cY2vJ8E<&w3y-;Yd#uxD zz3$!D=J(*R1v)YrXRN2Jho-|DiY6d*cIl z-(DAM{GYA|FNyzC_cIUo+=6QFv8VM*^nao%*3AFY^TXpY|4+?4Km4DX^W*>2_(S}k zn)#0SKlKpXer9cnpO54Hu(~+bcWo&0X1(DKn+v^Jj~M@_`(fT5{x8}`pRl4nv;Ok% z^BMf$C8sX;W}e?mlb3np|5{Cb(HsAF+4QB}tlzq2<_q3oWiOSYLPhbKdyCx9)k?oB4J;0%;p*Q!FvFh z|1aA3KQ;3c@qcPOApTE{r)2)08gFU;9c%nwbUXep+BWOoo8y%}eTg^6!~bdjVKW8? z|EC^v;n3j!)T7M<;{Vj+&dUw{Pu+i9*WmxI+UxS*{|28sDv{Oeg!-P>UJ$(Bg36~8 z#}-VepSgNk@O}8d+@0gR<^Qyuzc0?aX>@(@KGTBVW1iP1D@S@W@9UOb!(-ibpJ7dH zz6k%P*H>BN|J1BU+U%x0Z|1dCtjzJQv0gMg+pmw;Z(Nw=&HAAI&KThLhwpp$rc7^q z2=o8=J0E;trFjbcpBk@&|I_^z+TTy(|I~{&Z4drW&u`ft|EI37c}@5~b(Q%r{GYe^ zzGpx0?9KYGLl5obU19#~^NbF$zWc29vBv-Ddf6ZU*HAG%_&hhX0H9=o^c@@lFqIT^VcqpFV$8 zHh&EN7wth=&wH=7?+^GtZLc>^hW}F++SeEUPrb^%zVLr)ydVBgjR(a4sVn#RKQ-PD z|EFGM^PTX2(Z>H>ciD{K6It&N|EFGM_k;gaSD2^6|EbH&%i#aitVfCei#GmGz0&4) z;s4YH=6CRa>OxyD6aS}PZXUt>fp>xZ{r$CR-Mv@X-_JH{IL`aI`j>biw!Ra|EFGDvmOsutG=RPWAK0K>o*3UE3+)@qgN%#{a2n8$F_T z@vnMxG0)St*Dq}Jf7<@Um2-ms zQ?I=0?BM^@&(AuE=kKpyJaba;f7)Jg{dvLvsY~ygAN-&C!>Z!o|J3Ds{GVFu|ElqQ z_&+uC{p{<*yYiJ+!~8#Orye;s2tI|5KOS zygmG%8jpwnQ?ni`{!fkf!~dz77l{9h_J7XV82)eTg%|DdfMK4cZ)d$%{Gaxx@qcPOHvUh&iutSN|I}sX!SH|4#{a3y zH*N|3PmSNk|EZauhyPRKo$!BZ{1E<6*I#B{2>++;1?Io-e`-A5M>7ueE;R3i|I_xB zw%#fJPrb~%5&kdQ_&@cF_Wd3Ir)Gcq`pwbvW`5eAet)z#^V4?yox@c zr+#70`r!Z61?F+_f9hJhe%AkuHuL|~%nQW-MH~O;ZSN=kFWUG&HGU5Nr^d_S|Gdp- z;s5;iFV^@!b(zg?!~dx(Y&~7(|Ec*r;{VjVU-&=$evkQm_`hg(SvodHzyEEp&!_$S zFmKkg{os^|-i7rWga6a(OU(=7|Ge$~@PBIV5C5lTo+18EjbFt7sqt^j|5M`~@qcQ( zBK}WZWnVA&KlRGG^}+wCS;J0pe$4-iHvTW#v(BF7U2ebs!vAS|rTM{0 z_s;R>Q)kC7nl{(F+Md@zdGowW>o+8(9do5O9&p{)S9#<2+HAVUoArY6e>z|7`i+T6 zH(u{uy>>%luS;(5mjCnj-;Q_Yh?{&n^Cj_rIv&04?fHH_*3bQQ!_D5z^Xpl1i#ML{ z^rvq1#`_htxGhJ2eqLqs`daOOyLV~b+Qc2-Hub8SwZZ@C^Hyf_44MC@X8*TV-4%QN zkZ11pF0W}wl-zkwtlQ4J*SpkwApTF+L*xI{@_%aizi8wCqK*Gk7ufth=KrY+%WH%G zQ_KIUmz7qB^?%hXS5+t8edsZNJDpKmB}n&de#n|EYWRX!L*jc~+;)LxcbG?L%4w|EI>s;QylC z`__sa{rrpVEpModHS_+f{$H~`Z{*bE&kcT$`G46x-}ILM)BaiJv+irN!?)wt@PB$ejsJ`GAO7&R zH}6;9ec$nB{vG~L$L}|~eei#3=Ii1AqK*Gkj~v-H_&@b%dp-V7oj>}xF#k_IbWDdZ z|Igc=AO0`e_`hi5|DuimQ;#&SiT_jcJn?^Oo{GWRGh~vWizi8wC)I<09KXrcoal!wo<^Q6M|5NAe zng18Cn z3I0!=X~)O^UHX@u!5gxEFaA%>d_er4n)O_>dtBztygvM&t~c4|C9kiWJP$6plh>b3 zo+p@m{AB;vr(N8GC3o`qlDkX0_3zk8dwU+dWR|JKRAFTHKt5B6#u zKVDj^_~$jXWqf{R_haMt)1yV)NB&=5->rH4dfK%-D)zjR?>Bip;AD@O?EjLR`FGLx zqf58=*JE4zd`GvlUT?IM=l`)jF#hkhAKwlBkLQj5Qya_S(k}SFxz+Ck|3@?b zFWSuii#GmGjc;WBpPKcO@qg;BUAqSVr|!|i);qTOf4bkpZN44z|I|lh^$q?{-KAfj z;Q!Pe(|ZN~r~AX3;s4YrDJhBRUtisj*Zck8`&d7B-l0v62gCnqJN@AJD`SoS({_9n z{!iV@d=vgp=Nr|3VDNwHVSO`$|5M}1@PBH&8U9a==feM~@rs}Cdx<}fZaq2&|EK%! z+Pzcof9fITr_Fc!{<-#kw7Ta)Z@#~O@Zp7i{2{&55(n?y)VXOXiCGga^!wxc^>vrd z@aFjVze$&T5WHZXeSVkzXS#Q5^Xd3MZEw@Peei#JUisZS2LGqdvH6hrKQ&$y|EK2j zhyPP^J@`L0^K4V^JKOJv^`XxwKFb@Qj{npCd_Cg-^nAP6{p0`C%#+0bY5%m0M*pWy z@1GU?pSo{WcH*wTo$mL``;Y(A{qz3g|I}IiGQ#@5(Z>I&IUoK{&Gq2_bUyh%T`!*x z{GU24EiL%JXygCXU3;Yj|EJGOH}kRhKXsOEkAA8c zXXYaKzk#`Zga1=!=k-hc`-6|_)gy=X4E}G(msbV`n0E>@Q$Bv)XBXPvrc~7o7dlV+OAmR|8#w9$N#D2 z|I~On{9m;3e`@(Zb*|0loA&y)`u)z67@V~zjQ>p33&FWUG&wfvtN z|2KVPLH(VjR|MaO|64tFr8n#O;{UXLn9V1||EcBw)D!If@qg-x=I8K#YUb(T|J3*~ z{GWP~`9A!gdg3`*3H+a${qcWlJR1H_&362s8efP1Q=d3BH~2sGB=chUKQ+D%|EC^m z$H)JvIX?bR&H3?vYJ3^~PtTY6fcQVP{GWR4)a>B@)F+t-!~dx#*}OdbpPK7??Cl5r ze8cVa-@N}oQ=9)A@yY$(!_MoUc>1sRdE*6t{PNydkNy50Z=MhSPv<+~+??S5)Of&2 z``+dIkFob_+3)Z4*8D&1kJmi)h}(TT-m<9qZQjgx#Q$l3yx-&wxA=Cttn1C*_`icv z=g0coJ~w&yx9h|I>3H&G!!|T=u|EGTX z)z=bFo^pKs!Eav>ykE7=gTenr8~>-q|KR`B)#exQf9h4{8}NV8#{a38+IIY(nt5vY zKXs+eAH)CY`dDuh|EFHE`HjTi*Z22+!RGbh|8&31yTbqRcRct%{=N?X=WX+^SpQdD zzHwXP!uGxV^^46%F#k`-TlU(nF#k_oV~zh)uiyDm@PF#6w?7E}PtCkN{GS@HhyRN< z{!h*R_&>isYy98B2QCc$uh4uU{!jZC*gQM@pPKb~@qg+X+aLd@UT^;Fz_~|yuQPvE z@I*6j=HpFTf0#G(3V;0jAHA#1zv2IMJR1L}#;@W3)c7_0pL(fn$N#C9+41pz>UDPh zV;Ai0@9%2!dfBTJ-p`u1!~bdj7j}LS{GXcZ$N#DEclbXwJ`w*HZRY<)8~>-SwfThj zKQ-PF{}*lipWd(9tu~L({GS@Xi2qZU+j_?MKlLixj{j5F+VjN!MVs}1)eU>*|Ecjz z_&@b?*7!g5qCNgkUHfX|{6BS#`7!*Tw|#x%|DwISjYrSheMGIEM}v9M^qybVsO#+bc0D!PpY?#v zcQv*B`hx%S?biHH&HBBzeSmt8&&yKdEAfASyZhqc1?$ZR+y1_t`GEL8?Z3{R2ma67 zo)`X4&3eB0KlMx2_I$jx{;#&-;w@Z1jKXyi=~@etrAk9=C`2f7(8x_r1aYsVDWh zJ@`NM^ifaqeEjvNO};nyKRw^`XDkfWS6m+a zpL+Qo|EFF$?@XS*pMTlh#`S--ebseSga1<(+;M&If9m(D3VFZ$^{e*yKW$&VXa1kM z($)jU|EX*C_&+u4-Ln3#n)Pt;f9kdN{RaORZTmcA>;12>`DwO3d#v$)+8@u1|5M|g z@qcQz`F;35HS@;se`j{!cCcr^bWh|DtW)J4eq8&v)cQe~k64 zOAqs2ZoeLE9^1@&na$(E|LOGwbuR_~7j68X8XtuJQ&*WE!vE=dSicnir>?c?W-%ltoefz7MK|EUY@*JJ#jy55e*`oB6qUk~^{HQo*Xr>}?7^)Cnir+(7b zb7uWt^>g-m{GXb6Zr^>8o}=GC;5A>{*w-6B_TqCH-uSWk*Y@|WFke6Ulq~N`+m8R! z@$qQ*KXtMB&96Vt^ZjZ3pUzL?|J3+F{GXaX-{Ak$c)73c9GRovzv1ife`@CC;s4ak z)5HJi_p@v4e(m3f<>=2_%&)V5KjzImJ^S}%zCX`r!S7G<=Kj9>=wxsF-?-{iy*dB# z2Tu2{w)?~X>3S-y@qcQ*UhscvzP|8(>SFVP_&;?y&&y`RtC`1$byG9XkpEWm{^0+j zjsH{ge&YYsmFD^If6>PO>G_p6ycGPOy3D*E{!h(%xA;Fb-Vy(&uBcxh{9m;3e>xxY z_waw}O8a`m|Ec-2Z;p4_UN`yiIsbG2h&TSP>3ka!Q%}9w-|tGhpEvSviL}k@ zOS?7J_&?JBlfeI}SJ`|&{GYni=KJCQ)Xei^{$I42|EDgjs!!nm)CHA|^Z(QwsoSC&);|EFGFR37}FdPQMr@PGPw$nt`c;Q!Ri3W~z~KlSp$ z;xPYDy~MV^zu>8yXfNyjbWY}J7Xh5yyVL5FQ_&@EBm%;x<8~>;7 zlh-ow;ipwOhh)qPzKlNLgKF=LL9G(Kchz|JxA}jkzh2waHot5B=DJuHtgH9V9oi=N zKb;R>g#S|yw0VBa|5In%yuTBcuJzZCFfVxRv+KNvv%aeNKkYyG_)fw9shJ13zT-yU zj{hrY^Rjootq-!G`6h2X;PuTm$9np~TfFgn_&*&V@Au8QulV)kjP96daptSu%*Vt3 zX@7j#%yCOrr2GavA81Gam!9sj5I2d{vpL)>XR>A+Ndk<+H{GYn7 z`91ufny(-HpBg`i|5J|{*69D#qs`~mvlDIzpmz) z&Hs7t@qf|A|EV)Ob_xD3+RXn`=eBPj{GXb6dH6q_A76+6Q{(sWe`>rL{x911??2Z& z*}Emrzx%CD_J7I!TmCP3d$K=dz0;_lNcL$hTE+cZ>$Y)E_gmhsTkH7#om<3@mvYRJ zvGez85&wL3XceDt*U|i0^m_k@|vec&p+Q zbws!8|v&&3sDypPJ{%{6D=uJFQFbf9n1{It2fx?w8Ur_&;?< zYNz1;)V+H24E`_L_&;5LdP-{Wf6=~u`()pafBS!w-3OFa<=OxJ6O9^s$3pLY=rDcg z9RX1k#oi03paO~t*n2@~BGTKyFvBo?7@F8M_THn3NsKY3_)mTQ*Y`gBF7ADvcfEPv zto5wN@7nw9z0W>{G9RuR|EKL8x_1r!PmRYsw(n%$&g)xr*16u<{c?l<)AnE$8i&9&>t|EckStpBUmo7b21f7SR{=KsZw|5F$ANcz4aJAeHBmDxjc^Ap?0 z4JbG^--x(ENK9%A$VUK;R4 zgL=66zAp!V?u|$L`>@Zv@oLA8`qX=ntqj!V# z`hhpw=T*L+=t;HjCAvq$yNNz@_dDMBy)X8@o#^V9-txxlJ@(q0-tvFCzV7FAOZDsb z%Ld&q8vmzefBawE_&+uG1OFE{{!cw%V%OmR)I5LY|EYQY_&@dFNooJ5W_@7%pSq{5 z_ly5i;}4ntr^W-~|Ki5~squjLKQ%rR{}(s&|I|ZlfBc_%upJ-&r)K^h{x5F)pIY<( z;>Q1}@p<^axbc5#`M+hxvbMd>{TVZv3B`#~(L%OM{uF;Qe?! z{!cCc7dQS-J=Q!W{!cy5eB<;_HZ(NVM2oOw6=pPK#ge{tjg)Z^{`t@-=IiT>Ar9`a`WV*H=> zA7s~q|5M}jes=T&-pupE|7m+zAKLt1+y^(m*PHdBcWuAh@8@WH{0DpP^2U$;@ufQx zeefIeym^1s<;?Tr<=ge)|8%~5yB`alyTkXV_q=i2{xtG|5NAMyhZ$< zx~=_tPuBm{=X1hEqk{kYrt7uA|CQ9Q4gRnF)N6wOTfcX2@PF#E*VF#*>XNI|{?FFy z!vCq62Z;Yu%m2lV|5Gz>5C0c8{!hJi-~7M0@qg-Sn+Jyf)Ad!_dc*iX^_ExO4gOEf z{HvqB@8{cj{2j%88}$6k%>%W1ySI0l^$Y*#nP~i<_TTo}hr$2F&HBG;JRAN`z3aoT zg8x&$_(9tLsqq^4KlMtRABg``ud(Cd|I{46$Gt7Q@q6!d(K% z=I2e_aI$x;c{BW<_GkVa{!h*PIsBhGcscWbapV8g_&NNaTK-Qh|EHG!Q*ScwhX0HE zZ&QBm*V|xz4*#duce{B@{GWQ0-5>m)9$#wn6`B91uCe=t|5FFgX#P*ld_er4nt74< zKQ-&?;{Vi||EK2u;Q!QkK>Qy+L&Tfn{qTQk<{9Gu)Z8EZU)=aVHTUcKpI-Lk(=|h1 z@ZN6s|7Q#Kc-PtIX~Z`>yf>Sde4=-~cL|TT`F}cogKcO2pL)A}Uao0X=KI%~2ibPR z=0yK%=LT=qQyg-Pt^d34`-Oh^f|cHt*6)@qOEmsZ=VLqmFK+ywn)P`<&3Vk5`EqUV zeaO4q)&s=<-85xN@US%gPhD#M1^=gJJxKhYn)!cUesH7r7F+KT|7ZUfJYb3aJRSe1 zX1zrGpSsw7o{ayC8~>+XW&QyFr(S9Ec<_JfHTLsy{GWQY{k$6gr!KLdZ{q*dYqr(~ z|EFHItvI0Y}btfa!$L;iQYj`z^gRroLO zb62d!hk4)m(yPJ$>G60-{GXcj8u5Q>e71QcfBY)*Wj4RgdxPCSn{VgMddqe#-le~M z3s31?_Qu=XAMYA_f8zgi{WShhjW;z9=gqHIc5QXKzFOOk|5LNxFaJ~Tw)wL7KQ*4u z{yR_2yg+-t-aGgCKW*P>kH`PTjsH{Q74d&+JfmHEzOKK)-p|bcQ}3|P3-kZfczg4< z`FcOowtlyF{XYMv{p((QBW3H0`}WGczf3J#@R>LB|L}j>ziJ2TW&hiIeQDbN>3Z*3 zv@^{AQxBMMYw&;Go$n3)Pd%bn+W)C1^nM`tKlK&Emj(Z)zTl$AZQfjNf%=N8()0h+ z=gzu|&sTx2_m)Mgc)xg8E_f{XKkdJ0<}^OPzP+d zIqQdemp*t~s=EI?@6T&D@p^ez?AnoPx%GbUhL>No`}MFtpRLcokb1E7WyhA=ow5@0Djeq*x>|c4;*!3*y_Zx54(>?vi-+ANt@PD?(cksOUBK)7a z-24>&PtANj{GVF>PhDm6+3yNeL?lE;QzG!iEZ11|5GosX8xagZT;Rb|4+T8{<+}) z)Oavk@7wp^X!q;aw>R_NY`u8PzkkEmU7R|tP`|%!u;+*WiyQx^=JWB>T@w}w<&jd;}u{2 z?yf@pd3>9BzM1de?OktPxc%;XyzA`WtGv7EUhhi#zPM}QeTnWh?|$!U`~LXi+6TO= z?DxBmp7o%2dCl%r!N7+S{au%by{l`|{!j16%Br;gQ*X8Jx1YXy)b}r|+L>DO{$t+E z+r$59f9Cn&|GcZ~g8x%*si_a^|Ei0tYlHt&Z>p&a^Z(TNK>VM29fKA>3H|uJ~#M3^^~cXrPi$3TByITYS+G5>XB#5y*u_iCip*X@7KRs@PBH& z4E`@}{GU3nf79Uq;;#Izy6~cov)udP|I~fV`{Do8@_*`Vn-_@x^EMxZ|5LL*F#b=? ze6RQGcX$sP)-Lt4%AMZ$xlUVlc@G-bDfmA)t#+{GV^P>%sr2IUfE`&HA+X zKQ;5`@PBIN&*A^n@_%tN|4*&?f9isft%LvD-)(~biyQx^=J@!(xbOYj$KIO%r~5O; z{22aEjaOv--?;IA`@2K%e{r+^Z`>Q7|H{udaJYFX^MAS?d?5ZWZv3AbA9z~vuM>^` z)A3nfnfZU}QFi_KKehayTK-SXcIN-7@pFK+ywnt6ZB|5Fbh(jxdjJ%9PXxS9W_#{1#_)SMsxr{fJVzj%MEfB1HKTjPIv z53=XS`oG$Lpncx)e`@(Zb>SeJS7-iD&361>-1t8=-*5Q8xSPJWzwv*^PB_4~_svPp zgUjujTpzV}`=s|OYTm;BwqxfV`o94!lOCyiyX5-8^y?2^Rn(^UN5T8i_`kUEf8K4{ zh53JR((`pWCF%JxJzS>~j!nED zx}0)!qPsOYF3}w`ykKT`KQ(!My_zPyUgrJI^nIE4JF_$IU*_>LuP3uJ_s=|ki&K)< z+w#=p`=N2;WH)J&^tH{KCqI9geM;*ViTl~4UD5|0);{_9OEo?*_`frzejfZ^t0N8# z{!iWf(1XMJzv{+E{vxdZt8Q}Cp~3%kd+dwg0}nj%u;BmHN1xIth5u6@*{N;tf9hk+ zYvKQNJm#a}|J2Mg#Q&+8Ux@!x;~(*VgSvbc{NFM5{PBP4Mjg}sPp$QT)!jOE4*pNa z3+o%3|5JDE)+zWuHGb{V17`d7tj_I&|I_nnY+jD}f9htoelYX@4%_-=!vCpzn5V=4 zsqul#|5M|q@PFzon}61D`ptfP)*oj6pU%g8Ki2g|5Gy$4*#d_-=kabf9l~m{ZdtL zUFF+{W%o_xw!Yf0f1u4*#Q*8}vmWikk6)GOC1qE7;~Ce#d4)IEkN?x-2iUwl*8f#= zeCGeD$J+HX|4%)}ye0Gh)Op={1pgOzH}ikGzrA|(3jQx{{GXcjmhpdT)(2+(pPKc0 z-#z7AzaPx&Yn6XaqOUuDk~ixCFIhavA3vabui*c5eKh`0-KTqx)XL-bcUH$vsVzOv z^6gEtItTx!{af06z6Va5;OApL-}~2}p6E97$9uEhHU3YpFJ2J;r{?_lKXvbJ-NXDp zb&h>r^m_;XKfW;0S=|$z-#s}WFmqnu!0bN3|Jj<1!T$}($qN2YJ))pz@PF!IBfF$d zcf}x4c=O_7_=iCVF|#H@th=dbjvLT_5}7|J2Oi!~eyN|5M`&Z9aU1 z&BzLVjCp}JKi-?|%>Rq`$N#CBZ;1a>Ge3~|e`-7;{!cCcr^esm|J1C1i~m!z9sd_M z{x5F)U)=aVwfvu2{!cCcrygwc@$i3Yd|&ZVHGV%voYN)&PurRQhyRNk|EKO`z7PMW?rQ7Z;{VjlXT$%+ zjsH{Q%Z@)}l{dbu|8)PDUx@!xVM2jLnzC|EckRP2ZdAjsNTY$sF%Id;j78w14hJ{eu7Vw&UA>@8521f7bRc zFyD&*)BZI6PtEn>|Kfh{lxf~vAO27Glg9t4SuYv?rygbNDdYdtBhOF!KlSj*dBOjw z2b|p}_&;?w`}+(0pRVVOOUK&3H@(n%^Y-<@{~b7FN_zd@-Rb#%>asW93iJP7xbxcJ z|7vU=2L4aYdW!fz^){QY#QZ-s>*?bE)U4P0vdV@b}g9liv^UX8qNEr}p<| z{ZIVg{>OiiI_HCY?^^Rq|2iPgyUHHV{6AekjsH{QIeMPd*L#=wHvC`zgQo@$iC@G2 z#f|?{Gk=cxf9mJo{VdG?Q`f%#S@3`AhL6+!PyNci`G0CW2mVjJ(&icB|J3Vj-W&c; zz2n_aga1?SviWxSKQ(>~|EK2pJHb%#M%$)Acf65&x&IeeM0=|J1Cvy!)+x zZ&!0Y_&*&_^Z(R%K<58>+y3}JHO~+Kr!Lv&|J1BE%=|w!`{V!AJYW1DKQqMt?X<@K zsdw4?Y2l&o`Tktr=V!m=jUVi={&jDTkN?y08{Ydo_&+u0!~dzn>u>%~&F2gMr{?${ z-&yUw%bs7Wx3_sSKMen;{qa=zzqs*#YSxp*|HX~}Q*U|oo#6lCZuXxgzMb`YuNbq? zyTX3{Ub1w)ce!~H{GaY0UJ(DM#wT9)&VAl^mg<&wd$S&;{X8_$_`h+(uS?I*wDaTt z)FpO)`&qj8Mmzsu2VCyGcHjKJM-II{_`r?k7w~`TP38she`-7*{!hKqeqM|JQ?Idk zGWb9BDx0^2|5KOloByX?R$LzZpZc*?>x2J`8~>+XuxwrMf9fZetTLZ;kZ-^L>6O9% zY5Tp4m*cwr9X7g^C|99a7*9Ski=;ieKzv_iHFBSi%UT60g|EI^Vw)=zs zQ`hcI`#<$Ad%u{?@a>!J^?rWG*m}J_toLp{!<%1kuDbLDZ{|tfH02L<+8>W<9xl=L z`g-F5ZU0*Bzr(%{`Jb+b`F?gka@Fi_*O#YeyZJ)z?e=-H{r9(Rx7Q%sr&`sM%Bthf2Yw>y11jsMg3isxPr{!cCcr{h=b zu=Rk=|EX7P-og8)Kt1ot?ZN-)_0Ah}bMSxa{5JOl|EC_=^T{y(Pklk}2ZR4p-!Sx< z;Q!QDocCz(f9e~rUK-~AsV}&;Pc8qac@sE8wZC=?M-*@7Hzw&0j>q~XN_GZ4^9XI|i(dK>q_^jVs zcg2t1tbaST)!!10|9fWC4Z#btKlA_8_$U0Iy2LyU{!d+Qeg^*+H}n70eE;MB)Ob7m zpPKFXKQ&$)|EK%2&gN+`|4+SqTV3#f>if6W2LGqNudIget3uuX#anAqOR5`ruQvbl z*C$W*#w(7!;Z*NB^PJ|s$Y3d*9Ce#sBI0OU=ufm-pl2E%ASPJ{9JhE}ooKsLvPY!~dz7FNptBGtUnH z7q`t1FVycp*lzR1z43lEzsdIAV)Nuq*p=&DYV+o_4awk|HX~}Q!|eb z{}(s@Prc2KhyRNk|EKe@9sj3hJ>gS2&h_4GesI`{^Ae5!)A2Ui{`fz2u^q3;0eAW9 zTV~%k_&>e=H2zP`{674jn)!YBKlQfSJ;DE}tL*o;_&;@dUE2Stx7z;rKW{r8{!d+I z^Z)RF-sS_Bob-rysd>K<2RypJYjy_zr~S87?+E@+U1sa`p0WFJ-=98U^Aq082W0-A z?hk#zyeED8dYkWe)Rd>ZH<j7UqaG^Ke@RY8Lyvz6bKV1)v|5I<-S{eMG zdhwsK(&hoqZ&+2RerCn0)Sp_e_Q$VZwj%gH9dF*uTZ8{oUwP@|;Q#dZ zRjrye3jR;swcAmt-yF5Aa9iVBgV)P1Y??ae7Zu(;^P8q}e^%+;+vfjW@{g!(p5McN zuJY}@iW;XX&Hw3m_&)q!-1t8=^R}4(r^f5x|J2$0{9oMozqs*#>O5PI6#u8r8PzfP zzqpzIrKyZK_&;x(hsgXtb+-9F z{GS^C*K7KFg)`5&rEo&^?M2M{TYAm=-uStLFa5xq`Fqz-{?NN=6&bKqp!d958n7k{GZNG?=k{`J-uOM{|LK0w_&>G$U)=aVbzWhM;Q!*r|EaqTXc7FM zxPs4yYPSN|K`6kw`X?d{JqT1oUfPZ`7*s(W@mc8 z%*PirO|FNV-y}IN@W1)L>_$ls*zd&TJiJUFm^lwH)6;colJtJLCnr1q)TBSn^n97! zwRzINWp?KM`EQ*$UvZeN2OWErK~0nI_e}rS{N&{IpU^D%c{;Iq^8RPe3(RcR*NxAA zQtRaBkM(im?I)g?_J6eZ~qpga1=^ZkP6d>P~IjrP>@i z*Y|JTwps9h9l!ZJc)(8fc;^49yLCy=|BIXTe|0?O-7)_!Zsz}~<^SR?Yjdk_XP)4H zhTh`M`oAA-x@Cu+FTU^4*JpXl|NY^HUj-jXUvkV$-;V!#yvGc0=BMHRbUeHr{!fh` z!~dysdiM$Q|J40$z8n5e*FUgtcJP03xuC5dRnV&;NR*H-2yYN&B1iUl&|;J0zn3u%=shMAw_wHnWe!L#{{dBH3o)7=$_rn_hr)E80{GWPI&pyHb>G*iN7i-V< z^U?S}Js;M0#{a2#zm01)(f9Aw-PXe{I@6o|@qaoWuLu55&362s8h?lXQ_KH(+k8L# zpPKs@e;@r<|Ciwbd40}l_DzGW!5BOl?}xJ1UwaSE?HBxC!Nfa)|0^iy9{iuWu+aRS zt^cbYIJ#@_f3uI66a3$>@oE339(tzv(S@HksE1AL5&WMT4~YL$=i9tM{GYne_Q(Il zUGeje{QNu~|EKF=fBc`C?f5@6+wp&Dw&VZe#{a4N*!(;EpSrKjr^Ekwo8QC##f|@q z8~+zK{!fkH`()Lte*fuS8(v8?{?A`8+m8Q>JGI+v(M`l z=Krag--rKGkGA!D@qcRhKQ-sW|HX~}iyQx^W?mrk|Keu;pBf+duLJA+`3*HcH{sA) zZ}~sn4;ufc#^+5sr7F>-%__ZFe;EI#{h0@d|5G!6&;EU6gUu`p9&e1j{`JLW-dsQa zPy3Iu`F!|4HIK*t#f|?{bA9+fHR}W8|8zd){o()Act8A~dd&Gb!T+gwJpNCO&s#lp zZNni)-4_1-rmuOjTW(t8jn5iCdv&7Q-?_?rfcdKb*t|bIo_^=C72dh#wTc%m_h$au zyk*aNjlxP{*M!u*K~yg45JPshXSJ^sUdKi}BP3sP79^n~{qTVJ^FKaYD)Fn@>t)8lFU zpPK92bKIl8KfUCXN4)WShdunT@6SBMR`Vb79&ve5s%h4PzW*S*KY!`{fOo-#eNr#y z-JfXupU$6sVeb_FPu=f=UcvvVSzo)&S$F&6>3^Pgmp7lMw=ccZoA=j-Yvy^6G*38Z z+T27>oHfTAZ+A}WjzrsgX@A@K?9cLvwtow_zwPsZ|I_v6+xhW-YCb>sKQ-5f|5M|C zf8Or;MC1STdBX$a|J3Y{|5J}THz&;hQ;(R`FZJ!km;3R$+kDnW*Inw}VrcW=|8)L| zmrV%s|CWAsU3&iC_Tu3GzG!@1@PEZSc82+X>Z(^>4gRn7q^ZIG)!Dok{GXb6Mfg8; zr8WLfU1dJww1q<&#=So!c)x}>-wXav&3cUZKXs*fzkcTb)cB>3h7@|^yYPQHK8^oV zGY{|Ct~uVUcRT3pe%|;B{GXm5>!nWY-+O=CdXTfO>Y3*r|C7|$ zUw84|^}%PULyzk0z1zHBmwp|+Uo=m$;@kEOy8k=O!{Gna%kAgU_&;^A`7->Ude=Vx zr{4Kadj6jpzu5MyCVoB||EK5MVC&W5|J2Nj!~dz7XNUib8~^8Rz6}4T#-p{Eade^w zEk82RSG;t%cl|FvN z554R6`9I%(pZ`-)ujQ>;1|Hb{}%v+=F>G^-1Ti=kLA85V>{}(s@ zPrcE8-n?wV`QDpsJ-nWs&+=ydMDuFio9ySE_`lzLb3^cgH2zP`ye9mgdZYb375}H+ zZa>dt{-3&RQ$_H9>W5dX4E|63(DD`d4c~w1vNgf~Y5P+Pmj(Z)p8mk2!T+h}E_wzJ zSFh*$$g>;pVcu(PzKZ#rdhNf!e!gnn$9tuDNb_*sYxlko{Gaw;y=O1J$&bhSl{T-@ zyTm*O{!jZeZxR2e>tS9a{!hKdyeIxoU1skG{GVF>PhDa2_3(dc{3!k}Zup{!TZaLg;eCZ|UJrMk#`ljoa z^7--o&%5m**1Igw_0L{f%=^WA>*B@1|LOYX-*QXvf9kSXSBCk2>W$Mb3jR;M;pR(% z|5KOGnZo=~KYsZGbD1ydjsLUP%e%Z`2lGk28(w;u^~=5MZGM@pZ|=Rr*8j!->G@RH z{`fz2&1m%-ptd(|LOYhfcU?-@qcRezpZ<*H-3-#f4aZS2gLuWE6va0|I~H% z{Xg#b+Qj3T|EJ?uo1en}spbFT#{a2Ve;5B3H~vq}JUINHy25_H^wS6Ldzae!toT1| z-(nsM|EFfX+%rah<@byEe1{$IYwyiAzida(}D{)HUYK z@PBGNAO0`yCwk`>>i0MNe&G8f3cc}y_&@E>_2U2H#{a4DX!t)hJ{A9`t~7s%|BD;{ zr}J}v@PGRKGmZaK^Zv*G>Caotv&8?YdHwN!+P~C18~#td#kSkOSNF#IJ#^@#MC1Q- zJzMSh;{SBL%tyrk#f|?{SKIY5|1WO*pL(0kyTkvftL*cO|5KOS@89r$>fkrc|EamZ zSiiXWZ*_&ezW6^~Kl23fe|r9!{}(s@PmQ0&|EalN{GXcd1N@&F?~DJ_`S8T}KlNtw zx%fZzD*OE;{!fkH#sBGeoA&uXb+K*7|LOJJRMimtpSsjM9{x{VV~zh)vpz5WPrbQr zSMY!8lKS1j|EW11^Z(+;|Eagu?+X4eZv3COt?!HfiyQx^F0W1dKlN7IpZS04%Bs5H z|Ki5~#a*^=zIR1sZSa5Ej_TO$V!u&tA{GYm_tTMH0 z(UL;_{Yd$i^!z{drqZN|EI^VTe&LuKlL5Ar2U`z(hDX8|EIsN zYTqjD|Gc}W{h$8+w{KC}|EZaOh5w5i|EFd>U;LlCug&kn|HX~}iyQx^W_}?4Pc8qa z#``e;FK+yw8ZU(ZQ{##7e`@B-G5=4UXMPX=r^drE|1WOl|EckJ_&+uC{Fwiz`^R?t zU)=b=xNn;Il0P2Lw(N$Ny_xTa|I_ic{;ztJ`9Az#+_S4*D;zm$cJOwr&-LpquX_&~ z(J{>b)Bc=~`G0XU|4)sdWB#9-d4TvoHS4$H|Ki5~#f|^d^%U5=JN%z|#PE*6|EWig z=oI{)8t?bv86Wxn{YP~Q{!hmrYuoXEYCPRX-+t=N{rdS=pLrMB`Yc^P{@k1AbJjaw zcr)K{&TC&r-71Cu)A0++#Bh z-+FVrzdZW8L^r$t_ud>I|EJ@zJ~94J&GWfyuE{!cw}VC&%j)T~F2|5NjQ z)9sM|crzdLoYen#^L;Y!@5!DxD^;Y&_qTbc%>UEpb>P4jHt%46;{%!hr|oW*Z)=bZrLXIKXsp0ZG-<) zow@)2>L$t8uV-dw%s0$@{+ZtKf6YtG znD3W4?=N$G-rUAXKli_`H{*J`G)rE8X18tDJn{a_?9LgUuY0Scr^}pwndvE;Hch_Y zGw1hZuJ?Otn^uYI$y{F>&l-Q8j&76meg~d>RAPH;o6i^T&wRfRXWhNym}OrEFZZ(} z4^KUN`2IfR_+!KTzZTzo6@1{~%^HXKf9j)KH4pwzeO%jC!T-%X{OjQVPBibw{6BTO zcJ0FaKQ$f^|EI?@{}cbGW<7A`|EcBw)bfAoE;iqg`G0yoSshyk|EHG!iyQx^$M@^n zDfqv*@qcQ(6!ZV$#{a3ayJQ9b7x$>EX6@f@^VRTwdj8qgef~Jp8y|@O({|2>|5M}F z@PBH&8U9a=cfPp}9}fSgZf+h6|EK%O z{5$-g8lQ;&Q!}5h+4)y_P|hn zr&c_6zMsEa-#)4Dx1Q&nlamwtpPmnm|5F!a=LG+!F3d4MVg66edbapKHS-ed=bY`0 z55)iJdWQAQN&WTXv%Cl8m?!-AL~nfD4~L%Vk3VhbAoJ~KBpUyx^Yyazb@6}dto+>I z|I~$f{eu5fGjEdlf9k<~lI!~p>Ybe5$2`XP`-yptar1tSoA)#R@5;e*g8v)Xqj&Is z>XAA5!T;T}c24kr0|)dA{!cwcOXV3;u8QFXjgSH*{Q&F#k_Iz&s!RFK*`l zse9QxI{cryr+JEd|M_u)jz92Bd;h1BjsMej`9HP%pBlf1|5I~({GU4CJRtrrZv3B` z2K4|EK52{6YMm8n4Ivzqs*#YS!Du|EXDz z_rm!V4K|Z3cs?FKWAQd`JfN+A;LW^7{GaykbAF%T|J1=pm6iH-`nOeEyu-Y~hLS{| z^xWn|XT7{B(fB_dpZR9^zqs*#>Jc`-jro6ZzjnpC1~XT|`(>N=!~eyN|5M}7@PBdR z|J1D4ivNon|EI?D;s4^s|EXCo75^7E{!h*NyZApfJ`Vq<#^>Sx;(p+T#firM>G|Ua z@qcRhzqr5t>M4Ib-mdPqPbM1w7oQLR7dQS-&Gj}qXn!*=@4Lev^X*(e{!jbU_&+uG z|N0gWdoyowSo?>(nU{zE)BgR=?;ZS~I^X6+;{Vk6y%huR^XC0JW5m7Qyq`}ScaJw- z7yqZn)A&DiZ~J`U|Ki5~srh{3|J2M|#s8^u?el8??alSspRK()KK@Vp)A&DiKbz-y zRKFSCIp+Q92H)g8&bH(K^!kpq?_>O*8n1`{i@Rsfsotz-etzM#-h4kkH1cY19$!20 zO7CH3^$Gq@$Ln@xR`7r7R`%~*ng6Fg@5+h%e5RrP$LoXl+q%#Hsrh+>t?%U9x7&P; zXU-neFgNS^ee3_G{hxY=c{==`TK+F?{9j4&b;19!{vq@K)U0oa|5LL*FaA%B@5BGa zjsMf}*&qL>E;ql0|5I;!JMI6}tmpdcd3}6)?VIlh|EK4_^X(6U|5NXI@8cByPu=kD z$HD)px4-jIs?ph9{CLc3s+rfx8*hmJ)BfDAaTm7tX8qsk_qX-NuPxl#+M9WBbsx9% zuC(XF`oH{)>FBQ0ituR6|5Ml7yg>Y)&WB&a|Eckg_`kUEe`@)^xbc7LFmKWPU)=aV zHS^@~e{tjg)U4l&|BD;{r^d74|J1ebd=~tly4uz&X8vE?_&+u0$N$BR|5M`u@qcmS z|J1w9KjQz?%)@Ix_4nR9fBc{BH;w;`8~+zK{!hKx-XHisHS+_R|EK2qng6He{eb_A z8~>+fo*({C&GGSnx_%n}r>=fI?fb;b4_&@c$=`(`=Q_r1tbMSxan`Ye_{Ga;fTV@CUr#^kg%;5jj!>3Hef7R>y&%5!K z;Q!PY+&nw@Kka|+?GFY2r@nddy5RrR_pjTEPxIp~uG$^^pN_Y@F75x+8~5VzruhCf z=F{+h+P>X<8vaks`(yrh$JguiEV0+WX7hJ-YCNEMxH|36d_a4BeLFtT_OI3ctRKz) zv_J1(+n%fK_&j@jp0{luHLuLO+TM@0zc=$@tNmm&(FKYj%Ux`8&8Y> z)BZK~>nZ+Ejo-!p#f|?{<7?ZE+3Dw}ZGCa?isxQqUa5E0^S=!KPmizO&U)GZ^5d;q zUl;tJUf)L^t_l86J)r-!!T+fTpD;K0KlPby)BaCAqWitU|EbR#{50?X0`;ZmKgj39 zd)D;j!T)LdS#ur@{!iCC?dgrd|EX6jO3(k({`cH=TkwDCs@azZ|EJz^SpL)j&F9-jp-edFr@PBH2ApTE{ z55)hex7&Ko_&;4QjsH{EnxDr1scW8pJ@`L0^H%YHCl0wWcuN}pr^esm|J1xc@qcd%k$VQ1g;wl~*<|I_}=8~gT) zk9<3Ap4EGktzU}&)BP&8`Dyq+^*ZxK_&@bp^E>wa=Z(+%%{PDY^D$o!|EK%0)%;4U zPyg7K2~1C=c`c9Z{_BS)C=z(;=SDF zzvBP2eaVKc!T+fjuP+P!Pd$J2=HUO-58FK02U{QOkAHS~aqxfIUQ@d__&+u4cQXG^ zUB8?4s89A@XTA^rr|oOZf8qbstWR9Jv1y_1FY^%}yt}zK_aFbK{WsWl^TFQuzo}2R z_1?XWw10zr9`Jwa`sZH>^Z(SW zzl;A<;}!9LYP=o(PmQl*{a-cSjrD(ZemorhPru(|JN{39o}%%8YUbUQe{i}t>)#$z za)vkl4gaU(v0g9!Prb$b9{x|~r}2NfzGAyx{GS>>ivLsd`r`l8%ooJ}squCAzqs*# zYJ4C5FK*`l#f|@q8~YbG*RJblULgKY&yVj9=KsZw|MND_hyPPEUl0GM=KYHQiyQx^ z^WpXIe`@~y2>wsK!n(M4u0Ni}|LJ&}tf!uIr@vnKLHwUyU%tF#&mp-@1o8vuEve>(JTXiby)Fp+}els=ryoxR5sig-#?OkGh z_#gK7hK(h*9>7xHzRCVP!TP^C-?NLBrOw{4%(pLoYDw^aI{uOcPY3^}UbbXeYV~C+ zeE$t=Hl&UpyVASDjz2GZm3R574Z;8E@heuQ*Z)=Dc6-|YsqeVxj8wsAYyI&9+nkhY zII+A?fB)9C$KhfApSoZ`<1qhE-M_F&@PF!}g2rL~pBfMIpUbKWo95phJQ`l+%JZxD zxB0%eCe|c6Z)|O%@qap={GS^CH#2*??@xc#y}?`lPy6GG@PFzo^G^6bbx-qD_&@d8 z!_xjwJ#k38u>P-_d1?4R^$_z__&@#qAN~ygr|v(xLkj;FH~vqLXFL8+jUUAS#m)M^ z>T#pe{!cyDydVBg_ZuIE|BHL<`d@nE!)lhl;f)W&|LJ(lyTkvf^KJcP{Gaze{}(s@ zPd#vG+f?<*?|Toj$A5L~2i~lI%ltoG-)K7?^Z(R?hP4m=Pd(Vy-(~)vjxYbG9&N|R z|EYO>@PBdR|J1Bci~m#iHE)OiQ*(dte`@Xz{!fh$#s8^CjA$SHpIZJeZv3Ab--rKG z53_lA_`m(#I{3f1@qcQr5C5meFXI2yJRkgD-1t8={*d{9>e2T3!2hZ7efU51s39#= z_&@b{o4<$uQ;)OH-+%7?i@$z@2e(dLG3T#|#{X%5KF`emiyQx^9xx!i{;wK;$NWF_ z8HFu_|5Kly-#qv~HU1d?r)GU|{GVF>FK+yw8c&G-)8}=l%{RsWsSE9V_&;@iZqwlZ z)Oo$zr>e^iEYi;(yLD)sI-=Xpy)(UEX8$+;*P=y>;Q!7W|9S9#ZQHgD^Z(TSZM{$C z|EY^wwF>@EjUU4Q9oYG^wEwea{-0X@FK+ywKi>Qx{x5F)pSK+k{}(s@FYeeUWIo^j zr}>BR{ye|9^O_|+Wu~Xg^n?G+zh!REJl=ovg_-m6vdl-u*PFTCaOU|kJJSPZUQg!! zLo)o`;3og?_b2o5nSQTR#^akdKRNMyGCR`)X3pQsJYS}7%=CVl9Y1KZ_ zc-Z)UXP&=##=Om=k3B50|M5p0`M(HjPt1?!42tpVGET>ZD`u+Hv>tuY(tC(xG{(VC9|Oc)v?~B^&>z{kzya zKm4CMt9^R?Uv&qY56JqzaWnr<&HO<8pRS)~{-3&6`;Ms}ezCuMwzJ<4ng7${b31kk z{!g9VKE3|0x=WWX!T+hdb?cVG|Eck2%>RoU|EIe`@9p z;{Vj`x^)cxPu;$Ir{Mq8cr^TT!dHhxvc%!otGf|KdLKvT^?U4Jb4Za^KiQ`{Rna!T${!Q5gK6y8qC; z;Q!QvPB*Xm^%o6scl_<=-uS3H&gapV8g@_%ai zKku`$g8x$&Ozax`pPJ+2|Ki5~squmMKXrlmJp7-U^UrzY4ZnXh{!jN44}<@U8~^8R z`{V!ATtEI#-P_jh#s8`CjQBsb{9oMoKQ*4^H+!B>bm2>Tz41QyKkbj_!T+g8o|By# z{NZlz;b+_W*`Mw5#^?O$S347p|I_0KPU;){U)=aV^>CY?i2qX$ozyM(KXvxG-Gcv9 z=bqOi_&+s%r^(#v23vD9cs~4M&wH!(_vD_bkq=jTb3Xi^_8(#%%GNh%FtZfA+|cuS z^Y-1 z@r{}+_r|wvZvAYc2X|iP&3wI&dOnlr>vNZS^Y}vsKJATvduGIvME4rM*c%^t;p>b1 zdJAlxTfcV~diTGmZ|bN|7I+W1xL*qYr{~B0!vCpR-xmL;=JEJHHIK*tsfXMAJN%z| zgss1e|5I~({GXcR$b*_`kUEe`-FT_&+u4 zm*fAu?fU`$r{?-3FK+v9-yYV-HUFpWH2zPGpT_^Gxjy`# zI_vD7!T+hd+5A!bpL*0;z3uNKrhAW^*em!yeLe=C)hqbFxbc5#?hpPiZv3BmfL$N{ zPtAJv%>PqoPv{c-pE}Fdx4{3Y&%OHW;Q#oU#Plm~C@R}o66XJ@ZL(KXsXT zHvFF&4|UrO`H9B=>HMtEivLrW+PppH|EcTW{xJAIH6D=pe|o+&^Z(TBkN;EG+VPnG zr>?g1;s10z=B?rX)XZ<2yt#uno)Q12$Fn{y{!h((x}jZL`~J)?{PwJtiT>>8Eqs5D zkN=zS==9(LYhHaX_&*)5-nRoU|EFgE0`q_Ba(lnv|Ki5~squCAKQ$f@|EI1uFNgnA zvz{mZPtEIx|I_`J|5I;&8~#td-R6rv{?>v-f6!*WH|zi6|8%`u?fm`o z9`fG&!W*gk9=I>jZ+v){H|zP~|IGLWFUWe2_&+tr!~dyES-;Z!pL(VJyc_?gUS>b9 z#s8TJO3w@2o}T{~w|Oq#zSVwSiT~5~68m{0{!hJf{l?T?x8-;*S-vv(zh{=+6g=R= z58M;{pZcb0Q-l9g7hHNl@PF#@Gp7gtr@s28n}YvS-!MDv|I|0$dJDd*Ue|NQ)G7G2 zdOhD!mtBkx^By>P5MW|I_gYKejsfKOKMa`ugDi)OS}skC*bt zKe7{lHpRPi&+B+D@2z{&^Z)etO7oidKV2_v*I%dJY;8Wzn|XowKW#66EqJ}!xa|+D zyeGo@h4+UYFIUaHOZ=aj_cQ)a&HO*x-+Q0RpuA*e`@9z;{W2t|Ecj=_&=SW#{a41|J0RxUl0CIkFTzKE%-n6>UF^<73lSS z^#01=|I`EXuL}N8-S^nrga1>HX!AJlUw{12u6GCjr|stqSRDMH`rPv$2>wq!?WPsM z|EVv!^WotCbbYg)UK9MEx@5`xF#k{c&%a|PpWg!CKKFXo_x4^h^9tU7-s@&v7W|*~ zFP%3v_&>G$pBn#X{vUkJtFEYQ>d;8uOga6axcfR;a@PF#c7hVefPhD*u z5dWuU{cQZ7o?pFrKm4B>&x!w2SKId`^Z(Q}`~2V3RyPO#hv&xssquICKQ+D;|EI^- zzVce|e`>A||EK2p;Q!PO&%YG>pIY<(;>Q2!`7y5#{}(s@Py4eS|EKM&Uy1+oHlL0E zQ*W%>8~mTT*tX;U)SJw2pUXj& z_UkA9PtCmC%Pwr`&3d;3@>+W{Kd*74wu#37>G7;@ivLrW*}OaapSslM)#3lt%rC_M zd7EeYe6R^yeGq3*!IO_%{5X8b65tQ`gx2pK|9!Z_bbZ)A85THKeZm z;vDbdUC*TszUDl?zLnop&+n?ERN1_XM&hcJv*N^|xPVg8@`o_TY^`oHQ~*Pb8zpSo|y#=-yT@7LO8ACo%!uJS_t{co=! zO;fvOZ}ZN#^)#9Pr~T=trc@@jr|$A*ecJnu+wDDiXsgtZhwbqmV_xjs1E2FAWZnw@ zr{^#Kr@#MWz8?NhjprME$BVu{jsNq<@0Q1}nZJksQx7vQi~m#O1Mz=qd?5Z$uh$^^JmUZ2#{X%5*6+su#f|?{%m2lV|5M}h zSpQc&tf)ose`?MDQ)~X8TK+F?{GWPQ|K`E}>GMnD|J3+r{9oM6|5K0d+cK>Gs~*s~ zQR$Na*0 zduA6kO>Qq}oIGBerb+LX>CrOh2WEDD#(KVajg#xmX09)sIUg|72WB2WbKYHMXZpCz z&OCnR`7{0BpvK90dYQ+|?9A)UJbs(z$$5gA-L^$?zFuZ$UVn#-^@|%fZk%}iPdznx zyv*%Qnj~MJJu+ z5d5E-_ZR+8&AdPSpPG4p_&;^4Hcf;7`~A7U4*suQhnB(rshQ7*|BD;{r|#6YdGLSg zZk^hM`G0Es8~!hD{GS>xhyT;{1W#xFPd%hlr{Mq8gFAK%{!fq3>yn=Tr_SlrA;tVZ zb?45VQ!N+X;>TkiUrFsO?>^mo1plY~`}ORV!vCq6ABX?jbI)(m{?FDMX8vE?%>Ps4 z`S5>g=I=58Pu;R-x8VQOMcuQ4|5M}r@P9i01Y7SG|EC^r{tf@9W|8zgIbNdAU7dQS-&Ad7MU)=aV^%?#8rLxyt;XNro?f-N=@_%uEcJyVw zKmP2RUYC03W%myLPx~|f4*#d-dhma0=G9F(WPcasXQygAUbKI^&F4F0^o8E6*Ngwt z<5}Mq|EC_3lNbD-dO}V?@PF#@=KGlcryiW0_J3+T-=ja9Z% z;Q!Rj7sUUmS??JCr)GU({GWP2enIemYWyYh|J1#5bAta<_s+{r;s5md<=g9p|5M`y z@qgNXZ2!W<_tBWb{6rV_&r5XCfaG?rC;tB9{^S4Za^?m9hbP4UsZSp?Ao#ztpP3i@ zU;ZeYkCgS5Z!a9vCso<&OKRj`1 z_&+ti2>%y1{!iW0)(6J_se74E!vCq||Ki5~dE4>ve`=l&^Z(R6&h4K1{>Ivdrti%S zzOVQB=6P{!iO!{GWQrd1?Qr9z3}R|9-K-W|jr-hu6dZsad}l|EHdCUQY0T zYUUy0|I|EwK&R3~IvrG@PE3V z@#f#~e`@(Zwfvu&`E~fexF;O6s^P1n<_7P_5{9oMoKQ-PI|EC^opGW+k8lQ{* zi+l0Q_xtl_{qF8>-Ir+mpZ3QK;|Ec-) z1plYz*PBKc-r&vmHS_=UdExsU|EK2u;Q!RD?~eaddhmSZyG!}`jW_cV?B_e)n*XQ$YwhQ~tpBT)|5MBVU3tdz;Qwg+pBnFn z|5G!62>+*EZQcm~r(SD*3IC@qGarcmQ{$WPe>(p<+m8Q>8~>+fUK;cN)cCLaH}~>p z{$1A(dL$bE$IJ%2WR-2l|EVkY`9B>GUxxpS8~>-q_oY5)=e_fTFH@@yXzPvl!~ezm z>i2qab{=)yME6oE=-T52uDtrFS|I__%uG$U);?9Q?tG({!iD-JTv^Cn(g?% zcz^t#n)zw?KQ(>||EFGQJ_-M)UTxkF|EFf&AO0_H{GYnoj)(t?8~>-qSGAb&sCR{( z?~0cm^xkUouJC_)K4s=#@PF!3n|EdNP`sH3wdaRhy!m;t{p@%9yzg#G`#@{_pZZDr z`8EDe{jkk1vH3LKTPhk-*WWhLd#$a{Yo5#d8S@x6kH`D=IrlQ($NSMUCI$ajUw(7& zg!hgf&wRM;>Y|Bf1poKbEi-}#%o%rD@PF!Vlg|$RPd)L@JIoKA;E$j3;A6Jl=n>x2 zA75ae>>%$2ci(Rw@}Kp3e)r9|mG!Udb^ors@*?|r{HNZdM-K`9PuJJ|w9&!;sXGlH z%DlaLb=HK7ga1=cy!C)~Bvz6t-Q z>#ut;c)mJyxxF9of9i^t*nX||mbBNa)%G%5&zJwH)86m9Ty>SrueHbLscY>0j{j5R z`S5@0=l1zO^=|w8;s4ak|HJ>OnXhKY_r_b<{qbfy{!jO>($05X)k@z^+x6^k^N;vH z9UmWw|5I<<^Jg z6a1gvpXatu`#<&hJ%ev8P)`}~RPcZ5voA{fKlSw4Yl8n%UwiLU!T;%c<~@^M|5si1 zbb9`u_J7jm&*1;GedF!d1plXAck7kG|EX8sdO6<@1-d_*?wpDr_TKj3JbbY?>;Ky8 zjH{Ep|J5B^WR%lyu#Igk1NdtZFj-p}*B>t22}HS*bo-aB5md8Vg7?TsgW z@a|{*`QS~>gL?D*`_m6=6TNBeM(;ZN{_OGF62Jent>5ikV;=hHb1J=AKN$a~`&s=` z+W)Dm?E3M4>OJO>@PF#vd(-|;jaOp+pL&~ZXZ>F_{)+W~E$Wb|2^=9nPJ}F{R@@_|EI^_Yx7>2|EK+*z4O7~|J3tm+!6er z`i$9gga1>Xb;n)7|EZ_maewfC>RAsw8T_Am+Jg(j{6F>M8!P$z7V7ygGjB7bsFC-x zHM`9#ob0{E?%zNEa*FqcT`!wYZS2i@xcEOEkNI%;KQ-%_;{VjFcZ&a0Gd~djr`~Md z3;(BPe%{Ah@8sM>zwmTkq5uBI{MqVh1>Uvh7x8~OAM*!a z-ZRjjZrv&`s1|6y;(24*?CWRm)Uy1_&*)5)Vv@5PmeDv zuMPe$?gJlusxa%}X~FkxG2cDy#s%J+Y~DBiPusVaRt5hTH~vpuwzV?M|5KNiRRsU1 zF5i;&e{nPaPrZHP=HUO-73Rm8|EHdBzVC%6p7nnGsRhCRY5V<)mIVK&esa~C;Q!R? zSEl`+dc&%;|5I<;H~&xl)Pwg0|EHdD^X0++sk>!03;s`kpVp(#(ZT=e?^_3&=feM~ znV;7ArV8(#=6~>i+K#We?t{w0A;ohFtNwgj5q-)VRo-|U{Gaxx@qcRk4*pNgcKn~Z zm-#&WU)=aVb&mNy{9oMozqs*#>fB*1g8x$wGXI4CiyQx^X1!GWpY9ia?H><4?~M;@ zea{Pt#{X%5JQ@B^jkja|U))8nzwGD3-{Jps{!SyB2LGq-JhEAs|EI>!;s4^s|HX~} zQ{&(8e`@?3{!iD#`mOjsHNFr37dQSdZr1__toOw6=E{7MvKj~frykt8QR?fVKQB@bvH7d< z&+9Yi-(~v0OfN^{|0X{ArO)%j|HX~}i<|j>YJA>%6R$1WdiNKFS3Uk|(FmI-_WP_U z-b34@*Z<9`{VMps9&OtP{}(s@PtAO?Pl|8w<9BV>KJ}-&rg^jeaN_x9tPh*HUTo(4 zylyR%^Zz=W+9Ywj|K`K~+kCzu&6ECeV8;Br%z1*D-Jx~T+u^n1=llP6eqrYPzt+u? z^Y=1+U8djrU!C#%GS~Ob^nRIMFY|nv*OTcZJ2p*TZ`Tu(elW8${btKklOFKI6HiRs z&*P3eF42ddnCt^H*7H63u!9r(A9v)Ti9Y$*;a3{;y@%Ho^a?yLM_9{9oMoKXu2>ZG!(( zcgbp>TGV;2pD(L>=hXSz=XkR|EB;UW_wLa(_&;3_&HO)gzIi$3|EXC|l=**pJpGGt zvwb^W@2TmxdS_*21^=hVv;HprPmRA~{+}N&FE98%HS3!$dT^$1XMNLeHqY?x+pAlu z*Bdu`GyiPPk2fXywG;L?UhmX?H~RLR-hEP6Oq%YEkHY`y{LEj&|EckT_&;^Ge!Wv~ z-8a>rPxtITDg2+FU!Q(Gga1?G0r7uod>Zrr)U4Nw|5M}7@PBdR|J2?4^$q?{ozuT4 z_1ue>`}PsT3sd92yUhEvF@sY0Kka}1xKY9XsmBzVCz*JOZ^!rDdCSG#ctQN1o`3&> zoZ$b|tY?e=Q{(OMe`=l|{!h((J^Y`V`FhO%Q}cM{|HX~}Q?viOr|fUm1IGX9`EY#v zU)=aVJsz*f{6961;O@p||_HS-i%|5uHV#Q&-BgslIo=6G%9kN3{D`Gz-C zjPuURFG_s>49`#czs$x9#=o8n95^u1;|2~+^ytF=i5@j5H`V8@uN!tPx-)pc(S!4X z|5Fbg)jjyXOM2fKyx@q_dIkTd?mr@0@ofAIx#&euJ>7ztncm9XocnG$U)=aVHU97PLtbq-_>FnNx6xM}`HFWq{_!s- z+UCc5vp?(q>Uivr|5MBVshO9D|5LL*C;m^3_rw3Gdz(+f|EXC&6#u90Ik`vb(s4We zdg$2`cX;EMo|xQ_X#AfZ&%8nWpPK#OpIYbpb3Xi^?oVIyRro*kC|eH{|EFf&-X;I2 zY%rsgp66#C%>I3%_h9pi_&;rDo*Mp7jlaYHsYjoe9sHk~Q1}v+ex&KXpHwkB9$Lvz{#ePtTXe|EXF37XPQ_{e%Bg^Lpa{)V$vKKQ-PF z|EI<);{Vjc?D+UUHJ%Uur{?{E|5FdP&maCz&HEq!r{?{S|5M}F4%qX6KVQC&@PB&# zH2zP`{LsB0-s{c!>i9n$kNJN1KQ)iX|EYOA^Z(SHCuRlz7q|VlZ^yscpOwA4+xqJG zKkc7u+wp(uJll@{Q*%A|zqpzIr`G&GwdVh+xj*PhI!+C&B-z8*Kes{GXb6a`-=W@MH6uCz|ia6+zU}q5g8%dVZ5|r_PhDn>|5I;yB|ZO7z2b#eg8x&mef5pt z|J2Oy!~eyN|5M}n@PBdR|Gdo$XNc8fRb&)Ls^z1Qv98~opAduIe6xZLKO;Q!Q{wx#`_dhv?l;Q!QfZ9OggpZfGG zt_}WA-R|_$nHS{SJDz!F@P7**nHfA_@3YQep3!!7-$@hk5#C)do{YEfKK)uG5AV~P&Ex%9px1j+ z+xvO{dY|5X9`A4OD~2rO{qKF{rRnv5$DcJT_}4kJS1~`+w_kk!3<>CL-HT(RZy3W@B#s8_dTjT%qeCll;AO26x z>y7`58~>-Su=#!$PcHGUvd;(pPxqVoe6PPy;oF%XdDm?<-c`1qac-~eiMDy5-mGto z|I_g_|4&_M-?#X`xS9W_>%%uO|4&_RUZ`j1_q~g4el_#|w4M20_&+u4RpS5D_!In} zn)M#>f9g{67|j1uFSYe`@qfC$MQcie|5LBB`FrEf`nzv`dhzn$|Fr$l`A-G^r+(m( z$5Pe(4=7aMbmzR_|5|-IEBHZr!hnMd)pyLkJGHslFT8KO;g;b4^!U-&-4y(vdg81* zg8x&Gz2lzX|Keu;pSu48PX+&{zNk3u|MdJ9ZK(+UPrc0MW8weQc)qj&HPrc99zs3Kl57@juW&x`C`h&&O_3bf#$A8C-|5LL+^Z(R44;%~rPhE1zzJ8rK z!|z|QeZEG2Ff-A&jF{!k{lWj~erx`pn)%e>X9=hNe!u6G|I^>MS??VGr^YAZ|J3Y{ z|5M}j@PF#!{YQiUQIYH?_{AiQaL}LT~v$J-)&`A^uNYZu9-t*!sV^ z9@h80bumAf zxqe-k|EKM1mn;tcPrYEuovE!`%k%W}tgfx=2LGp@pSA3GVeo(Y`C@1Dari$qeh2@j z#_!<&)Op=&1^@SlO%DbCN8|szZM{(ZpYLyt|BD;{7dQS-t@(d(G^2RBpx*qNy{!h*Q!~d!Aeysni=JBlm>uvYt^c- zYTjS0{~I^{PtEh;|Ki5~#f|?{<2UhtYVP+M^M7jY2mVjZ^W*>2_{0%~fAs6m?{RtR z`1&ssjsMgA;`PP<#f|@q8~>-~c=$hc7h4|~{}(s@Pc8o!H~vqJFZ}V)e|UE-kH?P6}?f)`8U|yZ1Ph)-G*aP4J@qZ6?{b}%kJRbiSH~vp8|MzkBPlEp| zXxK3LKQ;3M*Vi8F`{VbR|F>ey&w>Y}@qcR8U&a6F_{>Mc|EV**S*FKpS+7>|dcLMx z)J=N3%>G};%kYDl-Z1liX09*%zdT)?q(98OzD&QE>FYART&DNS?9BZ$J9GWs%+8$m zm)V);pZR!R&-ne8*_r2)>HnJiFzNXk{UE~wntzLrU%yWB^*yIn^6_W<;KIcI-@4$u zM1T9j^AmmkWy$?7u9ut_Sl8ym#n0csJR0l&?tJKr;QvlD@AmXL)txfm$NWESui2=6 z@PF!BjqUphoByY-&AdEY|9Ah7ewFrrO`8P&rw;4q+Wfz`@qcQ39qa$9Szj0br{g!Z z^<43P>Sk@TQuPN_Hy)1pf7(vt|J1DKivNpyTC*A6csu-`w&U^ee{nPaPtEc0e`>rO z{!izhW%K5k|EC^g{tf@9?r-bG;{ViL+O-M(PmRaI|EaIe%}wF|)WghU;s4b5Ec~Au zpN0R68~>-qz1GPf9l>nng##&otATh z{~Odl?f=yBf7+k*e(`^5dQ2!@yzSP|HX~}Q!}3l{}(s@PmO=W|HX~}Q_KIw zjsH{Q^YDLa_Q(IJIX?bRjjzN1#f|@q8~>;7ceVMNf4o}thnMCA-`CgXYjrxUx|!dF z|I_vyTdx-Xr^W-#GXJOM`SE|==3nrCdOkc1{!fkfWBp$>9uWVh#=m^K{RuxFT|4jD zM7QhyOri(&J?`D|`ZmG;>3mw)`Q!i8@_%s`-EzdYek3r{?kaKXqr@-+q2kweLS^565;}-@u#gzh7AHjnA9=#O_4b zSX<_eFWbFomp5J#|EK3;ePR5c8Xt!LQ*%A|zqs*#apV8u#{a4DdiXyz=lhRe6#DtF z9sj56Wjp>)jlaYH#f|^-zA3%_ubTUV|5J0lKQRBN&aruT_&+tzhyRNk{}(s@FK+yw zn)`$QQ}cS^|J0lh{!iD>cKn~Z)eUWf|BD;{r{?kazqs*#YWyYsPu*nIynpe3 zYToboKQ+D<{}*?D@nS!J9{+B|B5xjl@8N~jZGH{^r|ZS%;s4Zpy~Y2HjEW19a{bAO+`cdU1Ty&mJH-RsT!tJWiTd*|8v z{pA&Rdb8g4fOyeGX9U>Dd7L^o_H~vq}`os7?_3pPn3hV!>@psJsi<|j>>St{`{!h*Q!2hX(A2a_K z_vtNa`RmJi$@o9L-W4{#5C5me+db3ZlB&@^oD#es_XGdu+wpAX|J2Mk#Q&-BXZXLk z@qcR8Z^r+rna79!Q}cYR{~I^!|EgIZ8vm!p7vlfaJU{*~Zv3D6!0Yb>|EE6q#=F7) zsh@rGz2N`U&%KqN|EDgs?acpEm)PU+f9eDF{P;h0n3rh&PtE$i_&+u8Km4DX`Gxqu zxbc5_JuA(x;{Vi#&9~zJv_GFG{GS?Mi2qX;S>ylIJM8}9|I|BeUfBz44|^Be{lfog zdzl@d`G4wC`+Vd7yv-Bg|J2M&WB#9dxA{Ki|HaMxKQ-&8;{W2t|HWN7VufFS*uP|% zH=fVd^GdYM2k|bl=g0r)c=TWHo$I~HJPZC$@Bj6u{GS>>fd5l79|ixX-eAAqw0Sb# zPn7Nr{;$K+Q-TM4!hT=I{6F=`(RZdAZy)IU59;2T_4vHIWH%4~Py5#&+$Z=yb@y?1 z2LE^8ol}GV>pgE?@PF!oix!#ps_W19z@o>^1J&?;aQSMynLppumFsQ29w-yEer|Vr)xRdvPrS9jF%^P_?d(U3^Wbl7F-?_FvG5$||+g-Qg&%C>g7>-Z# zZr!IBzRA1Q(CdQ#)8o6`au5E>x7S~^Cip*XAGq%Xey&pIyVBMVw(IqN`si!;#lzZu z(B@IyU3a&4<%zJq^I;utt9e%ZpL&~lSN^A#|5M{n?fg2a@lg0bb*1?}d;U&(e&z?_ z|I~ZT8{+@e%=feROQP|AI-dNW8gGpMQ{$8Ie`?m>#{a4Djj7|+2Wz# z|MdR8xA)rM|I`z2U&MUOT=k+EY5%9b?vZ7||EVW#O3(jOZ(g-B_&@dZ@#FaX`t$D` zGa~puo$ro&hV%OR_HFlG!`Fvgyk9krS$wionOVvY5%9jPain*X+Pfzd%V3Lyg6ROy9&MW zfFEC0dgy5If9mqGy}|#f zx7pV_{GYmP(X!zG)SG6`4gOC(h{GWQ(o#TW5)Bd9- zP7nT1Jvx3tf9kPCdxHN{ z-&e9f_&@cdrTc^bQ$KF=aPfcYl8Ph2|EbH&`y4p)@;tqNH<<^#@YCAfTWnsMeSPpQ zG(Yz8WA(jvnD4^>>G6f;#qfXXt@h_R{!fih!~d!AW%xh!4*UBL{x5F)pPKn}%>UEp zpZRpm|5F#)cIN-ZjsH_~eEeVB_&@#mT4Y|8`G0EpKQ;e80sp7weDHs2=J(BjsH{c!?&6LQ!@`9|EFd?9{w+G{GVF>PtEsJ_&+u41LObH%y-29 zsd+s9Pv=`^uP^>j&3eN4KQ;66@PF0)eDHtjeKyY)|EK19@qg-l=JW7>YF5&x&g`{Dm|e0(34FK+%@jZen^sdt;NW&U5> z_&?phqEr4aZv3BmyLmnQpL&~lKIZ?a@p!+vZFZjizD-{{a87lbH+(5)Zldvj`up@Q z+m8QJK*3mnE$6PvUz;?KQ-(B;{W2t|EWt3R)zV0>Qejqj{j5R_p(ne_Qvnw z|Fj(si2sWl|EDfB&y4?zyZ6r@_v^*~?R#yRxBQ>(*N(l1QdxtS=UrSpG4J9J#^i6S zIFPE{;Yn{i`FV9$BpUyx$KwINTaMVg8@`slpw>|EX7O*c|+yx_IsS;Q!R? z7e5yKpZf8c6N3NK&(nKn+j?o=ugKHS&)T-XAoxH1Jh8iZBK)5kpM?KY;{ox1YJ48+ z|HjSwziNCA{!h*R_&+t<@qcQzPp}-wpq#9%P;l{}(s@ zPu<778U9b*w_l^M{;zl6#=-xo`}AoP{GaY0>-*yW;>Q1Je>@icPmLe^PREz>RPpt z6x2ygHvgyQ>jC~x&Exy_`=>X)5C5m@qw#-gt^XT0{!cCc7xz!jJuP3)*D?RH)Wr*{ zyF*@$;QzFL=MI+!|EJDr`~Bem)Lk22ni~D%Gpe7j(Iqy2;Y{zZoA=kXetr9C$*~9Z zfA~E8H~*i<7cV z`(>_w+caa|-4&N5ediB-g*7|7zI!w)j8w#f=&T|EFfYAM^jzmp4tX|Eq3%MZMI4 zp>uqD^OlWM5B_X+)K{c>OiK25zE$0LzaOoB$oFTy9{x|qZfSjWga1>@|EcBw)Oa-fpPJ{x z|EXJbNc%rs4~_p*%m1nIS@=IS^WyM->MQ&74E|4jovlB_{6FpL*OqY5%9b}PuEZ5|Keu;pPKoA z_&+t?4F9L*`tg72t~O5*|EK1DOLLY2mhz${PBNk&L97$?%ypx_&;^8+>T-XpPJ+2|Ki5~soUjs3jR->ZI6$?-gUBh zm~r!d{l7YMf96-l`*VG9ckYxG*8knxqp}M;>Q1}@r(Gsxbc5+5X@4{r+KZybk_P$EQF4 z`9a@~-`V%u1KzB^i~rN})A&C%^VjfyYUZ!u|1ST3bHY44j*tISbA0@tnt5>eKQ;3P z@qcQLkN=CiS5c`q9`V!NCEk7P`6e7J_GW$Jvyboe?rG~AZ+x++x@~?S{!i!6JVE@Q zn)A8svu(bAAA7yxxb$N$BR|5M|i@PBdR|Keu;pBf+4Y}JOUZp-F`pHJ}ovo}2L z%{;yLwy#fgi{0zIIls9FpYmq@;)loACc4$hHQu~F^M172o7d;#4_A5f_>)(!^7CW9 z<4rfM^k#k}^Z#_e@QV09HSZVvU)=b=xbc7L@cA+Srw;Sx%>SwJxA;FbpFjMcn$Iu( zPxq6?|HX~}Q+FScp8u!j>m~kA&3rxlU)=aVHS_rJe`b@v~p__pY?x599x|{n#o0r`}`pjYhrL zv+9L!Ob*^}uX!WWy#v zpurW1X8xbRp<`G0D>BK}W}r^NrMxxe^7 zHR}m8|4+?&!1zD)Ub{c|KehZ{-1tAeo)va~@qcO_kN?yD%rnIQsd>Hde`^`q>SFVN_&@cbQ~ob*{GYnq=C9%Z;+}N+ z8o%BO`}%_a^XoTne7gBRHS+`Uf9hT4QSg82BAZ|JPVxLiqj z&%zOX9?FiU=l`j9*m{TfKlS=OmBIh1=dat!`gFd1^3vt0mEXR~yFur!!T)LhRBo@} z|Gaw+W_>^3|NP+tnHS`pH)p!}t*j%q#%S<`)8{Y2GkDKg@+3aOd%DfwDt=)Md6_u)V(CrRJB+yB*T@5}Rkq|J1u*44$x~8lP&9@1(|0+3~&ceE2_YXT4th zU)=aV^%3)c_`kUA_}+L!^JIxOALfm}U3}xFMBDjPx1B%!Psita@PF$4CteBuPrc99 zcf|jx_Z)vS_&@dP!hQJBT=m2A%JHS%{rXSldcAwLdN}w$y`K3^X7c{cRkyri8t-rK zp##Kh(S&;L_T*s#s~*q~hXj#bO?xqkdvWA6_B zPtU)7%t$`pe!h4=yZ_#WV@C%6r|T`Z^?>caeS7JG>B0YL`=-pmU)aB-1KKakH-gu?u zQTWyjc$u|EJe?i*3jMsh_Gi82q1lgROta{6F=g z6{~~)Q_q|`EBHV4z4wm|{!g8A$2GzKsXN?tZSa5U{2~2<|5NuEF(lQ$`#=5px(*$b zI^*yE@y;96KlSl@r{!t?76W>x_LraG-ER2cu>S8i&z}+eWzTD_59|M`Z=NtY)w|%^ zzW+^=9!%A%b&mI_X>(bR+k52HS*Z`+I@f#HgsG{D((}D*&zKkdpU$V_$_>H)si&;l z7W|)j`i7$5|I~8|D}w)1FDyMA{GWP*`M>L%*38rUfyV!-SMRF|{!hKu{1N_7z0v#= z{!d+4^+ND}>SB98;s4Y{Hop%4r`~?}Snz*pychmYjo-un#f|?{%m3-~%e+bapL)B^ zBg6lx`S%0(zqs*#YUUl{|MdCaYR`}VQ*S@D{;&3D-W>i<+iCotTJ!(n#{a4JSDgs{ zPv0-e|HX~}Q?oz*PhDn>|5NWaPlx|gv)(rI|J2*e!{PtbctHH08t;eyQ*W{R)u_ct z?`^jKoHMTT#`}H#{`HB@Explux4j>j|EKGv@qg;Q_UAwTPrb){DgIB*JUjef-1xt^ z@qcPO!3g*7wE#squaIzqs*#{`g({ zg8z#f|L1MqkNJObGyhLrx+^{ZPhDJ67W|)jSLyCB|4+TABJKawMW_5<-1t9rX+_%q zskfID2mhxovU!5c|5I;VzajWP^_JCX|EFI6#H!%`)GKCB4gOC*Z||4WGWb9JJgZgP zb6FoJPugN-~c=$gx z`{V!A_$K_HI7Y#RKZdcc5Y z!T+iI_iq~fpYB(m0qOaFapV8AKRyuur!Fwhh5ys}v3@ZAFK+yw?{9t(|EI>g;s4^s z|EZbRhW}G@f0+NL#;39VueY5K>;LNfnJF|GQ&IkV&H~vqJm&O07d4J&l^n9E@{!h*N*!Vv+_ZR;ccmB(N_WQv+&|f|CRid9b z^grHxY(4MJ<$p;u{!ho_>jCTk#*P0|;{)-3apV8g1qGL-_7wcfyIZ#!shXYt?T!Ci z(Dpxxp7MiKz8>GXYpqo2vg&4k{GYaW>QXaxX`|Ef_4>2_A2wBYmz)}@6SYqF?YV7# zm|DH2x;r*EA8Gzi_rG0}8o~dmGkqJrF8=*}rf18X2blTz<~BbM|M%wBU!*;t&A-F{ z#XWJ%z211YM|+L&&a&qpd;Pfl+u!@8dq4bN+%NuUobS*2x6J?3@$quZ|5Imry3GE% z`Fd^ZCFjqzYmoF}Z8PS@waeH)^YN`S_RsWenVsp|8fAF4OyAb%l8X|rU#*Li{_pZ1 zCVg7wsf0yYI|Cd*+l{}xXdwjEu{r}tN&%EAmniq}V?=~zi z(cit`>_ngSoih`C#@WgBe7}EL@_4M*8z2AtdbJbH{JwZQ&HTT~fBsGIe>DCtZsz}~ zFKAFV_&+u40W<$kjc>&Nsk53j4E|5ed_VkO-1t9rt5&Uo|5LZI`FI!3nRRr_(O;X# z`8*$wcjx!3yHoqNVg8@?XTBc(PdzX@JIw!6%m1nIeE7e(@qcRe$N#DEaQHuU%l7H{ zf9h;|KK!3r{!iVhT~6?SYCISIPmQm`|IO+1yWszruZRCrxx56UP6k@r}&?Q}^xLH~2qwr|Yf`{!cy3{2uH7 zsvjD6fAD|m2gi&L{!cya{_(;8#m)M^>IwJV7yO_4rWU z56J5r{9oMoKV854pBf*B|5I!JU)=aVH9ighr|#9>=5Lw*Q**!Zf9h^FFB1Q!=JjR% zpSpdUw!#0YdH>-5)c8==|5Xp|+$s1!^}zP&^?%iPI{crS`GEL8b=QKt;Q!R!y5|S~ zr@qS8=O(`1WO~2m&6_8-^Zt*&K4tFTxkGkhJD>l= z{_SmkXuY3R-B5pC@P8ew@qg;hJ+4Sy`_PZ8jvui#2h6keu=Rh(&;Q(;^&h|6;d9>~ zZ*p7SXWsIEI-dNW8n1`{iyQx^#^2%p)c6|wpPKFXzqs*#>OsTP{x5F)pBf*C|5Nw2 z>%sr2@iF*6HS?_Se`=opufKoY?+1h zg#U~CM1vQ+xnCbOeLm5D%6iT_>)KYq|LO5G{!h(3t}AvOud+2lgYTnH+jq>H^T+>b zJ3b2krygwAi~my(vipJmQ+K#F?f>Hb)@O%&yZoQF)A&C%^9}KTapV8g@_%aiKQm9k z|KX4De`@(Z^^og31plWVII>;ve``QiWK#{a4D zbUAPANc5}kZTDur9{x}J^ZfWfwftY)_&>G$U)=b=xbc7LeDh8Czu!JGH~7D+Z|D&G zpZY5EfcQW4;Op9_@PFz7*QEWQTK+F?{9kpq4gN1~{9oMoKb;@<6aS~?{qmR5D-ykU z?33PuuFVPlPw$WZSGNu8|EihaiT{h6`G4LcZ2qD7KQ-%#E|o|r}L-re`@?N z{!g7{??3#Xn$H*hFK+yw8vly_Q}?!{q||Ki5~sXO1^CHOyeTbrke|5LZH_dEVi-D~1t`}dim zPtD`;f9jntzLCQJsgJ(!M(}^?6Xp-=UD(pMA2UDLqf7Hd-*InKZ{{05x~7RY-fa4i z##JA0ooe5&jLXM2UOuCtH@@+i?e(kM9)H{0b-k->ejom?w8gaGHCdk)|EJ#j*89Q# zF%ts+x9dmg`G0CW82(Sqd_Mf&-~c=*4#@qcO_&-}l*@qcQ3DE=>Q{GWQ8c{==`db@c+{GS@X zi2sWl|EDfF<^R;od&K{#nfHhPQ}43(H~vq}{7UBk#f|^-*VE1){}=bVt6%lTH~y^T zCGQHmo+f8J@4ekVFZe$lpT_^GD{TH4{x5F)U)=aVHS3|`|I~%{`N#jMx0yG>|EZ7K zJTd0~#f|?{vz{dWPrc7PApTF+EB_a_t-p0dpP$|4`|S65-n-26;s3OMsd*IqU)-0S zKG%Dlc^dnDs6YQ2n~!6^n?0h>Ly7&qnE8L|r^^oFf4pau>r=Ga>>EQqVFl0vXe@|}M9{itr^_Jq` z|I|x16{TwZ`%-_tMYccwPsdyE^wu!{PyNV-Lj0C*f6N;Hr`KnF>7L;K)Ft-&N9O;j zi+5E7|EK3)UA{Z`KlS59JA(gHZ&nCYA)|j?}D}q?0oBbcWyHy_&>e=BZsWz{hzCzcE{r2{~BFB zGkCzq%>OkU(8agk@W^u3*Y=+9bP@9+y$e^Z4*t)Nckh_s|I|Cp`{Dm|zQyJN?e+E6 z{6B5qGd1o1)Ftz$1^=i1Xzvc@kNW*7KT^efQt!$a(*95PuhP~7#s8^~+q^&gpN?1j z{7d%d^-AwjTOYXAzt?y(9}xei>!I!a;M*&#dz@dG=zkvD;f?>>Grq(d|7Y(XZ|3{q z|8)F=CvE*~^MC67Hs25br#@hxAN-&CkbQrN|5G0{AB6u?MI8h4*pNwW=Nml|J1Dp_6+_{-Ta!N!T+gy zjK3@RKlQcKrUw6~zWJe9!T+fz&YT(ipZdOO=3UMIsqcSaa`1oZd&l3GTDJHbzWug| zQ&RWdahCTTQ)UGJr~OAiFf;f+^_^2@1^=hM@qwwq|EarPb6xO%>VY@j9Q>d9u4yxZ z|5J}zvNH9D=f0n(`#)h_p?TDcy=QGH4gOF2KT@(k_&@a%<%fg+)8kj#yf6Hp`U#sC zm^Ht4p5E^(%-`GB2k$Mmo+$oL`xn~#f%$)GzMkR#;>Q1}ciH~T|5LNRE&fl9zr+8j z3(ceA|I|C}_=VTD@!nzY&(pHAy_x5R|I_(1?+yQ_#?#^d)cCJuZ998!w)JR#|D8PV zZ8k5^{(XQqpCA06zCPgh@PBH2BJ=;$tY3@&Q_KJ9`y-n9f9fi`ANW7@5j%hUpL&mZ zNBp0r{?{E~i`SIUz zSI+j{W#=>I;yHdl>Fh&u^7Q@p4)c4g|En&t^Tq$E@qPF|HP?gxQ&-yO5C0c8{!h)< zbNrvWbbs3asqukb<}A$9-_PmNdln^{`G49UzqdGliEl5l_1*v3c&T^s-pbTn7d+;T z-}~Sn)h++0=R0D@!~dxd+y3}JwfvuczOu7CJ^xR=%X}Z}|7w5c0pkDE#pVT>|EJzr zwlA#ztLFP{{9oMoKlRRCyTklHbx~>B|Hb{q(RIE*^8v5kvEIAT_J3j7)83nRmW1_x z_4sYpTSjg4?VAd>2mhz-gUXQRR`>il zspXfI=jrEH{cYX{^Z(RY+2;lSr|x3j4*#d07v`AXVg8@GgUx@#|EZZDhW}IJfmr`n zKflHQJ^R7|Z}~s%&-$PEzqs*#YP=u*FYb%hAMxWc&+O=vRo?hE{GXm5e}(^3_w3&& zRXP2*xBQ=uPqY57deFco!T+fT*yCCMSNE%%dBIh`ect!)I^c@1{;&4uc=$gx9uWWM z=VOikQ?p(${!jbkuke3r<_Y5e)c833pE`Iq^M7jjKQ+D!|EFesRp$Sxd-kZE`pYA4 zc^BCB8)v_rX#Ah9pY6>5Q}g`H|BIXXe{tjg)J^RA@PF#2HV+a1r}L5jQ*(U$pY9i) z4gaU+e&PST&ClWg)c8aEpSL|8|EK2u;{VhG%tPY;)cwrAZXEnGZ+u3;C_0sp6N-@SGU|EC^WP&@cP^$_!Q z_&*&_{x9y1tN-SYXP)2B9{amD9uWVh{d;vw`#*Kht~F9Wec)fdKVEO~*ncNFd-Q)2 zjsMf**&qL>mjBcFGY=5|r|#bA^3+*}PRk!uZ*E?VmNWA6vM)(Z%Rb$^O;)|sy+1g^ z_ix^`X7GP{{W9mzwW^==ZkfKVP3`17y3F}`H2&}JBfbd!kH-JSjsH{Q_3(dcJRkn= zwS~V5{tsV>|5Gpb`nOEKm)T$E3BT_6 znSL$P`_-$J^m}zKOU|QfesR+KU2##;uQj;%f`rG&^nsa=Z*^&M{$0(>lh0qPcGBx* z-mlF0ftkn4?632InfE92_58Zde0*k~bMd)}`*YTXN$+>=x4)6t{{8d6ljyU4n4Ir- zL5A-;uWs`5^u78?KU%L|y~Oco{NIhmzYG4azRlmn|EU``Ot1f|*8D$p%_g;j|5G<< z(j@plHS7H{|4-e~))&VA#eMq?4;}44>9@i6WwmLMI`YR^-pu>M|7knx@#6o~tk*kZ z(1YFut+Rvw)A4(>%?bWbjkja|pBi6<|5Nk)_&+tzkN=As{}(s&|Ki5~shKax{696` zkokXVw&VZQ%pb)6eR1X=(*DmH|L1MzJHO)o>iw-Rdhb4O{NaYbkN3t;;s11e=DFej z)OfU>qsDsUE%ATa-nw<`;Q!QkE&QLln|Uzi|EWh@dtLB<>iZ@=5d5Ed=AiXvQnE$87=Q00J&HOn0 zpYAX7@t!(>@7vbqgDoBI+dH+)N)4zO=G`?rC-vdGS9%xZc1?}` z`%v#b1-(*V)vWGez5AwSbsgf{2Xrk6{!h=>vmih5^@aNv`@D`hZ4!;=O>DQ%XWV$l zxWCT-Y5w0gFP|U$Uw&TORQG8=sVdq(FL=KW16v3Gr|vu?JNQ4f{GT2#|EKP6o{sr{ z>V7sakokXVJRts0-Oc9x{bT2c{``2C@0EYx-PP8s#Q$l3o*)0GZfzb7|EHG!iyQx^ z*8D#;&xik0%m1m{ncu?ysqujLKiv-+|EFfY7yeI;m&5<52bzC;@vfJv1`eJVd>y@h z{7G;2$Ny=68vm!p_u>EI#{b2Q|5M`=@qg-8BU=Xl7x%F3&-nA>74d&MKN|n1X8s`l zFK+wycU5MLg0JIz?eFJ_#{X6C-zv=iQ*(U$U);?9iyQx^=J@!(xb5c;{(KzIem>!i zM`He;&X4(R_`kTB|EKPAO?v&`xS9W_*8IP?@qg+8=A-a`apV8gcuD-9n(M*;so9SI ziyQx^=KSz~apV8g1tW99{6BT~YuktQf7STECJ%0|TKUk!>GcMzADq9*8$bBY(v9AD zL;Roizsj~V|4%*K{1^UDJ<#Uw;s4YF%zHBbPmSMX{-2ub#s8^!y_o+OH~uef{GYA| zZ;Ss^x3&9;|5Nk%#s8`Cef1t#p6G)!pYX=(4W75mo39u6KfT{*{9oJ`u3MVezi7*n zMC1ST{CvG({-2t!Z}>ko+wp&KGyhM``o7HniyQx^=Ia;!FK+v9Z|2w8-(|g9*yjcR zr|Y@GUJvH~shisU!~dyUpYnfd)(^-3sqvloKQ-?s{GU4arfi$%Kh>W<|CSv4`~PI` zjyLC|-kdziyYsCb!ur2@e4aJ_Pn~~T$FTmdy8Er2ga1?a9F-U5|Eas(o)`R|8V`v7 zQ?s4*f7Kmr-r#Mgjq>x!x-mQT*!j15_n(^ff4bkZ7R(L)Z+D$(!T;?&axnNm^-lYJ z5&mz^&S}B_mD{`+{GVF>PhDl62>++vYxBVHe{mN-(!EN@XZ=F_U)=aVH6HMSi}Jnq zzWi43e>xsM3;(Cad*T1on*XQP{6F1qFGUJL&hH~!Dtt_T08K4Ry4R;rFS>%HRtSo7)q&ExWE=Kt|K zApGCKQ~poA&(?Rv|EbIIhUWjKZk(C+fA)O%KlL8l&ip^^zt^_o|J3+3{GS?+hyPO_ zH(!YVQy(*riT_jM`|y8p|EY^k`9C!t5C0c8{!h*M;s4aUAMt;BJ$XOl|Ki5~ zsdvBrwyn4Q(hD$ z-cJ^m;eU?k^D%eb=HUO-?FJ1G{!fih!~c1YyearUb^Z+_`F*?}|MrI;GLMz-{lMZC z!T)Lhc~5P{hxzdyU0;~`=dmWwrxf7s@q;s4aL%=fYWuX^VCEquQG z`R8re!sn$@ulLH`dxQT|Z?WHJ;{ViJZN8SxkE_)2N_LeoU(S1X#UA`nb#HkJkL3Nh zd35tl-nZO35-;V)?^e)}-@kjOay#P@D)oAv(Ysg5)@S!ljhSZiA}{dnT7EQjSLv@0 zYyZdg9O3AO z_&@c2`|}e2r)J(R{!d+LzR%u&-urC+CjL*`Y5bphzwM9zQy;MH_&;^Id3XGuuCK_} zQ^fzNcU8S;-s0oVx?dH~yu$tSE~|Wv_lNJld_y_!pIkkD%G^@E-h1cuN&7!Ne~%6e zga1=!H<`x!H&@-P(JbEI-a`iz2LIQ$>4U+);{Oi*vVE>v{!e}Vg2#jZQ%~HmgZt^n z+q-I2>aA;s`}sX`&pq~jzRr8+J;U%K-o^J0=l$VbWNlv`ybsM7m9p7Mxw>Dw=FQ;i zi}z>yN_ao}{(Fv?S1|vl`*q~`=fnIz^}%PK5B^VGWxfypr~6a#oOwa>e`%I5Ccrs=F+MjRFb1&etz1iRVwm18m@AhW9eO|mPt?kc;M4KP?-f!~^&6g+I zz8?7bu)gnUE1vacz0rd`U+^w9e>Co|C%y4L_VvZP+bvg9m-8 zxIFkj^|)E{g8x(Jn-^yOpSnh`0m1*N&$snEPW#6fe*F4Z4P`xW@22+i(Q!BZ(Yu#< zy@nTl<$b@culwn9fAyZcU`cBE{z)TzP$sjr`$p8uyFIrYKR$&$1E@z>9o&3fG4lWqTpZaUZd+H0>3{!fo@ za?P;d|I}T^-Oc*lzWWa$X|MY%dV_&cFf9ef39}xei{Wl*>`#<$In?JVki$=abZC_8k@k{tW?O$sC z4gaTRULgK2Zv3AbkIMSLIv<+(e`@CA;s4^s|EXC|_ctdxzWK&%zdk%4{!iD>d_VkO z-1t8=^ZM|AY95dOQ}cNIpPKW-|EYOA{!fkXWB#8SkB9%$->+%>pL)M}zM5Ap_TFcI zKH&efz0|hj|Ki5~shQV@|BL(9Cm+w#&nI?Q97+wHxh&E6KkZ*?-w!{zak+PieZPFh z!Y93%|A+t6{w3xC@qcR8^Tq$Eca)X~|EDgo#{a2{OLnIYmag&hVcy^Nm1`5da@JGc zc)B|Uga1=+w#NUdpWeDH_&;^w#?8V1skd&}6#Soh z^ZE_J|LK0Nd2(g&f9h3><_G_$pKlH9mK*$^TK-R+Utk`{{GWclg|EZ^#f|?{=XSp= zHTL~|dHQ*6UXPl=|9RVdFZ`bx4|wmJI(t1^=hcxAlDSf9fv%8wdZV?%lsZnE$8a_ZiSI_&+uC{+|2C34i{6{jLc9Pxp)Y zfA~M`Pc#2dE&r#M|I_mi>f0pvKlQ*qjf4Nw{<-Gi@PF#Oehq^EQ{x-)e{nPaPtD_* z|EKP3z77AU#?RsZ;>Q1}@oo6OxL=z3jyI2QbN{>E_&5BY?hlRsi+kL4ANc;+ee0w? z81|ueyMA?3^Z)XZ?~i9={-2(|yZJ=c|5bB-_&?o0&IkV&H~uef{GXcndiXzeK`&dM zxBSO>9WQ-2crN_jSKEK$&H3Q}v_HNQ{}=aH`M>bS6Rywsr8oDZcgrul`F#DU;ja>n z|I_v174d(%e{|W2-&Sw8>&5^1{?_;4 z<@1dHiyQx^?rR>9`G0CY@AyAIo;{xVe`-7+{!jbU_&;@S*R=oB{&>Llv;OJZyL71) z{Gaw`9w7ct&AdSTpBi5{u4O7e?jAdw`y`Gu#+?v#{Wj`G`_Mranzx8YQD*Ru)vwt1@A3hBKr{;M0KQ;6B@PBH29_#-$fTCedQ&WB>m$zYA3yD<~+fR>m)x< zncbjP^86dusT=%X&ryE}{;z?pw~hZ(H)@n#|5sh3S(7mTPkmYQD}w)1*m4#sqszB|I_hl*8f#!x5^6s zFK+ywTK+F?{GU3zb&D|nFK+ywI;VA;F#j)Z{GS?MhyRNk|EK2h_`iY2{uumUyDVFe z&itR6`Fr?3?a%S>e`>bl|Ki5~squ&SKQ;ak|EI?L;s4aE$ISdcb;A}-ga1=^DzJGn z=Ks_~Mve^rPd(;=wEt62nlK^wKlOd%#s&YUzJEe`{-1jClu5z=spp#y9P-;y{(QGw zIVAW$ZSUH*d+>ki?7a5D|EV?qPmKpWfBnsVyu2=*g8$R@PPy%a|5MBV>Gh!Te`>rX z^Z(S`Pv-xr^V`^bNSptsX8mXUpBn#n`lr|U`S5;NdRle2Y0)x;|I_)jZP_Y?|5JBu z-71xR&sE;t+GGX)r|n%@whsPJo!7io@PFzsKhpf4n)#9VKQ;3S@qcPOE$jd4{JXSE z`aZm4{PmD|nEzL2&hyLcOfQI+jgQy9ebYo26toNeZ~5-|dC%FrzovuJ{!iU(NP7OC z8h^t4zp_gf1V7l>{2KHB)Prrl6#h>=a9E4ft51JirN=Y>?`K;-N;LjY+wm*-KXq%H zkJaSB``&ejH%sMLz31I%WL9d#iFdt++wt!``HuIM!&;{1zVWsr^d^C_Qe~%Kj)AC)A?!spBg`e|BL&}TVJVqpwIl^{f3&~!~dxV+wt&!YJA_s z$uA|k|AQ}jv%Y4%c`qc|{{5LZkALHd=e#+;ZEH?=GtX!=i^Yy*iAOENQ@pt&Yxb5%n-fgdG$=~n2c|874&(Gs+eE{E%@3Qp+ zyxDI5zR;WP_&yMFwi8t;eyiyQx^=6>P-)ZMOW7v}%PjsH{Q*O>pO#;@W3)c8RB zpPKoD_&+s15dRl9{x5F)U)=aVHS5>n|J0lh{!fj+nlWZ;RhKFAg73p$y*+7*cRQPJ zi2u`e8vm!3|BD;{r)It({!h((L;Rnb=g0r43v7L9{GS@{i2sWl{}(s@PtE^!&{8!~d!AefYn)|2=<#clX;m z+0P^HOEmNUbbS0C>;J~h{J*$a|2OWle|m=>uV8e({d>*Zz2*OOK26NS;{ViFJ$hT1 z|EHe+*rUP!E&cQKwEwF*5d5EdqpjbD|GR1CjNtzYZN3ZsPrc9l0`vdW_yYW&8eg>V z+MZQ99*zG~%m2lV|5G1&Iqm=A&hD1$+woB&#&z<>vrS&#!JG9>*SwOG=*qumd*i`A zZQRzo!k#ZRqP6#tlW(Q!KHSQ?%C>i}XyMKC;s12KH2zN=e4F{dxbc502hOzbU&iG# zKM?;HH~vqJf5ZQ&57~Oj_&;@}%~Qnx@jIU2|IBOQ|CsrJ|6@KM>;J0pgZMu+es9c< zA10dhf3+RIhyPRK_wave&JX{m#^d4t)GyleH~vqJU&Q~ZxnKA{HSb6KpL(NtI{cry(7dJnd+Q^5 zJ($mzTl$$d9?(3EH}Ahc|KzPA~Ij{ayT@_TOv%clwa+eti7V zGuyX#^Y!Aa)JAXSrS%`N&U>#tAO6qJ-+Yq&zU+uTKV{Fq#`;^{ct87nUZUSz{iyd- zHg5|5r{k@(c{uj_OYf~VPiE@(W_ho(`6jm3m-j-OH)6l9_3OK1`C9yszurS1U4jqt zzGTR7{E+wHkyqo3yeG_@ZoX=u_o$_dga6a}XUgV{!T+fr-&~YB_xCxz|Ei+h_^>0t z={zfV-G{dC3jQx{{GWQEZMV<6KmL)z5SRDMHdacbj zvG;$adV~Ew75}H+Wb;(ak9lv|Um5(L&gbd!{rIy=^`i1Je46+Dt5@3jJ>id^J$-8M ze>#4@9tGyl?yA)LtyY(g!T+gik z!T+h{|Fr+I^<}~TsmDK99Q>cUWABMvZ?2wyaD&;w|EYUjHU;0~+jAOC3I0#pZy2~C z_`fS>&kFu;$|?V+X8m8AkL8cQX8x0Smt39iq%GyVU%boKuEV2v&%SpozQnuS{GWLd z?+WvN_WtuO8Fvj|AG{CG93A|hp08~F%;5jjpYJclAN&60hiyI7;`!eAKbv3befXId zga6b0J8pj3J|DSi=J7rLqZNtnGi!}EUeM;NdRN-KK>VK`f6#m%{!e}Q# zi_B}_|I~Zz>ks}(p3haV39Pd(|Wjlut^XKybF{!jhX*5cs*)a&f)FaA%xdTUYef9j<+ zpAi42p0jFQ@PFzFk1PrPPv>|2>^Z^zsYgst&;L_1KNkO|$KSW=so?+A3sG5~WoErR}ddTQoga6b1H;f%0{Ga;9arXuPr*1ZTVXAQQCI0;RPp)UZZ|?`z z?Fjx)`_C^qXkN8eo?hRzWru_RQ?IY63hV!B|COiwpL+FyV>ZvSp+A17{dt7{)8mWn z&vX2rn)es}PmkC9KQ;6G@PBdJ*JpoxkrN{!fjc#sBH+&rX|PhyPRWF)xPyQ_KH(R~`%gPrdK((J=o{ z&H3X0;%5GzdjG*=!T+gQ4;TNZ=K7fb7dQS-&HB58_Ft2y@89T>h1Yts{_oj0U7zUD zZEy7E`cHi8=0w-|U2-Vx|8zc^ZGIsBPrdb& z|I_*70r7uviGrUtnYhE*&~Uz@9({LpYnhHe5d@M`iOmf!2hWaRiyo&dY3i+FK+ywdiU-F z!T-gL|I^PSHtsnP{GWQ$-h-)bqo45Y+xHv{>;G!|wu-d>)A5S!-_zj#)Of#toxRc@ zzr*JJ{r1n*y?xi-)JGq$^6jO?yHh8hTkT!4vn+Lc%Qbmd*PEU<{h~4X_`ekwul3$p zyeoC$Kh<5dvo!V9FQ4-5biFs$d2c8wO^xdGv>$(6(azMc`Ww9078R!ozPr(Th55hM zf2r;*=Ktz^w#m2C`CT{r@e7|?pZf0WoAVZ|nwEFx%5ke_7#;|GDf}dlLQJ=XGAZ*uKV-q ze{Wv!Q#s~+_Ow6X&HTXiEf0EMX`X38!$aOfZQj`N(!+i{)*rsBurkrT&pG1zGw-kU z=~dqO=J_uBTXlCH&^YzYKOXh%^nweX$h|5!{!jZix8vjg)Gh7!_&+uG1OKPy`SE{hd@KG>&GGSn ze!Vsyu-7ZU@$O~*@DJbpt?$qIuKvdF65ah@)y=%Y-+%Rc-`=gDR_eXhfAH&Jp5XB& zfAr@0fAi6ozCXVA$+!OGo!_%onE$8qmH&$y|EK2l!T+hdndke(j=y^I{Eu(^e~HHb zX@Ay7#{a3a%o8qI@DFc%ApTF=bGz0K{?FUy4dVae#{a2%cc~NnpSow>g@KH2LGqdYE?V+W!dSzf32F|O^s@HhIj26$@yiOzAMwG zW%{j5Z`Q)*{S_D9m0w)=Yy0!yll(06e#d9t?alnWcdxp~JG*}E)Nfkc>z&iEZt#Eo zD}NLGAnWbo|I|F5`G0CW82(R2gY6@v-@9OH?e&{?c}^R z&L@6+o4QHwm0R=w?#%m}>D@Bt)%~~g?!In)*g&|O()Fs?KJ*R z=fnQY|5InRxFXE|i<|j>apV8In>A0h9X!R4kH7kS!enpxKkbh<#Q&+U$Z8e*pSo%5 z^!z_HzU$t5Ci?yy|L;pDc;m_Nf4=`I|EFgCWc;5xD=RC^|5I~5_&+tr$N#CDv~Cvs zpSnSd#=-xo>oiIGKXr?C?SubQ55D@^;Q!S3Oi24b^#k{%*Z)=Dckh_s|GdYK3G@Hd zlOLE6{GWRE+7!c_iKKOtkkq;hI)5y)jHMamqWbqvu~YK z-MpXhe>xuT$N1|V=My*QA2(hw?#%gqncgq6Gksxhn^uYAHO*<1YCiF&RnvDa2;Q$l zkL=+8)Y*euh53K#_E)C;pPKb27cBnFAK%G*-qTNf>fPJsS?yc>iFdCnTL%B9$Kwa_ ze{tLV@2ZX676c!M|FgdzBpUyx{hONi!T+i8KKMWNfMIF>r|y4ctKk3CU9M~q{9oL= zKmL(Fp6h$*CvSRlefU4^-_<-J{!iTv4{7uNsyi$Azqs*#y1s$KZ9UM}PF9)O3BIoX zm078G-g(Iz?}Pu-{xtqi&HcgushM|%|5M`=@qcmS|J3Y{|BD;{r{?+ae>y)J|L1M@ z8~+zK{x5F)U)=aVwfvtN|JP~IA>WRl!vASIjsH{Qqws%m=8b5B`tF|Eb%W2gLuWv&}Q%|J2M6Wd2{=_&@b9^NaXD^_Awu@PBH~2mhz$ z^~3+EdHwKzapV8u#{a3i+3SP;N!t@VG^cxC*bn)`?UQ**uc z-`;$l>}LhuIoGug{!jb!{P;gLpNGr;-yCn&1IPdA`r6ofz4$+Mr|YwW|5M}rnE&T( z>-pB~JkyWIyuZHvrh9j|sa^1YdVc2n;s4a#Zb|z;b-}G2Q}{o1zneP-|EC^c^ZrH@ zj`QsUZq2oS?>NSL(5QU-_mTH__ZijIex7odckkP}*!l~1RJY9w#Q*8|x%PhBIQTYy z|1~pz+yCZUysv%qR{QzUP2P*1TpIk}*ym;j|99}2%HaRh<@WpC(>D*OQtvnaSO3j^ z-n;Gh(Y^lD#~TlHXY=0Pd&~pk|MYm~0pkDE_yy+w#f|?{AGPhw|5G0`-+=#9vmP-1 zPhDXi4*#d#ZC(rir^e^u|J3_Wz8(Bu-1t9rmCYN(|EZ6f$HM=q58CtJ{^Mre2kiM5 zoY&Nw^&FZ1mpA0W;3q51e-*#b$orr@|Lb2h@W#{O|I8!>ABbPW|Eck7_`kUEfBa4d z|Ht*<|8kGbO3(j$<-Oql)Q4VuKlnd2-VFbzX8s)hPtE+o8)skS$LD%#U4MZ;KmPLg zg7dwZ$9U_WbG?tg{BG*E&A#i8uR58Y|EJ?~zW6^i*NgvCGanECr{;X|f9j*w_&+tC z691>Jdj0+2|J3+B{GXcR;s4ZJKmJdR-^Bl^<^R-0c0cfcYUWGg|MYtBc>G`7_&@al zdq3g-^m^{M_uIrpZynM51&@007q2H8|EK*qf9C(ijsH{2|HX~}Q|~ozRD0baZ`K1I z_0>M_{ipn&&X>mjspbFT#{cQ~6)(LR{9oMoKQ;ac|EFeu{GYna<_F^cbU&EihyPRW zFdu{eQ*X2RH~2qwp{?hO|I_hk{GXcNKihwMiOH#{!hKk_GkW|dY%0~)8@Zb z>VB*?e`D`w@2AXH;QzG$cKiLYc^~hm?f08DKg@e`>0UgN_u^Ggo7Y?B$9w$Y`FJUB z=GEK$ol3nvm*;gg58L0nM#tRLmz!F8r}|#W*DLQ1HcxRyi(ens(f{jjY^ zX};^Qu5a7k<6Q3{b!laK{-3UI^YO4AZbxvFr`~7tE%ATqgZ6o__g`l{AM^ffo}Bjq^SkE5yzzc^f4!NH6B$n-u(?I=jvT!T+gm9Y)i>7Y0>&f%JYTgp_&^>bX zdQU1W<^AHlZ{14s*2BCX9e+2z#JhOxh~WQp{L=B)@c!`QZy$eM@PFD~Hs!Y9|J1wY zrTw4!=bV+2H@w2algf^*Md1Z$D<95C5n8$@;zcKXtin$N#Ah zykOtIng3Jc{qTQk{2=~M&G&cA|5KOS`q%hBolk|$qs0HIE1!J{AMTA;#Q*8>tT&4P ziyQx^F0uJu_&;^A%^So2sqrF3Lr;3Mo+AEF?+4~7;r~t>`%v(pvmRa;{Ga;f2j&O= zr*6fyovsfUdo75twb|HxBog8x%Ly>3(Rf9h@K`I!Hw zUS)op`G0Za|I{07UMute;>Q1}pIoy#_&@dHWslo>=-=?|_sxGe_&=TR*txUA`oHS? z9)2|VKRtfo`pv=rsW+HkWd5J}Df5P(bU5F8^`b{p?JvB*d%?6R!T)LhNq5{D{9oM6 z|5In*Jt_DbsZa>GiyA)sEo*)U&qk3I0#Luk-eYsf7+jUcKAOv?|=NC9#7-{)I05X_&+t@ui*dGrRMAK ze`=d#YxADF<>~W@kHi0|@oe}%Z~OBa|EFfXTh{+o;{#d$H*V(tsktBcKQ;68@PBI7 zdu9Hgnt6lxKXr*U{!h*PMf{()&2z;6>Ff6{^LO|^b*ar~#{a2z9eg&0|5KM7IF_0_ z_@+F4Kgi>6t#^wz_oK^SZcTKpmqsP}pKC{ZY`KrPc8o!H~vpu zUVbpl|5M|^ng6Fge9Hf+51jIU>SCMEx8lPkdHVZ2{qVC(y_w&~{6FnarR{!h*EvIZ~rX8m90|LJ(F?|WX|71i6#`{Doe_#HMM5dWv%zH49bf9h?edxHOq z8~=CU&ohGm+fkhMf9h>TrNRHjjsH_`-?=OJKQ-(9;{SB~4cm)?|5LBqz9aZQ^{UNV zg8x(V_Zj?O-1t8ozi{oE;QxLxdPeYn8&^CT{GWRH(zO3m_wUs;RbyUZp1NhnOM?H? z&s(!P*9iVk&3vryT)!vpyl>49o{xE3f4Oq6ce`%2QlIzTmuUQ-_HSiA2mhzeG7p6R zQ}^jwH~2qwzk>Ry`)VHc?f9$fFRJv$1LFU*zx)S9jqyL-U zz0Ko|F8Gmmw?3DrhID+(JHO{;sZLpMd$WFUgU0W8_cZ_6uI!z>M$gR4`*!j4d|tne zh3_UB|EJdj|Aqfk&N|gs@AXl z`Iv{<^9R34bjuOH@#n)gUNZ2v-W>mo9>4R(|NXAh@4dTrs~P;C?l*o8{}=bp+FvGm z#l?T}=6*kP?w`GR{qO$9SBW0}&+6v*_&;4QjsH{2|HX~}Q{#v6e{tjg)Vb#S@PBa^ zR{Yb?hwV#?{*`F_pZ4#XUo-f>xbc5#*89D*(P`dzK>VNXS8k`Y|5JDFSTp!PwfvvD zZk_K1|EI2BGdb_BiLJ*QdjR}i+)Xb{u0NaU|610$Ecm~7uljB9e_d=nQ~Y1t_&+t? z5C0c8^ZzD}`CagT?Hkn#{!fh;#Q&-BXZSxgJ`Mk;=K16E&##;GV3~f8)uG%z1d3{dN8@)91&?K4Mml41ZZOdH$K+FSF0QFzNZut(iPtrYEdhBl&sA^nIBgFtaoF&-8@&S^VEc z@BJy^|Kh%V-CW;Z`--&x({}pY@6S2fZOxa#_tCd)o9$h%dDGzkv>gwK|5Gy`5dWuc z(W+_ie{tjg)Gf1`h4p{c&0Ag({GS@%hyRQF-BmNZIsWV;)4h2-^Z#@`ctHH0x>fTg zVf|lq>y}M}|BH{0|5I~3*8kQ1%~~`G{!iVod9&dE)Of(h&zk6u$M5Afn~-SypZ3RJ z;s4b5E9U>Hn`X5M{!iV+{MMSEj;%hPT~DuXRd=%{4TAsE{;c=R{6978IWzxHeNlr( zVg8@GuK6|Q|Ec-?#Wyal?(q{Rh4p{6{r>yY{!cw-Oxpjc$Bn%w_&@c;3FCwRQ%^Dv z$oxO`RU?Ll`G4x(d7Z-iKQ+FT^?%j3|-gZCmf9hO&J@9{O=JEY%#kGl^cxa?|URzrq(dPeYf13G!-Zn1~{}(s@PtEc1 ze`@)^xbc5_zjn!L8T_BRQ&x-M|I{5?HVghwT`Q|e@P9g9-R$OxKfjnq8UJ~f*&W(u zC$?vH=K8>y{;y|F^6}lXlh1cWZu3;p^FOIN+3Ats?b`OrNzHoo$KLqA5pRF)oins` zs`*Esd1skF!~fmB^^xEQY5boWuY&(mv%V$s|J3+3{GS?+hX2#~$p6KS|I_|FAO26> zY-rQq|J3+A=KrbjdCdQ-?)3b>xbc5+3aH@C&d4m;R*h)w|PVSpPKuD|I_|>HvFF&kB9$@8~>-~eC*$+`SIv$&!}$Zm*M}k zKR(O;{hRNPFT(%nd}#cin)!zKzqs*#YSstF|HX~}Q_KIU<^R<9EBv3D^;+?NYR&(P z8~>+fePjGz-1t8=^9=ESYJ3#)|I~Og{9oMoKQ;c0`G0Epzqns%T2i(Ajs?Nrv47pR z#ooirpW*+s|IiU>|EKOXB0E)ozz*M^^?s)g-|mgid-M8jiEeazp*Qmfng6Hfr}2O4 z7T2ZM|BV~}r|x!bo8bTA#{a3WvHOGnQ(tZGAN-%1`+@&c^M1qssqwn_KXpsj&H3Q})bfA2UwBCTU)=b=xbc5+ow#5)SS=0|IGF-xUOxg-&xho_59@AhkQHhNl*E~EN`~s z|8zXIc02p2mhzW2jc(K zJ?<~Cf3JDJzu)rh{e}P2`;YmJ_&@a>&!qgHdhUwF!T)XPH8J?V!>3LJ|EJ#nLdyTC zkJ$XKJL>l;zw(8rQ~$o)eja?*%{{z#+IIY(_AfQRhyPQTncu_zshRhM|BD;{r#^1; z)$o66))&VAsSm&MPV$4FweiP4^s>!UIIzf=AX?}z`3 z8~>-q&*A_084msrKbNz!N?O13UgfkNeRd^pd|kz?3f^Ho!0p8-<#u~c<;QlzUJ(6y`Q(|d%V%v-p|?o zcMnRuxgQsu`=4XFe$F@G=6`zQLzk8O)q9_L!H>`R^O?5iU-RZac=P@-|KiR4C_U#3 zZ|)cVPmjmEMEqaeJ7@p=nC=hr5AlEMBldp7|LOg}>x=)3`@ij9PwP&rUQX*7e|^Cl z&&T{fou9`4srh{3|J1u|9v}Ws&3dKG|I_vJ{>J~QOYHN@{6Fi?G|2xxf2LBf~{!hKlzF+Wvdj4DN`w0K1EEe4Q*Yf=9OnP2CvMsr{GWR2)*ZqBsSCH32LGqtux*d|p6bWc z&lacrpPG4q%>PqQ+q^x&|EZrT-i6=tUSh}N|FnIbt#^k1)9bs~e%^`yQ!ldlCip+? zKW~qDO7nl}StT}q&HSJG8C$Q+)`Rxr$E-^EKb>#xocX+7NA-FPeRx>#f9iYt^bP(` zeOs5V!T+iIoc4d}2k+zfFOR5uPM#b5pZbx_rTDHRdi+JZPVjsWt5@uM(f+)fB)a~k z<^h@ir(SpJZQdVk)mv@;pFQ8Sw*9?JUU;3?qn-Ar&9`|UviX8GFVdTNocKTOkH5wL zshPit|MRx}@qcR8&&L1h`Ruc{?}K)F{(J0t%@=#i|7rgNHqQwEr!G45Cf}#tQbxTHgieve|mmTY$^@@PrYOH>fry>(;k03_&@dT#|I}iFDg%6I{FUY zf8NET?%?~ud;93S`2O%NneqhRFWw*S+7$esuCMIC{^0-A$DV&K_&@d0=S~Ixr#@+3 z5C5n8Sz?Xv-z>!yUkUyy(q*Dg2+V7w>@o z)B9oi_OjsrcHKHT_`i-13=95G-LF^w;Q!R^+u6UT`Scfg>f8JDNfs~pmG|PQQ>0C@;Xk>+d*QS5ga6b1#T$!)|5LBD z$H)K0jsH^@uUs4apL)&Qg~9)+mrj@v{Ga-%`|b<#|I~Nibx-hr>cO|)5&WOJ`KYIY z|I_Q)ch0il|J1`)YzqEQJ*DJO@PF#9yN)Ky%4+88{juHFcOUsoZSSr2>s9|d>v}Wq z&%C@h{_ny|8hUTH_uFTmHS#`ep6bMrZ11Dyp@=e@&ze`CJc8((($l=f+j|I_iz%ftW0 zjsNqu^W*>2rREFqe`@(ZHJ%Uur!eDRKx5fWyJB|NSmzXbncA40|5NWXKlkAEBfa<9yvkGc9``P_ z_iK&+jP~aG?bjD?wwGj&_xrWm&WHcg`-%B}%mP&Jv)2zBsK$?SuXVq7+4~*;=WXX_ z{a;-#KJ?bUQ~drNJ#ajErR7xb!~2ef`G2~RoU z|EJ!2+W*Ck|BIXXf9gFp&yV$g)myFce|r6k?R@w@HNJe*j`?Yg|I_v@_WNJf|5b0c z-~ZzO)Etlhi@RFuCEmMs?GOG>+iCot8t?c1=wIQTzx;pUY8Q?FdNG5A0A zhIJ|br!HKxF3kV)$6vWR8D4*rKcDrs{x9?Yy0v^dc)$g7XNCEH>fSxN1plYbZv4Zf z)$p?XfBrY+`UJHf z2LGqV>)`+5#{a1cY(5$OPtE$V%>Prj>|Ha=|5Gsvqg zKXu2x4U>}BPWpCw#q%$CU)LuqnR4iqcmG}ulSg*H=*{}UgNj~C>keyQj=Dk8aLFra zedV*SdUxtmKlnfWePc)SetRmskstT%m%f?S#~*mpkH`NN5B_mls|Ek3?$Etz@PBI7!^QupyLPJ){NI9uGlKua&*A^n_%ZyS_GkTD{GYl_w`#%v zsqub2Cw}P1(|bq%+?(^`|Fl2n$N#DEem&p#*t@G8-~5GNdgJTxf4ZME{!cCcr)FLt z{!iz}_u>EIX8xb{$LBHsFK*`ldE50e|4+^1;s4avb*h$hx${du{{Z`Z;Q#b^ojcol z+vfk&UAj~a{!h(z{GXcjZ_hdK2fu&$ovS9pc7E;6^}fIHkKXuS{GX1;|Kk7Dy#Dw< zHQo^ar{??x-~2VL>woz-Z$9sr|LX5){h#;#;oZc%;umlJ)4OqpYm#?P{mUDVcjV~5 zy_wI4|I_2+_wave_8+(YzuxvQNs@b(|IfR1L8UPNPxqhm;s4Z}5C5n0Y5t#D^Z(R2 z&1#4Ff9hKGD+T|j&h%;jU;SIA2WwKdMsmxrhYE6D{ayaVAs-d=tXDtj*JX%zkGl23 z{J-S5hWmEr0~X91;oY`Don+tx zk9zm2-yqF5bggCQkJdNN^lq7*>G?A6Pvcs3($AOCnfE8t+hxw%%beGjIUg`{J>ksb z8=HrWpI_H%>E5y9HRVVg?n zUb5Xa>GK6M&!6ctGw1(huD5$>h4k}ZRW;oYR<4+SzbagnzJG-Z>FYILeRaCu%-o*2 zesJX~>7Mr5>Xm~3``5g`1pmkVX8m7vqq@}-{GWI2I${1_-1xsQ`+pPsUnAR&|5NAK z=aKn;>MU#gpE{>O!{GnC8`TT`FK+x_+|2(|GcRyLzo)(NSol9}$A97f)LHg<#s8_Z z8`cf}PtS+``S-^Ac0AyWhU2`MU&#DF9pA#%L&pE9*?-Q8G2ZyWR^_9;@rR#(`nWgi z4defGJoEYRe`@Bvec6AccWze7|LJ<0=j0|GS3c_7@qT|OAK_g$D<}9roiE4kFaA%> z^ZlmLFz*_T8U+8R^ViC56#SoB{!e|a&5OhTsagL5|EGTN(MN;-Q?uT0)xi(>_F+SZ zhWUTmK5FQY;Q!R)N2dIrnt6cuKXvb3-Gl#ASIJBHKlQ~8>j(d*#-HN<)Obq#pSneE zPVj$f)_cbP#f|?{v;HjpPmK@6|EckN_&+uC>+pYSwpUzpv)})g%^D}Cp1a8#fB5Kc z2Ayg1bND|U&-^_6pSnx4mdWVrZ}9y)HEo{M7<;`ppAY<>UVobTf8H%q{!iVmS;OG} z)D2rSNG3M!@B3%BPWOMDFaAEx?ElAly>|cN{h5Clcjo*+<|W44nYS2s^A1gtx)nYx zH&YV)S$@wpwtnHSyqgcmN(R>b#Ji=<@B1?Qm)^|BJNMI%%m31BR`7%E%=diw+h2I& z-AcdyD6MDw?dRV3zQO7``G4v>^Lw9O_P#gAAFS}6H(qZ3wLkO5|J`5b zr)iy+^^-GwV^)~|*Kggd;1@d%%1-cqYP=l&PtEgL*8MF%p2q*_`tWf0KQ;5f@PBa^ zzxbNpKRguvPxqh3|EYQYLx1sdTI2t8KAtcBPtEYg{|hV_5d+&}zZ-1t8=^9fo1SB)=Z{+}BEhX0Ej z|EHG!Q{$EJf9kHbzA*kTZv3CRz4<^}-=IAI&S!$p>tOTFs-7LSoe%$~{qb6_{%E)F zk4LOld6#$3K~0j;HA}p?pZGtWU;aQ2Q zjsH{Q)9`<4&Hqz#JJ`ew=?q~0Jn}^~1 z^LkWhxyGB<3;(D68=LRM|HX~}Q!}3r{}(s@PmK>{{-0hS=JVnI)ObMrU)=aVHTMJm zr{;b!|4-e^d?fS#)V*(S75tyNo6Sqa|EW11{}(s&|I|Dl{_jjT3;s{d`q214HTNI? zr{?`+|Lx6ovubIL|I_}hZfz0#U)=aVH9isl7dQS-&HEkyr|xX~b{rkT$-W~2t`9JMXPsOy*DrTKQ(?3|EKp`7yG`#|EcTSuSfVl_1$wH3iJQe3vHgs@vZ~Pmo%Fc z{NI7+jtBpzE`9#Rr2L<~%iFvx%(mnI-urw~m ztL25>ygpyweZDuZ5B^Wr!}0h(HS_=Qe`?le#{a1~9{;D__wqZz|EYIdbFwH}e3$dhf$ydc6G{+6KlM8EC-^^|Zx%>2K&@qg+a=3DT8dOq7;OwIpOmzq~% z{-1iQ{d^Mtr`~z=6zh$7?<#+ZpI>?x+Rqzp7KitoP1}-}&U?c9!DXw0|I_tU?A{w6 z=Fczb&@TADO3Nk(5BS4dQtSV!hmIH<{GWP(t$)b+zv?xsHU$5t-fSMj=KJ{e8Jkk` z|FnIU{rrvjf9mC%cLx8bUTOXW|EHd_aff-JN`Aew*KcDzT<^;`zQQ7Cq zduh>bJ}*c0dKQ+Z{GWQY{k#+Z7q`ui^Il`~{>=M$FSDO7nji9BWX})(r{kwDTVdZX z3yPkq-N_Xq!{?$x7z@PF!#HZPF*f9k&1-x&O#`ih4h5B^Wx z-PWVT|LJhz&SSyV=~p z4gODEI`+Zf|J1w2+#md(di~>f2mhzuF#4Y0|I|AsjSl`#{ZZ+b;Qw^JrTh2cll^+j zPd;zIKF;=*|I_}@+4rB#$MpNT%jPv69kkS&d6W1*?O$fz8ULr=bMjR_Z{FMO{f7V3 zcFu?YQ9d)ca4I3jR-BV(Y8p|Ki5~sdt%&!vCpv9xAu_WG{Lb z*?cAZpI+~!=A+FQdrw)hKKbQM@8pd-YfA8=wc2z{mR#h&}PrYK^g5dwW&A*-X@89OBw-jv;{!d+K>!;)Y^!S@>eP8^adga!VQBtw~S@}AC+3F3!|LO7OELM8UpL)%Pt-=4r{r9ha=#Rf~^`>Ot3zvDXUa}_mKkZ-m?6b*5k6-EA=Z+hfJkaNA z@6q=R4*pO34;f_ZDckzL>g2ZD!}`DKs^gyw{!h<;(7ctw|EV9|SQ7l7dR6hh;Q#dg z*jRcj_&@cMvXuW*FE^ir|5G!s3;(C){fGZkvFr`~w@ zc<_Jf&E{S4e`@(Zwfvtx5A2WsiyQx^-eK#{;{W2t|9RW*hwy)D*1N_3sad}l|EJz% z9uWVh#``h*+w(a=8xO&{GawOF4-IWpSoyQS<LO z{NHs`CI*`Z@xaXpntD!N$+pZbk&^8lJ|d9mj7+Z%;2@EHMuZDbzP(YqO3CEk?eosctDOAq)BWC!@~b2_esI7WFL>g| z2fdrMzb0w;;vsM52`)K$IIaIzcEp?YgNGC!^=7`@Pu3mt&a?S;`Af^aTlcD!6hC|1 zyRFUp!~f~;zYBWR4gOEfJiRZ5Kkxf@>s>#&?*5bB-TO2M{!jaNH{XZ`?;bUi*AM-~?+@z*GyhNTCmR13H~vq@H||j__&;^i zUNwUMQ*%82PscOg4*#ca+r4`5f7+kM|EYr?H2&5@6@pbq=HJ%Xvr{?i)edzzroX;Bn=jXS^|HX~} ziyQl;`-8_@apL!BjsMejt_T08#_Qq#;%3&3n*Ddo|Fbvq|E`|#Orx1_+^&R^wZdgK4J zJ-=PWu>Nn{)jS`Qo4F+V$sFN#CC7bmFoClaWFEDeSVCKBR%=?)+Pw~7f(*0fLJixOrOJDytbN{QZNVmU_rC@I*Pv#t;Q!PO&9CDB)cDhblcyYCaQP7yeHz|EJEX zQ#bfOZ}WHfKQ$hW`G0D>+_67S^v0**|9rc7T>PIJ?~4CZ<7e@I>YS>Tg8x(Ve#8H% z`MfayPtOnki~rO17LDo#|EF%1otpm_H~vp8|EFdiA^tCJ{GS@Xi2sWl|EK1B_&;@v z293h}KV5ILdJTgA({|=B;{Vju&A&1KPmO=X|EcBw)U21x{6C$aX8xbLUfl*^{+~KK zt8wsu>fXJ32mhxYYQAq_n<0L@{GYbV|EZs}{abB*!1teIez0WKeSWgRlWF3cWB-+c{S%o z-`=l9i{SsXe_xw#i2qY}Xqj67SKXtaUGRVEuI*Zf`G0EmXZ>Gw^OjA6|5LYWlkV|4 zwNCeVnf@4L;|EFgCUi_b*&l>-y#(&}e)Ob1kpIZJeZv3B``Ed9@HS^l=e`@?2{!fi}!~dyy zJp7-U`GfdB@6-OT)r#4{|8=r?b@;!yPjqGg|EXCY z^heW9l>c_ntl;D5hvppjzRtYb@g?Qn{q1_MSbNO7r(NHWEl0hXclcb%5pUifS06Z> z){h)Npl9XJ>GaK{GXm5 zjsJ^#)J3J@_%aiKQ;60mLwa?-}v1#!Ta^Qxp{*BQ{(IKe``L~O`yV~R7|MY(EHn@54e{tjg;%5Gz8sCQhiyQx^#>e6R)Vv<} zzqpzI7dQS-&Ff|V?cLd453_0B-EDne{GaykVe>2Tf9lrud0_sZn)`|WQ*%A|KQ-5j z|5Nk)@PF!pyIKeTr|xq{tKk3QZvMd2et+?OzaBFot>?}h?_FS?5C5mvlg9t4nGd+= z@Z;WX?rfbDyf)Iioq4~ne*UO8^8@jJx}MH=r{@2~jsH{kvF-T3xVz^(=;y-|;{S9# zc>@~-|EI2FjsH_Wu=tT=O@)EwQ>#o4-f!8uRl)zM_m>|I{!hKr=568s9x9s@{2%jS znE$87yW#)h#{Zq^w-fxIdatebiT_iV*}OCSpPG4n_&+s%3;(CyZ$1nEr`~JFyTl&X#_yu#%^T(%~A3n#M^^)KF{H(MdcUj`i zdcF8RJ--9y+nE2SX8l?GU);?9Qy(=?ivLry{`jE{-!T+fb*v}L3e`?mR#s8_Ntlb>^pZeOBON0N@ z^&}ng@L~S?*X-OT_`eyGrv(4kZ^Zp!{-1i-*m1%CspqX+75txi&guDoapV8g;|e#K zr)lYr_ms^8eCzDS-t*0m+_tlxH}j@`JE*$%67zldKfQk!nCHO%sfVuF5d5EdgsnG> z|5LMmCH_y%dc8J3@2Kv_V)K1A&(eF5{ruAWnD>UFoxITU0r%e;Gb>TJjV z-w_>u<&C!l|EKfkJvABMbwoXA_LAWL^!)E!yw?7{G)dG;7q4e~8}*?BF9iRm*Ke(@ zpNs!f7ux!{_&@bp^H}&l^(ymH_&@a=o1cdNQ!g@~h5u6@w$CH}PkqSN7smgo588Ud z_&@c&=U)x;|8%|be|o<1f9hSQ*Zr|sJxy(#!V_4-F|4gOEPW%QlF|EYIO z9TWVY`WO4Q2LGq$zwf|-;QzG!1;OkJ);^_&@dDQ?CU77dQS-E&r#M|5NWY4~YL$vwkW5PhDnS z2>++vZr%_7r=D-~jXvA?iuaghtAqd3`=j}yg-NB7xAW9Vi{|!y`%~}Q&9jqdFZ{r} z+o1l*_a6R5-iF_&yx>Fk+?AA9{+0LYrHhl%uYczK%<94IAr?lF#k_I zdf~D#|4+Tf{Q9dqFUnW%D&869|EX8nJSgV>sn?iC!TOEpL&t~`e5so`}PfX zfA;2LGpS^XL=7|Ecd- zx`yuuKmYvIMZy2+@z?J>82q1ly!jjE|EVXNSF`Vve7(PRnP0NsuY2ROuDYp_ccFQx z$Fj1$*V}gc{yEdO{%h9zO}z1c&+N?g-eex_HG;CKv z?f=yHxVO(4oUcD$;oIGh$!&WY$LGJ*Tp#{V&j+uF|BHLT`&0dXY~61@@40DdowIGa z_j>#Nc-2KSyf@hA@dr=N^yc^L-`@L-_kR2RI{q(yJp5nW_&+uN@8AV<{CK+PPiI>G zPp{uLTaOq2r)GU#=KsZQfBx|Euitwx+5hH3?+yD7C13r1VZQ!8V6(0NTlr^;ytml; z_4q$+FR|ZG_{GWP#@s6eEF0U-uSW!W1sWxWS$NGr~NzktR4KHx=XJ* z!T;&+yYYkgKQ(?3|EFeNAO0_H{GYeY6U6_i+nYDU|DEZ2!T-gL|5MBVshRhO|BD;{ z7dQSdZv0=|_&+tz{~xcvlXgGuKKX81Tca@ z2LGqV|CP=8+_%%Kr~byfW2dUg^zmPKvp(^N$A0VG*&ZMNr}NSHzqs*#YL0*5-LKBv ze{1}o?l(RU{}(s@Pp$cXapV8u#{a41|J3+B{9oMoKV2W&@qcmS|J1DijsH`3E2tLy zpBfL${J*%F|EJdczqs*#YR&&s;|1}5YPRG5;>Q1Z=Up58pSo4s)cU`1pMUr)-(U0p zv^}?Z<>3F+SvglG9T%Qcpr0pX*G->i_W$S_RqSs|PCTvuWzK73{#@fbA1K)K*&l-U zYhwNf|EI>&;s4?;{neRnTBlwzP9y2j`@G;%=w1jwf=7A`ns7OF4Mndda}&pGdpv>UF~X>((Z4~s_FCO8dpl6 zCzsh-8S61Ou2M1WeBbr>4JuxfwtxMMd3c$RmtEn?wEeHGkp6hpGv@U*tdjnG8eH@L z{(N#OrhB@~=a=aLGw=U*b=}J8=fCjE@25SV^Dnw4KKPshQ8n z{6BTWhN<;`)vS+;|5G>2O8GxE9`Km?KQ-&q;{Vk6S^S?GAB+D}*Q;JR_&;@>Ybyr- zr^Y|x|J3+K{GXnGw$1Ov|7kn(_?Z8vX8qVM7d~;kc-&v}$CUrFphtFga#_w8Z|3_k z|4;if-w*$%X1!kgpPKbi@qg-eO>@HhKQ-&G;{VjFKfLtu$Gq`@%>VQ4P3i{!r_OC! zFZe%olg26kr*3NdGyhM``mgvu-47c7r)GWPuYNq#o9Dy)KW*>Or&sWQ>br-f{GWQH zc|PXoEUMo!`1m@PE2~8vmzmZe9=n7dQS-jd#QU#f|?{vmP$<|J0rA`QiW6TtD;w z)a_cf3jR;sIk!ddf9ej6&DWX#Q#Wmv6a1e#w|V2V?ep`mKhx_mk2BuR`#Wyl zUvV>^F>XE|wq9EK!hW-Z-@+H#{A%yE`PG8|GjkIBU$4H6ga1>vGT*@bKXpr6UzhoR z>imHz|JSYVv%wP^b?WnTKfbYfun(^P(3|yqN8I*-H@@wA_r9Oj zs~>(Zt#e2I%o`8*%DA6;GhgnG$v;W!zdiG=H;;FDvv>Xan%ePSwt2@JpN9X__0#>f z{@9OaUf*way_wce9(co>^>6Wix?l7i^w9lK<<0##e9sHsEzM{BaOg>I=F8##bbak@o*(o7)WI*B|MT~c`9=Jn zn&*%IiyQwJH~uef{GXcni1@#_@qcPOC;l&P{GS>hivLryelY$|&3r!mpPKo6_&+tT z2mUW^{GS?Mi2qaL5AlC$&HsxV|EJdczqs*#aWnrd7$xs>byIf2mcp0{!cCcr&um&+ zj7BhCe|Ec#rcQp7v?-yPT{?G1lYW|=7d>Q|zX1!hfU)=aVHQo>Zr)EAM z{!fix!vCq6&xZd~?|td*;Q!*r|EckV_`kUEe`>s6zveB|8vm#5csu-`dbjyK{GXcZ z#s8`0|IT#E|EZY=i2qZwzAOGOZv3C_?;*Q>{9oKZe7UA~u^oSTzZ&KI%%#C?!wYu2 z`CjmUwkD>}1Kif|+VZ%2531tL`pJKsT-h7{x3Hw5H_xZVhgW;c|LJ_Y-+VWzbMSJ1 zd>a3!>)B_=%t+^wpg=goS>_&;6Wv9~@9 z{!h)kLHwV$&5LY3?%QK()@#Q9U32!-;3bckU&Q~#jsH_WZ`<*I>gViu{GWQaoge?F z^W!n^srl(KzkX}{U)=aVHS->s|EFdiB=i5&%#XzX#f|?{<5QXcr{?|2{697G`(E$& zTw3G*biG^6f8hVrc)pc`_xt{M-;WQLdES?Rivc8|6f28?9{GZ-$PpsV-{Ga-nHJgI}Q?s5V{!fk9u+O{S zzqzZ|GY`*um_5GDc zy^VVQ@mG0&v{kd7qIoIrJvJ}R_V?a>@}=Pa^!hUo3je2m#(utT^OoA_e2b1Ve{YC4 zUeEUR{qcVIKOKMYxtH-?zW)LHyfFVy=VKn6y*};q{P)`Dk@J?0f{zN7EI`}oUT zzjyK8SAzf3`KHceecN;M)FU2R8~mTTYr&}C|I|I|K7~*9{d?AXn)k1FcJY_L$c;pYFZGyomXA?`1a6$b7r^ zsAuQd=iv=M|G;sRg8$R|{oIC4ga1<}*;Rx8Q`Z~Z*S?=W%2Pi&;*sP(_kQBNdew6K zKL5;n`MPz%|Go9W)G%Lg-IguE|EUYtZx8-Yy{>Ru@PF$0n|1{Mr=GWQdxHN{&phq_ z)U!724Dvgf6|H?aW$=9Ek@PFSlxy^g0-7ox~wlmLeM3p=8_2)18&EMbY z&HB$-<#&6t{`2g)_j+fzAOGujTglKsrQ=q!~ezo zRi9bjyUp8u*kX2CzjE!fXL`?p;Qw@dsd+v8pL&P+Jm&w!jsH{Q0r7uoydd-c)Xeug zcHTmNztH$Uz28`$7yqYbeO~;Znt6Ztzqs*#>ax@RPhEQ2|Eaf}_J5_Q#O|_Q(I}_@eDQ!u-Fung6Gj|BD;{r{}+JfGj6g!zB!dM#4(|J3zcrsn^tb6Q;;=KrZ1x2_QU zU)=aVb(1y~!~8#WgEm!z|5In>rTm||S^l-b|EXKFPx(J}>n=5d|5M`u@qcQ382(Sq zd^h}`xA{Qk|EW9MdbzCstH1Bgv#vAnly5KST_;)4JDjsH{Q`|y8p&-vNge!cR4dj9x6{GYe24~+kd zoB4lnGygAc{GT3=^@Sf_^uBNJ+^c%>$ul2#bAOrtr{nW`rPlvd<2SE;Q1}na79! zQ*%82PtA7xpBlgS$KU*)KR$iSFTV6PtEhi|EbxI z|5LM_^?!AJ`Q~w1|5u&Yp;}n~*W1?j#s9^P|5G#X@5G&d_w%=JUo~kk=pWuq%}Xxn z^H1+wd;a)89nbpV%>RoU{}(s&|Ki5~squsOzqs*#>NcnSU);?9Q)~WT+|2(|H_5FS z{GYmER{A`%oO(Aa_?E!D*fwlYV znZ^g<{|3+hWAK8^2gCoVb8GPa8Cvj%cmEXpAAS%2H{t4Ug8!o{J~7O<dVX0~Uy=5FzN<5RV&?VK$aub&UX%WL z_+jNAr9EENis{>{XWXC6^Ji|)^qiTUc|V%k=VSkCQ;&Z#>L0=T)vaG6_&;^M1~r5K zQ`c?WAoxFZ!)DpR|EU`^X&n5YI;&Z3nE$74)I2BYGJ5jylEeQD-mretMq&P+w&UCI ze`*=pzP(lJ z;Q!P&v}qIk-(@*}5B{&ec`f{(x<#wp-y?bb2)KlQD{hlKfm>c<{?Ecie5uwlc3|5J|`J~TON z%>90SqeiCupRRYp!w-k~f9hT~Zx8>cZj@a=_`kUEe`@AS;{VjlUpz48PVa`ce(yc2 z??`L>pRSMfX<7eQji+P%Uv>Z7R>A+N`!sGI{GXcRng6H9r}2O4Z1a8iKXoJXbof6t zuOI#|Zv3Ab4~PF#K08>>;I~mugCho-gf@FUkvbOekJ}-+iBMSRdfI1?|*z= z+?oClPa1D$J?*%8{o=+8$BiGv|F!G(Z18_P9{x|=sY9J)<3qpl?$@WOtzYQ1}b8pHH z{!fkf!vDpM|BD;{r^c`0|Ki5~sk6+VJ-gr??;P`8HCDXsjrTiL_*Pou|8%_kU)=aV zwfvtt-_{q#|LOko`1n6{ws|xBpBn#&|BD;{r)C}?{x5F)pPJ{7|BD;{r^eUaKkE6k zKKkTy-tvFipY@mVe`>BD|EK2qyI*{)eEo;BgHPl6-+sl>w0^A05pN!UW}U;{tWUf) z=a4s#zqi#vZyx{E4hOt>{7-uB_vZ2cHgKOe^BM7fx;`5Jr^X-R|Ki5~spbFT#{a4D zam@cy^M1hpspbFT#{b2Q|5M}n@PFzq*7(1;@qfC%%;&@Z#f|?{;{ox1apV8g%=5$l zsqu{XKehayn)BiR)cC&N)moRV{*US95?9w&fE$#Ke|LOTK&y)Fo>Q=YsCbwL- z($Cj+aBec<))i?z{odu?_%!^Vj>o6r|Keu;pIZJ;-TKZJ!T-gL|5LX&pVsoqh29Wj-OV3#@g5YqMqE_&@u%U}d))e`{PoEw^DNA2?MW{GWQat>4M~zn5*k)st5YE7)W6y6}H$yb=CSjrYUJDjsH_0Fdv5hi~HMO)$u-I9uEJf`+eLz7yeJZ)qG&nzg73%W+%!8{xOPkqw78~#s?$HV`{jsH{Q3Gsh%-`e*a?=rg|%>UE# zq49red?o%bZv5Y?zf1WY{3HHPjeo@dskvVKpZa-wJ#GG(pO5*6_&=SW#{cPh@qqY0 zHS-klf9k#FGx2}weKxNV|ECU~)cl{C`I7iQHQVujYPRG5)Ma+P_&+t?)%=BD?{1qH zhX2#`Gv5#Y=lk1yK>VM2xA`FapZ3QK;s4YJZGB<`1SSd-Oc{|a*w}1#*QBy{NKGd+s`~7e6(P~w3)&Gsh8V44E&#Z z+}hOozv}V!^D+FN-fv@8tqcB7&Hm;OeEXuJlHmWeeWlG4!T+h3?<}+XS<$a|{^o7L z|LOV6+p<0QKlOsGJMI3Q2w?9`Dv!lY{?LH@xM#;Q!S9`g95Y zPu;h7%KxczZ%Fw+JzoFEhVuFzQQtm#wDp&V)elUZXn%f967`tLv)JB7y)Ukv_Fz0KD5wb#ebzr*GO;{S9#J5Kw*GyA_1{GWPr*~|D)-~XxE z>+z#`I)2Put9XBT-`IX!@P9hKZ{x|q|Ec>oof`a~x@F^W_I*;%kH2ZaD(;W>lMl@a z{!foLcl9Ig+b7-={GYmHN^1RI z_14J`1^=gBH#Rl@PrY?oYW|=4!vn>5R)73GhYtn+r|0|J%P$50r^eqg|4+T&{59+U zst>*Ra`1oZW3Rp*{Ga;7%PIe-E`RYAyT9xGcswEV|Fr$+3oqIC$yV<}r~RL{A2jcW z|5M{v@qg;l7hbmSs{`IUPWwM?-+9{q>3-}wS|0qLddr@D!T+h(+4mRzPd#Dw{NVp| zzM-Q>B{!b)wm)9&99#dRYp1yC#J~1lzKlR!*D}w)1FI}}h z_`m<2nil-uD*HbB+~)tOix#X2{!d*vYiY9ll|TFWht6M-^dIv#??-L@_X}(P%lp0+ z8^ioR9Y56kAoKs!^9qZD|5Hy|xGJpwd*3C~gZ~>jJvIMNJ#kUW|EX8me5F@y{-1hl z(YB<0+wc4Nm)Lwi{GZOh*wzQGHs*)lOvz0?Z+?Ou`l>PT_27AQ%|;EFPZ!C9LPtAI$_`kUEe`>r|%S!F@_4(Lg z9&Yg;I(Tn8ayB;TLjyR7kle!M+C z{!jaB{a-cf4Kx2weZYP_yY7w~^7ZTSLHqsN%|~y{*Pnmze=X+TGAiO@5BG8_u9WV z!T;&`>@}ZRvVFKeUmE|X=U=}6MDTxcGyhM`d`jm3sY~s8@qcmS|J2N{oU(nqKR*8N z&Zj1L@3HxJ_&;6W+SC3|y}@2@*2Y!y`1n6Ho)P<{=gax|@3`@QYWY7k^Ih?O>f+P> zFK+ywdY8@1!~dyE?Ds?XKQ$f?|EI?D;s4aE-^={Jxbc5#`MVllK>VNHFEsv7y>(a0|EY_2r~IF~WLL`n#f|?{AGBZpnE$8VzkPR@|EDgp`F_m* zyR*%d;Qwgm|EYJF2gLtr{}S``_&;^g_MO51skdxP&Hqzx+`1#o|BKt!Q}N^1ZrT$3 zpSG`9w?6sb)$9H7SKE5PCI36qt86>|Px}|HSr`1Dde!ok!T;&{moA*2e0yk9{+-h% z=O5`YwBYue2PF>|ZuV}MS10(tHVbD5|5v+C%KxeB=A`_eI;;6r!T+fnE7_LH(v11)sA>KZCfc>ebrI# z+`J0G|LJ@!+E)(q|I~OP=Krai*}OpfpBle}|BHL|`_K9L@lIXeeBK*RcJ#Ive1GQ8 z;s10z^Xl+_-ZpO#|EFes;`>^>?A^xJ-+immD{0-P=BwWLzfBciOY2K6eck)|?)8$f z-+RORx~_GS&%Qm=-Fwtd`hN4KZ>JCa-;cfVbTvPDE3NT=x?Z+3|1WO*pBlf1|5JDA zom&4_&HBOry7Ikz{rzbdTaOt3r@q1F72^N2KaKxW;}7wFYWyMV|EhUD_&;^mZZ(7d zQ{(x*x%p$?PUHWyo!1Nhr*7T#+Tj1<#{a3?bgLHT|LOYic=*4#@qcPOU)LY}#*e3W zpYw%xk51PH|EK+X+4|Pg{`gzpF8`;;m;Z|!{}(s@PtE%m{}(s@PmLdB{olCpf9lp< zt_l86-KJ}mu>P-F{!iC0|EKOyP$l_lLQ=FR*){GZN8a zX!G(q|I52&hbqaCHvdlRpEUl~8y{Fu_dnivzv3$YO>6w0u9xljzqncdSIzuD{GXb6 zfXx3>w`g5C!T+gqT2%@DPhGRoW%jopXXg2}t(NYc+Eq{YPMPbiHmjaKudH6pD#8B^ ztMsSf|LWJO8vLIcABg``vmPt{@1k~p4*su=&5OhT#f|^_VA40K^?|RxD)_&mm;Ms` zU&|}62>wsoD_?bK@PBH&7XD9Nw_>^<%k*a7)s?HHd$?<=rhB>Xnm6~I+cW0jeV6ac z^k@|-rN3U8*PH3fzU%zgR!YBLnVv3lK40efGW)xpf9CaNddSTAe+?_7Uti|qWp?KM z%Jg}e{t-_ae?IEeOn<#IJ9Gc~HPSsTzBN8y(~Qp#^ZerNjp|kp{%=OZe+B>7$h;r( z|I|5Ib%Os><`R!T+gQPZj^SWaPht|HA{a{;#$(FAx70 zH~vrEEH~x<)XkeU2=o8c_#*tD8XxqtVN|0DQ6d>8&tjiwq5Xl>JIJlg8x%@YnvDRpE|#3v*7>q_{>Mc z|EZZ5hyPP|Z{0HZKONtpY2)Dk)WLJT`G{Xni`<;x|MdKs7l;3gyZ7j!e*R8Pnwi@PBH&D*jK+{6_qr8jp7A zbA!F{XGcH3J*^+S=uEfIX_{P-bDM83$ZnFH76`rZ;Psukd60Kb zPEIoLwHv*8{Az!?!JBz|UtM*knNNxT)A^ZCiT_jM^_c&s=JSjH^R~|u{!h((Nc^8V z%jQSo|I|%v|M>glyS!i9-1PlhHLja>eDkdI_3B&MWbk;|&FTmLXXYgM zzoxCSg8x&u>6sn;pSr_<=E47|<^R;o1H}KSyO{UG|LO5MoA<;2saY=={}(s@Pn~l^ zcJO~{=I`PE)bf97`9C#&3;!24{!fj^!vDpM|5M}7@PBdR|J3+1{9oMoKXnJ2&&T{f zHNFi0r{?jQ{}(s@Pxp`Kga3;g{}(s@FK+ywn(M>=#eJ{&KXvCpxxxRbna7C#iyQx^ zWG7{ z7dQS-&3ekL{~I^{FK+x_-1t8={_e6@xBB(r@9=+me)v25pPKoE_&+trxxDuj-}+zMXEibG|pnyvfe%{PC#Q$l3`9C%D5b=L%yy!pwJHwBse|W)}W}YJc zPy5sOKQ;3S`_-K4$J6&Un&QoT#PQ81d*d+|Cn-QMOo;{Wt~JKobO!T)*R-P-;=Z2!*1plWlv-R8XfBzUVH8ub5#n*!WQe`@)^xbc5#=Fj2(;>Q1}OW$}W_`kUEf9l=llkk6WT{*p8dz&P%o|Ve>(n{dA~K6)lTbz4mG`59~b|p*Mr9YwX*py_&@v} z{!fkH8~3woyboKiKBsb8La#4{x5F) zpPG4j_`kUEe`@C6;s4akzr+8j*^d8H2Ty7KFK+ywo)6pcf9i7ckNCg1@qbUeH!aNX zV*VulFK+yw`iPyc|9ijp<7xb#&WESN|HX~})Aix|@PFz(Hh&TSr)GX1{x5F)pBg{Q z{J*&If9k`h{hyl88~#tN`G0Za|8%{0Km1?Z_&@DmX6r%X|J0@S`N#kH{x)w6|EK2j zkN;E4|HX~}JJWC4`*pRSe}{RKYHO@PB&zz2=?pe`FWK2mhz{%N-NO+q|^f z{QdLfGqcU3T<^VLZ6WjAyl30|3!BH|J=cCdhX2#~#;jQ%{GWPK(RTckKmKa-3+AKJ z+SUj6Ubka!g8$R?uPoZd=hvU_;;p;zxZX>OcL)Ec=fBM6C*l9pt9PgTpZBhm|5LB9 z`-}h6!!GJl`&Fejbkh({?-v{!fjs#Q&*Bn$N`lsps40!_M!0#6F++ zKfON=+vgMir)EAI^Z(TRdT!6xk6&tD0{^G;udwwa@qg;F6R(?x`?>d?=icD@y?2+U z{GaxpF>_t;f9jEUtPK87eM5&QdA@n-&bc#!|I_sqWKRzMPu-}=*x>)Pf3N<_xj%mV z$opmn|EKM!ur4JXSeLai{|O|Kem3EdFz4Rg;U4b_wy~@+op{+&waP| zmPwCs|NZf|PJATzKb?Q==zH)PzJ1Nq(P93dw!gWrDEL41;lqc+`oHRvCr{e_n(fE$ zvH6ksKi!W*_U|$9f9iuTy%PMN`moLWGe7Oeh&eN%_F_y z`%juXpZBNtLqkUd|EI^RRs8^`nbdCNpPUkgwzM z)t}vck@ses|A+t6cGh?ARQQ8@T@T;SJMiC8@qg-KTR(TgqwVtbd7#ZVdvCVi z-{AkWoyPyEi*24A{!h(%!1zBkK5)mw-Ml$J{!iQSi}*h^>+9nG)SSQivA$`I|I_vj z<{6p)r`}?I&%ST-_5F)4v_GHb>(4j)?ELsY^)9;~_&+uC0k7Y2bH4ukw8!?x|HX~} zQ!`%>{}(s@PtE!9e{tjg)Etlhi`)MFoi{!Z|L50djsMg0V>|Qz;_iQVg!e)7b=h+s z^FCz04*#e7#r5I;;>Q1}@pPNsAM3}nKmJdT$GkrLpPG4o_&+tTFZ2K6#{a2z+WbA% za@F&r@qg;w=4G*RYUTm*-|C&__n7||_l<3*`~AcJO{+O0t@m9#(;NTy**9le{!iz_ z*Wv%vctHH0n*H&AYCItRPrc22FZ2J@JIqJo|Ge$+cKbQ*D=eGw*Ly&1K%Z&G*&1c)7RM|JCs{ z{!hKxydVBgkGEy_p5Xt~JM7>4{N;<)zI~hhev|os+Frahwf=A1_&@dL)BaCgc-sHz z@mcQ||EFHNrZAav=Z5_Kd#8kXep}4@P3X4Kd$Y~|8=Aezd-Z~p|9k7dSo!S6L}dR4OK z`u*N)@7D8xcUCj=d<6&3bc>Y#)A2d2QvOdZ|EHG!Q)lH>PP%>nn4hn)%@6z2S>X4_|5Nw1^Wp#E#{a2V&lvxwW_}_5?@XuspSo-Bx(WVI&HO$5 zpBfK{|5M}h@PBbL|4)q%#Q*8Rg-GhyPRK34iqJgWgT5R!V-m_91W9cg6pm%=v5Zf6VWzwf+%rwln`v+nK+{ z{J*&If9mh@eVIP3e#UyWne+5A*X!l^#oi*bGw)YsXFmRSb-fHPm^qIxvoqJr&GdAc z_b1cOWp?KN-_@Dx3pc84pP$H|X0ETCb#3*u?YuwY{WG7>cRl`hZO`){}iZ^VRTw;~V`a<^Rkt;s3Nh^X>3|apV8g%s*rPpBm4^ z{J*&Ie{tjg)CEl&1plXQms2-s{ONe#&husdpSCw>&>;9fb(?Ive)E67TK2Et|Jvp> z3I0!wH^l#`@mcskHS^w>{}(sw|LXkAXUl6e%DZvHM#=k^J?8sYw)uyfT0ZJs-5wAB zr{nRN%>UE*nRmzhKehayn*CY-SI6VQ)(v>XoBNIb)AoYK*~vNg5ApNmRI8f2Ir|~+ zdN$7x|EK*2J@ioW?FDCg$jFgNan^&royPxZ|8b9}{Ga;XJMIkrPkq7QTY~>nC-(gC ze`?m7#{a4DbIku!S1>Qg{6BSN^N;vHb%Wfj;Q!RjyTt#g<^STw|Ecq{8VCQU#slL2 z)U0Rw$D42V`$gmb^m^bC@qg-uO`8P&r{?{H|5LLbF#b<{oq5m$?XLIkW1euz-2=Vx zp8aNC=gsR~sbqjR{`NQT_D^g4pRQl)|Ee?B|HY5S-!C0=)7S6K^nsmPw@BNc`I_!tJ#W^t zz46q~yqTxByqERTJ!(ZJU;$UjjzK0 zsqtU3GcEt8 z{qbmho+$O>dH>uqX}32XZtSdG-u>)+^A?q)_2$((y?H&3Y~GR9Zn{#$OY3h> z6no?Q@PE2Kt^ccTY3uENG;NDNzZN$)OCFuK*&FY7{)$cB_^>q_HhK@R{h9x#^U43I z<^STw|EY6qy;=O9y0Oip!~dySj~4$IH~vrWr|#wjJNH=S+k2j#|EK-&eE2^#9t-~$ z_o_#hr8WLf+gYC${}(s@Pc8o!_XVpK`gZ2W;s3Oq#{a2VzqaT8d1-y;@wwguZGYR> zdw|Wavp?&3Gp`Q+r}N?IY!!k9`}JREdgBZ6e>%SZ?Ja`;Q?q}q%clEw zx=p2N-mFKA|I_~Rf9h7|CGmgimgXt(e`?NGWd1L1{GXcV!~DOv@qcmS|J3+K{GXb~ z$N$BR|5I~*{GXcph5u7CpYWV6kEC_ZpohJi-`ytoKkeV_uGYc-se9j=9sHlVN&Cx# z|I_!$1=rOG{*S+d$NxQ0Iw|>J$aUp)22Kl}Z(r%|WcHU3ZcgYEdgxGPVu<9*Ps|JeRoX^sE$>#_Uy$%yJ{ zeSNKJ<$8UXUx)uIx@daJ16t$%)Q8Lm;{W14-ngPS{tf@9?RY}`pSPV4{}(s@PtAJ0 z(@y@-uZMYzMSuE%Hy#oHr~T=#`dsAOIsOMvUf|98zW6`wk3Yo!sY}hfG5=4Ef5ZQs zcw&0+jJ)6Qe`@9{;{VjlSH%C-eSW(8zf<-8>f5;=7f<}tnYR7$e>$G`tN9o29oAJ} z`TUr!XQ%Ct|5JziVg4^}{GXclH~vq}`y2mvrr!$wPkq4VVdDSP$Ia6+|4&_R^ZM|A z>OI!X|BL(5ZO6R%Jlt^Z;k3s8Y5#qv=l`kq*!sIQFW=?ccbWft@R99ljsMgA+V$e= zVg8?*d4u>r^){O)ivQF3ng56XQ_KIU<^R+NY&|*rpZeg5lfnO~H`)4g_&@bh`}vr8 zGVcZEAMk(Le(NKng8x(BG3b`WeqQU_`*!Vt|MBbZ*RLP*!Mw+g9UJ_g-d{teJQMt% z`pG4$g8x&q9x(n-z1G%Ww4d+$`KH^?<7|CX?>ROP1plY|w{UxD@PF$0#k=hOR`=~o z&EMhww0()q3&j8F`K>VThyPO-+RrbU|EFG4b|Cmab)yr*tHG6-0 zui1AnvG<$z>b(be|9BUc>^09^=)HDFS@3^4-)j5$C;m^pV8fQ+|I|;fS`p^|srwHd z68xXKPycSg|EXKHX%hUOcaL^>rX#vP4^K$>KlQY!)A_s~Rxezz$o@QQf1*A8eN(t_ z1>4)GU$CF&n@?=3^W!P(`Fd}$`(^&ndz1MHdp+7||FyP0oULE%J=&5@YjsNqu`GNR9^)~zb$G|gZMx7UYqBI z|5LMG=zV|L@6CFk=F7dA|Aqh4{`(Fc3I0#L=d}M*Z`f5D{GWQNeg5!&>WPmJ3;s{n zTifOtF#k_ovC$>L|EY&QeOK^*>M4^Z1^=gBvuYLp9@USZW8S#*oG;S4?y#@&+Bdc} zE6oS4pR+Ler1IC^%cnlW{9xaI>{FBZ_XXZhOqdk>pN=0gVMg-&JOAKa5@PF!i=FAEHPkryA<-z}{AGLXf%>PqwUQ-nOpL*x!UG{!&=-0p2etlf@W|nuc z`6v7S@m^t`ug{n!-YX9swa-JYccJ;J3#v8u-e6wNem(bQ-rw^txAJB^-D+#vc+3Ck z{>uNUH`;u_mgfKB#{a41|Ki5~shO{b|5N|}D7zErs>*Z!<6G^lx7AulK#)Q1}H`(@zFK+Ozw%23-yqo=cH`(`B{GXn0jrl(OpBgWR z|5GzR@QBOr^2QJ1|8#%3Klndydq3j;^mvYk|5MBV#f|?{Z?VVY|KeWI?_t0Gy84X& z)BUgAvOD-cb)9)R{GXcZ$Ihwof7~nGFMJ;UPtCuN!2hZ7jQBq_+wp(u4ff~Jqu-h4 zU1NV<9dcm0Hy#oHr}J|@{GXcnefU3hb#2D~#f|?{SJ}Ki{GZM*|EJzrw=4KR^$t58 z{!d+Df1bnt#m)M^apV8=^MNw^_cZuF^(I^Y7yqZOwm%Q!|J3q->UGWQ|EgEopRe(M zI^SBmAI$$#*OpZU|EI1oFOC0GvtImJJ6C#F+dM%0pSH{Ysn^)NzfJR27nd)4B>29y z_Wg6keQUf~j~@T0?Hd-#eQFK+yw8Xt%MQ{&_Ce`@C4;s4a~e`nqYQA3af9heyZ4%c1)%%ZT{a^K| z#jS(?)BZI6PmSlp|HWNt{!iVv=%nEP)VTxgcz-#>xA(Srr6X@S)VrH~{!RK_OP|^$ zy<9RBa%EuRJth~L8hsqu06KQ-(5;{VjW%?INDYTo@k z_&@f?|HX~}Q!`KS-EZGoa{2tv!aPB`{x>b1?d`HV+uLRPzwGr|yR=Vxzmm4?_-WFE z`d?9-v~T;e^JTA3oZZ>}Eqfm0(38^VAKWTEpD}yA-)uklW%Kv4ecb^ zVtRXaXFvb!`;&b=|G&>C+jDmBoW7rUJiWI3f7Y{(yIY5jsqWq}?ft&Y4>CV9J|5@C z|Gl~RUzz!TojM2qr|#9|l;Ho=%tK@TpPKbK@qcROr!oIeos-)m%>Rq~$QK_@Z9n20 zllNZr{=b6<)cil~k1xXisqsYkKQ;61CYt|KGY=5|r)FLt{!d+;+co$OuXw2mhyL-WmSS+vXGE|Keu-Uo}3D z^?%j)J^Y`V`E~d|b;s`Ag8$R?<#g*F{GYbx_UIY>pPKoGuiN}THR~PY|MYnIKQ;a@ z@6?-o|5I~wg8$Rw^SX2j{!iU)Kz_2c?t0(<(wlA${!ho7V7?Fk7x%y0U+eqNyk|o4 z{D^D3@4V#7;QzFL-dSUV|5JabN0;FL)U5xE|5M}j@PBIVFaA%>>xchS<5!vgr{?{O z|5LL+^Z(+0;&&JM_2NU%|8`3k^vp>*_PfxxGw%=or~9S(e`?MDQ}^rFFZe$-^B3`d z>LI!Pg8x%9{}2DC9^LH!)ObVupPKXG|J1x6D)x=r+w{fXi)StRc?mu5gRw1b&!72! zdj7mW;?I+UytMzr8^+u7diP6pVZZ!TGhZ{_pZS_`_b$!&zoS>o4j!=Y@Vo^7=RLMZ z@PF#O@j1c&*$k_c|BD;{r)GWMe@uTj)%ZVcm;Y1C|EbxI|5FbQ1}Szi|a7dQS-E&mrc{!cy9o)7*{eVX}4 z{GXcndicM%@qg;x_W1KEo^3Ky6#O1u@|N0z-kg8Ru4laQhfAJ1;C=epeS-hf`ue}24X|EI?P{p7n_e1GQG;s10! z_&xle8gGgJQ{y}Fe{tjg)bf9EC|LOVA z_&+u82mGIU*!da%r#}7MjQ`X1j5()onE$87KkonT8oyo||EKNTFZ`dH`F;35b>Ss_ zg8x%9Kd#rQ%Y8fZ{qTRCJq&nZxF%8vm!qvmPz}Pc8qa=J@!(xb45a$6Yok_&;qw-R9xp z|J3+3{GS@XhX0Ej|EI>={j+AOU+*aMa&vb+o@)DDi#NyH^TMO4KJ$%7QvJK1Px0pX zlYTeZd!XI_qyO@7sw@BTkaypU``X`!TblKSE89%+?ZYnWZ-3vO;Egv-hTfm*Zs*E4JFM}4apV8I%`;V34^B1y zPv^sPefVF+zMc7jvx*0KZ?VVY|8zVW|EDgu#{cPfWzW76{GYn!U}pZGy4Lo`|LO4@ z5C5me8{+@e%qztI#f|?{G9>}OYnc{El*|U|EcS3Jz(blshMYn z|5G#X%+?3nqxTc*&)I)_ueaYH+WZpl`Rg|X|EI@aaO17P|EWvQKR5V4b>9)g@jrgP z)m-zwE0Ztxx62mA+!wqy?V#?;Qw^IHQTlY{}(s@PtETu@qckM z|4+?&X81q#@-=1LfA57$mj(Z)?N?lLE%(Q_=bSf==j(l3$pHLagZA%U+K2bE_rwK{ zaD4BD3udtYZtef%{Au?0*921xAb~k*$|EE6i%n!}i&GYT74~zfP_H9ocz;AhTe*B-d zSD079|EX*CX8fPJ&ej9Q|Eag_d^-3)_4JvGga1?Ca{c1q|I~v9To?SGdTfWu!T+g8 zw3&ckEmF5S>ZaiT)P=pL2mhxYaqgtx|J3(BR>Rj%k?!B3MPNQV3!RzbCUov}A@PFFA@QDZb{P69wo}3c=pRTWZOUD1HYj^Aj z{!iWX%rkbsX87}G-riMPXL&czcP!HPuU*eQZ{BL5Z>RBpIv)GyY+BK>zj;6WpB}%- zK0on)apV8gRgKRC|EJ^C?teb`KlPS92h2Ow`}t`6pSClf75}H!{6F=!osGf&sdt&@ z8N28i-@j^0#{X&ioJ9+HfBJUT?`8d8U2i-4{SW?6opk+9@PF#@4__DjpL*Kkj|cy! zUb}jA@PFzjR;~>GPd&@F<=Ff9f^%`GWt`^(|eWng6F=Wb>Wyf9fagcs9SYSg*&dWy^#AQ_o($!rqU^ z`u4?7%u4d!KF)i_gAeod?)}gM6N3NK@vpe}lHmW;r;a^4d17)~KYz*TX9fSK?cJ`s zG5A0Am}yT0|EIp`iK)T=sVA>n75txi&8qdm|EVi0s)PU2^O*1Q=0PtE$i_&+t?4F9Lbmofh@Zsz}~YnuI^8qbFRQ&*W6 zWB#9-d2jeXb%l8}{9oMoKlPd|4Z;7Z%WXY-`+iic&pVFy&e3DNIUoK{+xh;7|5H~r z`#&}74degx=L;JDr^fH$|I|D`*8f#AFA)EyzrW!H@qg-#HgA{tf9fjpmiRw4^XKq? zYVJ4wFK+x_-1xt^@qcRhKV2WbAOEN4%X~-tpBkTs|BD;{r{?+M|8)Pk9}k-U^XC5B z`oC)C`xV?j!JFsH{68I!>%;$f+x@}+#f|^d^=tm0y2gAV^Z(S$=fnTSjsH`#zAiS* z?~gVAt**4M5B#56{!cCcr;J0pefU3hrTIMkpZ@+&z2sW;f?KmJc$ZjJv_SJ?je zKlOV1esD(b)qebS&HiuUF335Px)T(f9itV?L-BuV)(<`H!@b_j7yHYv_IYdmpZ2H2`oGQRWBwWQ|8#%o zWxEde54|?|aZ)YQFE|(_Z#w{oAEQucUf--&a$O|I_jCa?4J7-M7=jzV~Bqj)(u# z&rk7l_&+rs5dWv+$^WT`+5N%)spbFT#{a1~KmJe6`SE{hd?fx)jgQ3tsquFBKQ;FU z|EK2qmQ4AjKRr^kf`ZwOZK0_~j-+P#OK<5AH_`II@KQ(?7|EI=_ z;{VimK>VK?f5-a2apV8g_&(;J0pd(8h+^M1zvsq=@n3;s{d{6G9( z-1t8=evkQoYJ48^|I~Ox{9oMoKlKp%dd2^#2b<@`|EckW_&>G$pZZjr_lN(}`;W%| zsY}cYGyhNf)A+x*@qg;#K_@2oKQ-%*GygAc{GXcnrT9N}&%9%T|5N98ZzifV7_Vdr4|Cc?lE_?o7 z_PoCA&VGFM`3AO5zg~mdq}Q*__Hx;s{rJLGX%E`<`1JAqqq98dm))=b*q(L#?D>G% z&o}$}v;AL>lhW6p?E$mr8FuWL_Iq8rq}RXfVg4?DzhwKqPFeH)+S~i_|Jpy>3wG#` zo)^gV%xm+=-n!)9!LxPm+$FiUc8Yh;Q@SRXmbP@~Ufq+@Hz)gcy6X)sjR!pPpAY+X zJRtM`CXV|e_`=|+%>Sv`&ip?$KFQ{<_~TjMw$-)=y@%!XOWuEbk~ba=|EI?nG&63er0m)Ti5yVAGrM5 z;Qw^J6Rx-}!T)LhyRW=5_&@c|I_s{4-)^Umj6?8 z|M7on?mzSY)EuAre`=1;`oHR;+`hs8sR#A$6a1f=uLt~}n&;2_KQ;3^J54xa@7SsT z2K|Ecke#S5F7esj}o_jx~F zwI|j1KkbjN#Q(*O|MNDF$NIl&{2Knxk8j)Ye`>bl|I~Oi{9oMoKlQ0L|B(5AYOaU* ze{tjg)a-vt>pJhjHXjfF=htW3m*i|tZSPf3lWP2*_Lu*Q`=fKJTJ|^ZhyU~Q+w;T! zshQu0|5G!M5C5m;`Q!iM#{b2Q|BIXXe{uJ%UYqLYwyjC^rF&PW`qSrDc{87I+G{Jl znNNuS)APmqG5=4^da|QFTIT!X*WUY|rQXc$J1l4oRezXH?_b0-O(Fw zX#bWh)iyicACG4%oHxT8zxK+q>E3v_Ys;pk8vm#3#lPYI;>Q1}S??GBr^f5y|Ki5~ zsquT0%>StiFUkx4PhDX1Ch>o2`MH7|HVD?^7g*}2HU=AUOVqfTW=Qsr~R4lhyOci{^P-S?lf?a%zbN8Wurc$Qt}(eQt2`9C%D`|y8i=G)=_bbNds{x9wywmrfdUy1+IcKJW` zM)Q6-8^7k;>+JaBfASUY+GhW!^W*dIeQ0yvS@1Xf9#L{ z({|=P;{Vi~5C5m$Y_FerpFKK1^8oRGapV8gjkX>Cr*5$K8~#tN`G0E7|5Nk+Wc^P`0k$N#CTZJrj*|7evdh6bU_Wqme+iUh` z{GYbhKArJ@dOy|Ld>Z@R-X3*@{k{?Zr(R;e?`Qs>9)H1gHwXWxKJVPKg8x(Zw|VX6 ze|-PK0eyr2)AlPbyC}i`>HYG9TW$~jPrcOUTj2lHlNKxs{!cx-ygK+l9dB{vrr`h7 z%)`U~shQt||BD;{r(SOB{o?=BD>l?7S1mZI<@wusz4rC!&HNwypY9LyX7GP%*4xAX zsaMx2JO&skr^{rBy2 z7B3C{PutJA$gGs54vCs*W*29^?Z)+J*R?sgTLRc{iiHl zVt;>467>U%ma)B1z1n<(J$|5iL$m)=Z`yZ&{eAn|{Rg{!2CbGf1WlUi~m#O$MAn@JU{+Vz0Kxl;{W2t|EX)t-!lJCT^r^P{=s|y z&dmHjZQr-!06x1&*IQTCh%fc7T(LFyKkZ-nXm#*^>X|pp!LR!MS6wlO_qX?j=ReN< z@t$?XRK7mEe_X-mTaov{hG&!NX+w+j{(QmKGw%56XzvDlJysllmiG>O{mhqmH|}Xj zW>#F`y=(VQ?!O;@)9!7-|LOTw?W_;}PrYH+c0ONx|C+sxyq~?d?%5OkpPqkXv;R}e z|HaMvzxw`#$HxC@`*!<0#{a3=&icP`+xx+Lhs}4!|LJ%;?fqf%TYWq8SDF8($K%17 z|EI=Vn-BNr!@NNI{^8B%GyYHe^ZvKb1K+;QJh6R$^4_s$FW$mL+{!foD+rB#~+Lsio zSK2(Q6BixoJ$d1Z!B=|o)eyQCr=Krbdwrx*lpLck% zuBXa{ax z2mhyjY|gCY-6 z>$U%+vp+w)3iJQ8z1-FV{%NOfe!hB}Kg;|-UEfmkHuyg^>-FOQyzTvo|5KOk%J@I^ z`W+3y|EbGuePH{%D%R%%9_yamd~dwgIbSLC-eisc)8p}e_&@bdJKg}B|EJy&Jndj_ zj)(u#c03&ZPtANf{GXcnbfwEi`1!Zne7JVEj`D8UmGOVNe*D^@>rOA$=PUi*UE{p* zbbE)7_r~|x=dCyE3Fi+yyI6n!q8A;0t~dVev!9)pYUclGe~yR$Q*%E2pSL|f{GWRB z&b`6^dE56_{GXaX-{Ak$%v;3&#f|?{Z?O4%_&+tCp80>eA1mzq_&?pR)pq~zf9j3) zc>JGwgIy2)PmK@7|LOIqZuWm_USH<_X@5Lp-N_I5`8U|>J^Pah-aLNiClmd8x&C7g zJecaj=O6N}s&7ng*z&OVM)ROcmQMDrviHYxlc#uB+UFH(!RmfgS>ylItgnk5Yw67V zzqpzIr>?NaGyhLrZk~_%e`?MDi~El18NMC=XJ+3U|M%*InckZ=Z%@9sdRD6Oe>z@8 z&9>nG)EjJn{GYnawzK}Py26gn{6Dq)pL)G{KK!40qy707|EIstS8dApKXt7gpZS04 z&9?oFnTv|`^9B6hsdp{*UbnF}>3z`>?=qX$hyT;#%kA$Izph;7jpv&;cX_G@-?zeh zeMM&dUtRAyn+Ldh#HyC<&Hhivm;clCvHmaf|J2KtX6FB?E0$&apL(@@zhM1e_3|0h zg8ysR_Oamq&K*`7{GYnVDTfFDr=NHA>2*}{mx)`7NBuM7{RZ|uCip*fQUBwD|5I!I z-?*9o7dP|&;>Q1ZH~YW3CuXJmpSq)+pZR~<|C9md`E355x~t6tWc^3-q+@PFE#Go(%Mf9f7XZ9QW1 zf9jsY+6MopmjBc72H1Q-{GWP+T@U^*Zv3Abe}(^3mzLW4y5|4X__E>V|8%~vo~-#l zHJ%Lr7dQS-ji3H&g+Aja6W`EZI)&BIF@;AL%KNtU}?WYcJ7v}$|@qYL}HP^@d zKQ;FY|EKO{UJ(DM&K=n?8Mfmczka;lN7e6okFf1a*Z$l)_`JoxNcBfE-}64({2u;K z&u_f>Jp7-!)EfV%W<6j0pL)#DjQ>-QF7257Y20spJC9#7>;vy1<~@fF{GE5-;q8+@ z_5QtgpJ68_OFI9-oA*a)>;F#mpN{&YH~w$&*FW?gHteKi=)YPTKZyU+{i7HE?jzqH ze_HzUkG+cqXZ)Y`XFL8+&Gyp0pZNaxygzOI)El3-c;jc@T>p^OpL-9tug4D;{MDQF zcNdvO)BU4MAO4#+zVO4l|DNi_H~%BmtpBU)D=cXp*8f#A-w*$%&M!JK_&@ak^L_Zg zxbc5#=8fY2)O_CH|J0iQr|vP}*x>)v1wBp*{!g9PHSN8!{a^p~X+L+`$!WioJ&%t0 zem^_>hLRnB_@ChO`gLfV)cvxhPc{Ga_>LQW`=GYWkG#2La>3t&|6_mrpPG4U%>Pr5 zXx}lc{~I^!|EjaSRhM?@d2avV?T$~chx{L2Ez7(0I=;32G-=<1`d@CVw&~7Vzc$;i zWp_^N^!&x_d3f3WE_;35?EQ02NY9t+d0hJS9e!Ne4-P#heg0m@rnmPzChhAwAAfY} z`F1%Wy?%7h@{Q%+8M zzwFL_|9zPs#1qal|JQ2U7s3B=J@~)4@qcRO%i;gj%$LLedE0uj_&+tC>hoDGjeq*t z$t~TdXRl=c)`xt5w&VZw_=0{J|EC__KR@_Cby1I;q%N7{`{Uo3|9AA1q~wbC-z&i{ z;s4^Eyk~+pUJ(DM?f5+WpL(Fp>%;%4nO}zg)APtAJ4 z_&+u0!~eyN|5I~6@qg-^9;XEVr|Xmd({>vF=iR+$nEw|y{!fiZ!~dySuNeRLovZ&H z{2$kk|5I~({GYma&y4@m<1fAF>fry>ciO+#?DMZ{{rESXeNOOy+J4ixp~3&DFDSBk zU(2rX``*C`Sv|N_&>Gg|EYO>@qaoV9uEJf#tY*A)Oa@hpPG4r_&+tT5B^Wh z`n7cjFZAbMJa9m=;=>EPdA*qbr~P~O>>2!@n)QkCf9l>jeS-f}_qBO{_&@caoPNRo z#m)M^YTj>u>v)!*pMHPzncnzT{NH`~{|f#OUyA=z^L+7tdOhj*^NIDM1n?6XTF{JeQW>xcB*&& z{iojez#ko!Zsz~#c$)tgH}n70JRbiSH~vq}`o#FZxbc5#d?5ZW?)m4u;@5}AtGx7O zZ{`i+|Kk1ee{tjg)WeuxIQa#C{7{>hc+3;edvpExKiyv%{}(s@FK+ywTK+F?`}=2; z8KvO!*nZ}y(?5&swW_g3!l=g;}^ zfARG#Xx#1lv%UMlU8%3DcO`}siAXMdg@{(T`n&whU3&HO$5pY|VhUM@d>@a-Jm z{(WMq?dKQX93TIu$J4i%|BL&u&b6t=|7kndga3>Bz>rPe_`D0pRHqvM=lh#i!vDpM z|5MBVspbFF_(c4ln(M*;dE4>ve`?l0#{a1~9{w+G{9oMoKQ+$>|EFesU;LkXxOu;} z@2qHP^Jm-MU+&F3HvFIVXT8}`4=wfAgL!(ZrZ4fv&oTc``_uS8HS6Ev|Ki5~sYlrQ zvG~8Zng8c)$7BAVn)7!UH!s!rKW*oF?Z3T?E-6gx?`Gb`mkvzq-)?!czs-L4#-HK; zbUYgWr!KvqZ}5NWAs6HY|EDg!a6p*wr9zJ7V| ze=qNQJovu@Pwfu=PhH-)C%No_aZPuh@p$lR8=7psz^2o^H}82md4KAdChfn|e!q#XaWTl9uh}m+*hS-TIle1O56~ulKh0Py25$ z--Q3;cMAAL8vm!3|BD;{r^i>BhhqMpn)P1se`@>}^Z(TNDg2-ACw>n9r)C};{!jbk z_3(dcJRkl~``4J4!~d!AX!t+vzt+b?K*bB~@M@1GUNzwV9C!~bdjEjG^& z|EI3D^*Hf=>dp4`f&Yse{}(s@Prc>fOTquCSuYs>r`}-S+n@1&apV8g@_*{hwqE9|OQ!qwI$KW<|EK%Q?@RH2>XkMR z3IC_ZUvt;p!T+hppOcyYr|x0@-pTxr@1Nx52LGq+U9Y|@_&>d$uD<1#;Q!Rq=g-G; z`QxYA{5V^m)O$&Jm|x~C|EJ?Gt=f!#^6m3CZcbjjsf$0Kd6hMZtq<Szs!8Wh@9VfuQGpt|I_|7{!iDt zde^St|J2L2ZpGXA_6_wJ|EKL`wHg1{(!p!`@fWS#X#Vhe?`cmi!*h9;j2h4V@#81M zih}>s@xC&a`HjDCP@i?#C0vj9qIGL{eZ4CyE7^ay_FuYmsr~&mNz}J4SN;B=(f0SQdFtul|Fj)Hg8x%5-p2hLuy&szz zp9}s^{ZzC6Q#T%XHu%4|@qg-_Pd^>}U)=WoYuUcHDVdaayZ81zjpk+V@vb)ChX2#` z*V(_X!2hXh&Bxj7CGYwJ&++-?-FV<2^G&@Qo_+@3S)|uzoB6%NW-RdSctQL8^p^kA z{=9zpKXuj92U(xpyXN2zga6a^t?holjh64 zx7hypKi}T$|I}L>n}YvS*W3J2{GYmNV>O>I-s|SgN+!;I#jpR&!A16Y`(y7U_xR+K zU%ll$^nojb|LZ$>TJZnV9?SSYbzMzu@PF!Mn>Gdir(SEHU-&10T2aZLAHD0=tmWUAcyC^{ny+{7RrBT~_&*(g z*2515|EIp@>MN3s-P`*1frSHt|I_s+gNFqFr|x6(1lJwf$)DeZM;}evPVDTDU$SNVzb@PBIj5&loT%D#W$|J3q-aW~HB=g+r%cSG=hx_|Zd z`s4r9Tg(gM|I~QBzHbfm#tWKn_QuEkX+lY=ng6HrSC|LG|Ec+YWPjf9{po9-8=h+X zpU%I{ycYgXz0*9KeZMW%=b`+cn)!3@ng3I>9sj4UGjE3fQ!_6R|EE7+(D*-fwRuGR zpL&z|J^Y`V{qcWlJRSZ|&7WuRe{nPaPrcFR+2Q}xRrdVwe`?le#{a3gU-&;Y^K$Wj z>T-Mj_&+_rHTL}*|EK%6erLx2sqvinKQ-PH|EK2l$N%Z|!}r;IS>KMo!~bc28vm#B zuebSp_&+s15&suoFaA%B2gLuWH`?ou|5M}p@PBGNAO0_H{GXcjckzE}<^kgW)U4Nw zEmLo{uP^>v&3e7~zqs*#YUTkl|4+@lK>VMY^@;I+YP=u*PrY&Tw&4HNtoMumQ!}rR z`G0Za|J1AO@#k-wTdcp2Gr#%kE9QCgc-H^b{+j=%uBfaF{!fpmng6HWSh*#+ynJD? z{{COJu|D`e^@e8ur!H&uf9m!2?|s@0S?Z6czteS@H}g*Me>xwH|5ICw1dFKDr_#fu~sqsPhKQ;3K@qcRO0pkC3zwk}?KW)b&G5=4^ z`l!I;~YUZ`! z|8)KW^JC2aQ!{T4{}=bnH(&L~Gmj7dr{fJB)-J67tH%Ga{;yj8Pd)s!jQ>;fc>JGQ z{!cCc=WX-yhQ0YyzdropM=!kX-S4yx!T)K0)>Fp+>G^Ox{GXch;s4a7_IeC8|EK2p z;{Vj6@pk6_;>Q1}<^R<9zw@{J+TX9k?D(Y>zezRzPy5UN#f|?{;~nvTapV8gJRbiS zH~vpuV%`-07dQS-&ExTZx_>nOPuu1H;%5C{?H@ef5C7u()A&E_FaM_w` z_`kUEe`>xS@qcmS|I~c_;{Viq{o()AJRbk2>y`gg7YsTn_`kTB{}=b&b_g9We_$K? z{YXpqD?TAP`MZbscIE+o{zOaX6`q*9@byD|d%yhS?e{M&UC{g3;Qw^KzTJ*Ye)sdk z{QNnc(*CPg$F%=qeqZbXve&<5y;}U=l?(qK{2%l2@PBI7>&5@YjsLs#gMS47$9DW* z++BCvRw5rU=)`tO$?V&`i&~wWoORvzy*su^d&TU|p2yeixU^^MacsJ?{aW`nY469p z!}xymZS#M3_IkJ{pP2S}*}gB^|7Caf{{P|WvV3Fyv1#u(;Fz@6%l3QOo$dcR9(z>k z`DgE+eLdOp`Lg|9Vb=Y~KR*5b%l3TPkI!D8`sCJWf0*t4vOQq7_sgE|m+k$s`^)@a zwg+V1ApURv)}-W~reBnt(yc@Cn?tAUZF6{1!up@|g$pNp_w3d=d8KPhV6hkQF8s^XrOW;^~*`v-qy{!h*PweMU#$sf;pu796C(Hnn;|I_~X-btM& zrW*fu?WKnV57@0!+c5txZv3Bmu+2ln|EW*w)-CuyHS^2xe>xw{`oC(t9R5$ud^7x? z8b9{_uYTai$EVHxdQ0>Ci+bGU+qqx(KRurNh5w72`G2}T`9E#PKjQz?gL-xk{!h*P zKK!4W=Y#)K%m3;9kl#Ny_&+u4zvBPY{d4*z?@zkUyGQ44!T;%ay*t{xVe^0LPA9Yq z{!d-h?u6j~)Tef6oh-cdYTrMDxcd|MRxT-n-?biDn`n)g$@|DXZs^?nNm<|VIP{6W*h*Uz`#w?0%-IA}m}^&#&!o$=Vb z;QfjRcMtwgJz{kKWXu)6Y8r6Nyx{%h|Kjd{;1^A{=4J4HL(Kc(|I|Zm9w7ctjUQwE zUp>B$`5^qCwx4d>@qg+u=G*XpYSs_N|Hb{ABYu)F?8KQ-6C_qrc>YojQ$2U&L2u^sbw2AEZ|3vi|8ze2zqs*# zYUUl{|J2Mw#Q&*ze)vB%J`Vq{{5dfkH`OMe;WU%9(Qg(e!h@u{GYam{muWWIY0hSjprOOwJz28KRq8FkN=As z|L1L<4*#ddJK_J-_&WTb8b62sQ?vgkZ&&*HnSVC&{S7UBe*a|UM-{35-L;@o6phjrfgDg2+VhsOWKjsH{QtMGs7VYa?6{!cCc z=iTi8;{Nmp%l!Pzzr+9O^(ekPKls16KYMbqZx8F`n*Y=Bm=}ouiyQx^*80C{t^cbY zZ|n2o|J38m^Wp#0>~H_=E&r$OTo3*)Zv0=|_&+uC`tW~h`9HP%pPKcWng16z^Z(TN zxX;Hv?)QiHEB;US508iciyQx^#`lfBcS@@9fAMzwpSmB%H~**Zab8aFf4ZJt_I}3y zsX0FWFK+ywn)g5cFK+ywy1=|5{!d+KJ`w+?mj8!GXF1b{GYmS^ZY+`r_;Lx z|EKOb`sCpM)b}pDIq7uU*-c;kcjo7>v#T~F!`GhaUGen3q-5myrfUaG4c@QHe&71o zH^%w)YMZ}OG4OQn+NJ}^>R*iZ{qcYMjvD37`l7!o9pR0CI`r=0-gu_=8-{x0nM&Ut z;>~vE|4rI3HTXmt|EJzz9;xj1BHy3&K=FUN{!Qiw@qcRk*w?-Zt+J{}(sw|9ac? zvHq``^Wp#0&syXE{(1GZ;QtQV{`fyN^XKq?apV8gct8AK-1xsMYo`VO$NWRq|BV~} zr^W~3|MYm8`G4Mae*B-B`;GrobA0@ty3Srt{GYe^K<59cwf?W4-;R&}Q*(U$pBf*E z|5M}r%&VmOh|53quCw_@_&@Ex!scu3pZCW-I{)e)y}|r5Z`S`EIr{xn&#d@ms$V_q z=iaOjY+lM6AB+Ff@oD^@dZ)c#-@EJORCj#!1#kS_4LzSrb@j9Z-ka_5AHToPo3GdY zL-u&ro7cN{<*rmW{(YM_UL-khOR9&~*LZI|@O(1$J5}Dyi+b^<3UB6xedoD#-uS|^ zJFfP|3*!HDziIrR_x|U?{6BTA%>%^$sW+N`Vg28@@qcRO|Cz7x#{ZeW@m^h98~mU4 zzje~2;Q!Qjo_ltf|EE4DKM#N9j~`lcYVd#Be$C}quzsj-|Nad(v%aYJqS^C;|I_|c z7Ouu8`Tdx=dLw?x`-!sZr19_lz2|PMONQ3>in=!VKfPZT+3z3mf9i$y`$_ztdV#Gk zhX3Pts(9$-HeUq)r(SQr|6a26Q14at`)vH5w$u1O?;X4C_whgVUcIv+_&+_r#Wv55 z`G4v;Ht)~;kavZ7MCSi#JM&PO|EFGBvmLM5sOx`l{<7fz)WdE575-11oH`UA=8rEK zJP5Dieame(;@28<{N=ab&h>b|ylx$@ulK6Wo7sQ2_Fq$1XMf*K67?+eIkvq}y~5^C z+T#bRcR%$E$M@c4^Zsmq?^^Rvc721if93AX{694w0RN}n7X081-n*L)2LE^e$p z-m^cm{;zt6&C_K5pSr=;561tg_wNfH%a7OC(8TNKjSs~C>HIIg`UcnUz1uzy@qgOB z>!skci`4t<^PTyB>izb4ZqL`d>ABZ~|I_w8&%Va{w@9z&?q}cP{q5cG+)sG_d+&Za z%=0bM`;oq>e2{mOtylcp4@$io_x&)rtm|lR=G~b`@#E3>Kb;?s$NWF_&L6(S`_Fs- zGY5nJ)AlCwocKTW4tu?CduEdNo@bxu{p?+1{t*AC=fC-xjQ>+VW$!2apL)OfX8Zc^ z-ktH$smA|le?E`x^VJ&q+DP{CEeS=l$$`(5{F1 zf7*Uv-+|!&)b;lHY~Nq}`7$rizW;dF+564DKY7=ipSAB_-nI65V&C7qEA8_G|EJ^Q z4e)=u-V4oZslk58Z!h6e>Ey>C6{>pp3t>5_0qrdfL zek}g)y_=^8Ke)DjTkwDCvhA7qf9e`*{GYnk=Aq*M)XSUwpPKoh_&+u4YvTXZE7w&9 z|EHcZYe91FTVM6<6CR&s^CZ7stmivp*|KExfNy$l*ts*QJp6F)nw{oV%>QZss%`c5 ze*1Q@?(drV`sBv%9_hW>?vH)_dT%fvi2u|68_jFt|J0jpej@%)U0J>%_&@a=n;*6O zuvWhP_J^kg|EKFY|Ef!a|5JCe^@VJGaKGMRMg5Yif85^t{yT0k&)Tu2?e)d~>G8|$ z^Bw=EUbwa*_&@b(n}>`4QZyAsy_jT`@`=gW5c`$w_< z{Jz6Hm;L?3d%O81`}a%U<<>Ue+#8Q(pKrzbyyMR^&);3_jSsZ>=`C%3Y-9UUKR;d& z|EKFIv#&q=pSr@n{_ub5-S+s?z8G1o&odhTr>-?m#{9py-!uQG-eJBD|EJz%o)7=0 z#_Qq#^n6%P82_i1|5MlO+86wvn)Q_Nf9h3sefU2$^Y`$7>XmkW{GYnI+5g3j|BD;{ zr)FLv{!h*I;{W3Q+ABA;w0XSMSKsQ-m*-<%+?&_$;&0rM>VmiL^ycgTxauEx*O;HP z?=RjP?EUfMarb%i`Go(|{atOo?)(lD{Cd`yhr|Erdduzj_&+uC2l0PuydVBgy}^7Q z{!h*I;Q!*r|Ec+U!T+h*AOEM`+U)<-%;&?#sVlAd@3?!;ndV;)%-ehSp6T9rMf{)k zU)Sva)T^5PpPKc2ng6HWV1Hi5|EbGu-rnEdpY6vlvp=6!zBI>ssWtvjU(d^IfBc_% zz4eYq=BN7Fo1gT?^PTkAlg0XZ4c>3&%?rHQj{nooH|Sdn7WsDk-@9!Wr<(bH+JD`q zjQ>-wxB1%mKlMhNACCXi_2U0N`h2->$N&A}-4)(t>noC%53Kawux@>F@mZ_<{FUp= zg8$R=S<~$Q)GN&URex=*?~ng${b5V5UAQ=T;`MdDeR1>rKRy0}F{8r#KQ-PC|EHgS zb+dUQ_&@#pk9mKr|En&}J3jb7b#DL6`oD3HJGia*@w?{)-`BT)tE8}Dd#dq&zJ0)P z!T-h0`oC&?AO25`?|WrRgLmP8TmwsS8hSmHheXr(3!xGyhN9@kIE)xbc7LfyM2@{694w3je3ZFX8{x%pb)6sS9jA z8~#tt`mBGx_Qg~$yZ9yVuzs=mKkZNB|J0lx|EDgt`Gd^=Q?tJ9$EUpJjTgM~>DT@J zf=^@pU+vGlzK_58hW8koU$^v&md4W!`|M5M9_A7L;jL6JeeWl!#{cQ~@_*_uzi|K0 ze0#Va^MBfof5ZR9jsH{2|HX~}^S0-U|5G!cZ_0DO^!FQH?v_2jN;UpZ@7Lh-%>TuW z|I_jCbZ8~>-~ezX3szCM}fi2u{}aD4NBYOasC ziT~5_ig4=HT_SjzhD2iRA02=@7{d<4!-iAe!P71dVf6cU*2qAbo#%&3rbE* zN=v_JX*(bOFTNi9U)=aV^?*Sq1plYT2aa2NNQqwm9P`u9v_8~3x9ajm9IqtaQlDw;~_iojy zRdVsnn@av`$UlP@WPM)z-vtZ)6+9r#{J*%rJ?=K|&LtdzAbzG+LMk;&+BV(|-tWt{XM4Z@%?INDKA&|+@P9qJn5Q@Ym;0NH|D*AL-sS=Ef9jl`orC}LHviXf z#>2iH&xZfgc03jSPtEo=hqrX_f#&~oJv9DL`{T9ne`@(Z?VsDFeei$kp0@rr{;#3n z(BS`ib!?j)d&dKQ{O;y`f4S&>@7|s5_oL?jw11)f{DAp?YOWXmr{m+H@PBI7$Ho7t zS-%wjr^b)r|8zXohsFP?<^R<3e|kLYC*%LrthbE+)BfC_K~rw??KJ*R`xo}=9sHk~ z^W*>2efsnX{!g8kmlx*$>3*|*5%d4z#{a4DWB5OHZkLY9t7X@EvmQGBPsgWO|5u&g zr9<$4>OtMR1plYTGhXrJRlYy3KmJeKd4J*m)Vw}D-o4Dv&-%E>ePQgXxGcT0G^@PBdR|Kg6n zpWp@m&(2!Um**4jpWi1h)dTw%q`IJ>AbII;?>Ft5G(UJh-hcQ%b@AX%{Cn%BUmh_( zc)wAn=LY|$&O5VLnE$8lKfY&z|FbnPga0c%vuE&sYUbDB|J3-qyMOVHH|zJ}|FnI$ z`8E8Xnt6EmKQ)iX|HX~}Q{(0Ee`@(ZHQPI#@`i68V&@x}`(tnX9{x}JcO^N zG5$|I#Mb-8|EckS_`kUEe`>A={}(s@PtEf|I{URKk$EQ&HsygA5RYJ?e@T-Xl5wP0Le_|7$sa|KR`BcsS<&squFBKQ-G&ty<*GcKn~Nm&X68 z*`N7;YPK`~Pd)CU0m1*N$6jdPzs>)tN7=kN`@2@E?cZW~vp@b%`=5S6|1keg&GX0q zsqtv|KQ*rp^Z(St%;U2DubTHa{!h*OdG*k#{`{Hui2u|5q49re-e35?xbc5#{2l&J zjX%Zzsqww|KQ+D=|EK2bx3u&@Z@xbNc-}pZ*v24*oB0{GXcZ z$N#DM`oRCGnTN>wzj5RL)I%@I5B@K1{GS?+$^1Wcw=o@q|5N9j-ZA;wpmUpUdu?j? z_tq1a-4XnsdQDAb@PF!UPwh#red7$@zpSA#_&;r5Z}Tbee`?m-eD>DS-VNrBK3Fr- z8(;MGH%{|r9@;7281BuyGW_2;Cru09kjDS1>utWvtfxi5Ua`6sV#>({f#8vpm-r%w<5 zkH-J08|?Yu|Ki5~sW~40PmM3c|Cyl*{*U#6@qcR82e#k;db3_F{!fo*JzM;rn%5Km zr{?v>|HX~}Q!_sh|EJz+_Y40QH}n7E>%srUjsH{g{P2HqLm%KLba z&WHcR|EZb(i2qabe#if*@t*j ze{tjg)HMfR4*oB0{GXch;s4^s|Eae=oAH0@dYjjW|5LL*DE?2q+2)Vo|GdrH;Q!RM z`=1Z~Pu+OnC40Xv_wBpQ>-_AU#on9j^T*~}`Rh~D?Emz7Ra@i#)Lf7Kw|A|1X8fPF zSMO>F{!hK8epB#&>N_8OF!(?9O*h>X{GWR8;KBGVKVIITVtkNa@5piE@k8EcTy{Ob z@AjTBBX~9M`)4k~C+*Sa&9vp^{C?ki`pR&eH^MLq2^-BAFKK@V5@6&JY_IaZ|f9Sh5f6&s+{!jbM|LJ}) zKM?p)plE-c&_)l^)`6&Ef-1t8=^U?5sYUah6U-VvXUI726?d$F9!H)0E*9Y_eDi5C#{NEPy zwygiFZnUpg^IpFH9{YN>>+ybiZ^r-W_&d!r;{Vi7*t{_OpL*l#8ULp~`08uH|EZsP z=|^GypBnFm|5GLqUJ@sw>|e_@PE1<=JPTC zPrb`LC;m^(>yQ6aZ!u>W(z3c6Gw#|E&&F8E5^GxrZ=1J}A!<+S-Z9PH1 zKKkpIE%xT$OW5bD@4waFANKX;y~TVe{!gzDZSz~B&iKEU?V0(1>OIdq8~mS|`@#G_ zHUFLj|EK4>+2$YO|I}N|XXF3W^){~+|EJz&J`VqicIu z8T_C6-kI})|I_tOU%ou}KXrx8W3{ixV!b}~c0DyWAK_hV*Ngwt_VTS6|EI3lww2G* zV!a+4%tH^k?r85Sn~&J8;27^M8*BLUrT1oAPm=k6I^L>vWx@Zc@0<9bdDYgw{fw)w zNY1Z3$-9-U_k#b^^EoQNPw;>0F?Ze){GWQl0~3S)Q?FaQKKMWNf-+lA-sbyLH}@%zvGN&EK(-fQgp_l%2%d*cCb=sCihd4Bjmz1}tU z=L7to8lT?uw=sS`y7lv8z1biCr~R1+i2qY_y$}51Y;We zUT=;6)AMECAO25`XT$%+{kQL5?)MY_cmCijQ@#DjtGzk@G4EaD&H3-ze4RJjU!Qb? zH{0=lIv?{F@qc>0tjCN0Q*%G?e`@YG{!d+HkH`PTjsH_u+wt&!asU0y`~Ccz%=h8{ zbUifwPtE4~YL$Gw+YJWA*-~nJuTr z|6$YO=D*{{|Hb{pWiz7Qo(wwe32%JgfA^Z1>ZQldO7*CJw>0bj;{SAf8vm!pO}`NjJA%7*H#!T+f%s?1-T|5J1Pf1SC|dsFqc;QzF}&K{5d zQ`g$#@qapBmCZ9{{$JeqKXtXO5B$YQnPiOzwN9zW9!t=4R&i4QQQQ{pwclo_Vbj{GYbt_waw}+`n&~mZo&C)`2KjjhfaSp)gPPx)A7T6KJ$O-!r>jl{696G zt^3Ju`{S9{ckHo0^Bz)qQkegz{aODO|EFgCTl}Az^=_H}7dQS-jjzN1#f|^d`;G1R zzqs*#>S9~}nfZTeo`0|9?|bJDZA+pjsH{g{P2HjoGl5z{_pssz8n0Xnt6Emzg-{x zEBL=2?OFx@$31!I#&=4(w>>fVKQ-I&e`>bl|J2!jtJ6v8d40uMojt$sKfGVodcN7d zFT0s{7<-HC?VZ}Cydv*#yf_rMdn;CpzAxTC+XFKH@3z~f>>a-6kTCDBt<6)z|Eb&c=#b2|d43OcJS2FbUgohL zozv3H`+J~cOEW+1_MH#;{&==)#w3eX!7t`_?GpT-x?iUb$*3_CTDF@n!~bbJ-VFceZI8$QefyZhf)~W^;s4ak zH^cvFe>@caPd&PK#{b2Q|5I!JpN>bf{;#(8w#T#nZ`{oPQ+Kuf@qcmOcFFDDcq{y$ zw$u1OHNNllAKl`eo0}W_pSE}Im+^n*D|7e&vqw-uS|XC1-du&oKVHzz@b< zke6P+H@oq#@&2Xueu_K$c-iM0RM0>8zYh028T=pKbj=yRX`23(CxiFvH>^wWf9jGm z`Xt}l^2?^b%$*;6AO5dh!+WX5|7rWE@x6loiyQx^?rk0g|EJD1uY&(m>t+u zZEjva{Gay6ONI4+o439BTUbg=5in>kS%v<}U zq1v1Ec1IknN;UpZ$CLkyoB4lgJQw~iZv3A*-+UVWFK+yw8lQ&$Q;)HEa`-!0HP z)T}4_>3}uf%n!u>X?tIr_lN&e;|KA7apV8gW6cZV|Ki5~sWtyE?y&xE^XtQQ{9n8s z|EHG!)B9EaPc8o!H~vqJ@3a5*9%;VJ{x0P${}=C%|5J}QKZyTRpJDf#`G0EpKQ;bu zbgL))`k7z1y3-7A-Y=i!O!wyfJGyXMs_}n%{_=luhxLD(?;l^!Vg29c&a?A}^?#ci zUyA?J;E=yr^EWcQI9tNr~OBt*Dv@#^{8|E2LGq#{P;gLpEsos-{+loQLg=c z{vK~U;Np!x@aFwjy7x|R=2znXbUz1Ok{|qE-1tBBX%`m+|EC^d^BwVjYUV@Y|I`DT z=l`isIiqXvf4|r{E%?8CSKk->pL+S`>fry>oAzb=pL+G~J;DE}SK7Q4{GWR3-e-gV zQ#YD-!vCq6r-%QG8~>-q-;EeJ)Vt=X=acJi9pb(HnU{nA8}`-d!3Q?J@J8}TaY>UJ z|Hk}3HOIsMsaM)|{9oLx|I6HHh>iO)nd2pNNwM#Yg|Fr*Z zd;T3>Y170SNO(maf8dK&-aE|yU7K^FcY}FH{NLMoGlCbafARI;|J2)To)iA>)G0H9 z|6^X0{eIW?-)r~Be*f!@m&E_+@vJ9||5M}d@PBGvKm4DX*BAe%-tj`l|Eckl_&+uC z9c_J5?Lyd@qcPwAN-%1<1_y+?z=nG`14_2->%6Uy?H+PKkdJ> z+5f3`HTysH)8_r~e{tjg)ObGppPnDSkokXV`9C$=?RV|IeY4G@!vAUe23wz&`G4vK z4LgJXQ{T60dGLSg>67mZ{!e}SutE4AzrKQk9>M?VdIt{d75tw%f5f=p|I}CAc|ZQh z@7LK6%?kcc@249Vt`GiC{n+BN;Q!Qf)^5f>`Qzu?dSUoKZKv(?VUIo^=GyvW9S=V~ z)s-(D={?K5V9z<iMoQ zPiF5o?}e3{@Mn#>pR;X!V*H=>e|YH{e3SRRa~B8yr|m`OUc&sHMm^ur!$xvHy^976 z#LxNhuN^jo&nrLPuEh(2|I_iFEHB5iHmLD2_WF9)?A{yvpRSknr1?Mf)~2U}|5NWi zV4lqUpL&hWXT$%gSMS5`{oZ?r%}2xkX?w=!<#^YaH^cvFd;LqVa(wS?FTTe6Io0;{ z;l1Cy8U9a?f9ly6g8x&$WM3cVGkyF1X8)({t9I@T{!hL8_1C$6-~UH1zs~3BAl<*` zUwE0%=OT5ZeSX>Jz4yKsZGH3wM|p3z&rAHD_QzwJUoFz>%l8j^e|z)&7XPR1+s!ZI z|I~cmn~(8su+QJaCzKZH{YpQ!Ym|4*^Difd{B?Y)@qaqrX7iKyKXsiwAAA3K?==60 z|I_tvxAkxFf8OTt@PFzC^OyKP^(OO?_`kT#a(Lqt@qgORyj5F&(9e(8!~f~}_~+Jdfz^2B7WZc#&bsD z>%A`Gj$=q3A^?r2bZ2NxqwPHQL$5*VhwaUNY&A<1tug7BDzisB>?ayc4wYHwI{rSzi z!rK0P=gs=T_&+_qZ1a}j|J3ER^}+wCtIVh4|I`&_8~J+oo^9*zGXGE4d;NVAga1=s zaKQz^|Ec+Tcix0{zJKY!jQ`X9x#zZPga1=cnUL{+>PnjzS^aDmfBZbVpVOCi^~Q5D z|4;j`vey^?r(SK}-|&Cx@@D_1u4?vwYWY81e}&D1w0XY%{Hx95;s5mcRBL}9!~d!A zTKK=X@qhaI#@FHh)Oa%dpL(15HvFIN|4v&!7yqX&Ghd7UQe`=18|5G#X5C0c8{x5F)pUzidug}%1Z}H~w zPv3r<_g1^UlLvp_yWXzvp`-5fmjBc9rSX4p9|EXC&7rUmvA6IVL zmhj)|jW#d3{~uc#@7MA58NOZqFFqdrFK+ywx~h5ppPKc9@qg-Fo3%S zONV*h@_)KM`9J-9WL;Ip|Ebs7n!Kr}Ncp+#LL0 z-1t9rrTOgTyO#O!D$E1o|8%@sYy6*jlYL&||J3q-YS#P3|Ebrn%&h;bUbAdf@PF#E zWtsVZ>J_%0J@fz6i=LPf*8f$XH)eF0|EKQK|AgTG^z*y+y}uXc|EckRvp(2TeCg%$ zg7=gEQ{(IKf9hT~pAY}1?mHmk|I~Ot{GS@XhyRNk|EFgCO#GjEz`#~v{-64E^Lotx zQ;)IZ;s4b5y*XDlr8=zt+x+v+?gLNAtpD5GJ=$KmJeq)A+x* z!}`C?`*Xgok}V2>n(5Q`wg7@lT=@O_fNf9UwH0~Z+n;8db@`l{*GTC z{_elOXleW%{!jNu{x9yZ{%`aB!uKtD{XIV(jsMg0A2~SV|I{N+JvprZs}A$?%>SvG zpNIcb=i2q+|Kk42V;^|qHUD(~@4WGOVg29c>*IW3{om#uZtusi{%>=K`FyPZ+uXd~ zVg29cX1?TY`G4}`Ghgz;o*#MR1Mz>lK0GS^PtE%Y|EK2thyPP|Hm}G0KXq3-KmJcW zZcv-#;4eP&=Ic4E|J!_h@_*XDXyEa||EckU_&@a!^S$^#wfvu+KmM=Jynp(3{NG8B z|0~tsnDB3JzTU(7zs=W!|NW>>QljGzEi(VSsiiqT{!iQa{J{UI``PCy^Z(RgKI)>D z?wNB;@PGRKME}mMga1?KbxHfC5$!wLPgC|isQ(SiTK~4+$?5&GJsk6Gjy-5lFk7oX#n&aXB;>Q1}v%OaK`n;@9s%z)}7oVJ7ulLKYe_-ph zM=Lrh?Z0`VYWYPeNy`Qo@DEp#`hz8UShWY%f8>)oqhj%c5atCewQv? zQr)Rjr&MQer}2LmE<7~&zs{#*=KrZ#{}=x^`=1&Ahxfz(seAYA8vLJH{!fkH!~dz7 zUx)vT8~>-qZ#{8jOZVy7E4eR!qHo88U3K{cZ|2v1P&dJ^KetEEkEH2~ z`@NYLhyS~@^swLsY5bp>^KaU7pLf5U-pPHxzSmp+Py5UNsf+vNhWUSLJQ@B^&HcD* z^Xn@m6LR)4a)zR;s4ZQ?SA6_)ZEX;7q9VVePsNf zu7611+~EJz#W_8L|5M}r@PBdR|J3-v!P_tQ(qQyC3*J^{F|w9;W#}HC_<^ z7dQS-jc>#MsqvxA|5Nk)nE$87Uo!ts&3r-ppPKg%{!h)kJN%zIKR-YCKlPBj{N&`f z&i3v2IsBitkG%*iwe`8u(TlEL-NzU zke|4slJcLUDs zmOMB7J@5Rpx+j;M@eA)FTkrRi3x4j+yt-*uz1z}f^-kK}@=mI^-u*LgJlm*;-cB|C zPv>X;AO26x{6PGln#be+;rQ{x5F) zpPKXI|Khg4Kl%B1y#4(u)%N!RoU|EK2q@qcmS|I}O${!h*N)AsKVn?{^7Km0sm$k~1Q`9!MM|E11b z>;LNUH2zO5{}(s@PmO27|HX~}QwQ&8{!h*E@PBIj7W4n&#{b2Q|5M|&*4$I>*N-3D zKDjK__&@EBKg0j2@n`ryHIK*tshR(V|5FEFX#Ov5{GS?MhyPPE4-o&S9(i$};Q!R4 zFSYA2|EC^q>jSg?Z`}AlHJ%Uu7dQS-&H0)Cr}sbSXa1j>=g0g%HR~7Ke|xjt{_d1& z{Gay6H!}Y(Zv3Bmtep@4r#}6{e!>5#x&NOZIn%F~#{cR1ng56XQxCPT7yO@^uP^+c z8V`v7QwN`C^Z(Smzwm!*-k)-btcyVU_pYC_jr3DH8PtE&>^?%iPKm4D1 z?4<*P|5F!^%B=sZ?tW(P;Qz+1njZY$Ju4>!|EFG2Qx*K5x@K=Sj z03o#WUMHE!^wdcvlLQDQNE1axP*lWz&fyb<|C!%4|Gl4gy{xm|v(~d7ziXF! z@4F?;d~*F+e;EI##uwoK)XZ~Z{$JeqKQ;3S@qcRO$Kn6fcr^T9-1tA;4?Y6_7dQS- z`*VHxKh`|L|8YM2pBhhr|5LY_KeTyZ-EAI&`F}6LPhD&Cp74L_I`ew?KlN5?{9oMoKQ+D&|EFeNApXzq$3DOKzqs*# zzQ1`t=KrZToA)z+;@#fm|FnI#oe%$~X8mCNU*pwtf=8AAQ#1dJ`G0EW1LFVGt$X(e z|EI1uPlEqbH@58z{!hKw)~~YPulnP!pZ5g5$NS>xrv(3}>l-(=H26RD*fAx+|Ec?q zpTzIG{rMSp`BnI%-TM4i+R9Z{Kkz^JcvB z%PWKb)A^6J|Ng}PsSD4Zi4XI>=<3T@@7Q~-&BHanwo9+~#)kUf|8#vjZ2lJhPrZ5P zUiROq{kQFY*8Y1qV>7cl-;cD-6D-sIZRY#z_;U4p^Hcag?LW`_lg#wi@Aj8pvGYCYz1w^i{!fp;@1@T9f9jWCemVF* z^)t^r!}p6HUu*N{?EA`l#}C5#=id7dyc+zUuK!u{iZ(y8Qm@Aj^K&*|(tD@*G;l0EDeuDqgcJ{~r zsqu68KQ+Gkdj;ooxA{KvBHr7de-Z!T{fw=TYo5ceXRoc-TiJSx_l~{KGH=Pd-PZeU znQ^Zlztzrn{a+tQw9Q8H{cG+0Ve^W7d%YcR{=l30g0`NZ_ZGXJ0Y@zIX8qz{*Dg)8 zect^1Y_A@@HqrP$y`CHF{fz&M8~^8R{uTeHuDAF1U%$20&&T}4#zWf@eN|1ncT;Kwb%0v@0+f>%+?cq%O7v* zq*1I_?wvXPe0;w5nALUmef~?opQkpoGT+yGdFyVz4=VL}!H3O1`p@2L%`+Ww_g^ay zdv8vd$GOxz*#03OC;F~8KJi{|UZ(Ur|MF%%)9)OWsnYSxJG6h_P^HIPXY-kC{;~Jn z^XBvKBdYZLfA{exn4j!Dd)Zq4e&xN^=84+pu}YtxW}9bsWBn1{d|$tD$C2JEY~EGg zDPQqkZS%S8^XrZO`{SR#mgvbHM|*FoYY6^N*SDdjHuyjFQ#Kz8|EK%==JhuQ|EI1x z`~2Yl)V)e7g8x(V?~A`at)Cx%>$k7Bd6ombAHMT@nb-a{(7S0}r~lLOi#Bcy{!hKm z<`-UmO}6j9%KZEIQNz5~n2$1F?v4LD=!4Q2!`NaD%|1WO*pL(NR5B^VGYy0E>)SCaN#=qhJ^mwel zi~m!vvE%W7>V}rK;Q!Q3=8f@xYOenmzx=j09@PGP@vb$Gy6oQDyqU*`|I_iTAB_J~ zvtIKDmwnH#AMZD@_%81{`}ZCAKkZ**-*3$SiyQx^#_Qq#;>Q1}n_9Pp`G4xhmaW16 zsW;esx(Ba#uu6a5-PF7#bIWNDc{khqKh~<%_D1_Y!vCrHzQVG_&Hq-{+242Ze{mnZ zbB^~0`~Es)^<#;~|LOJQ{J*~Tao=8VkN@V(C%iY?-+%FcI)AHqMEsvx{!hK$=8Hb{ z*Qb3u>j|^|uYMjvr(U~qZSa5Ul`A^u|EX6jUlshH z_tNEI{-1h*{rw;Rr(QaDPVj%~vnEf2aCtoNZMf{_?5d!?Mbb&z#w3yLVx6ugtwi@9-`z z?USkhQk(aPGV@{P|8%~Q<$Z(yQ{#W|e{tjg)cKXYg8z&AyJzk3?KxFFGnY=?>piTx zS7!R?ect#W{GWb4S!DhR|EI=79o6SK-ybjaucP;SU;s4^s|EYPt@PBIgKko^>ga3;g|EFesV*H<)^?`TK`k6QL@_sktokYL& zw|D*ZV1C}d-~T+(^*{fGH{K5ar}q!nhyPRK`XZv3B``(OCZ zZ~XdrzMgsg18<)HKR@?dZ=T=d+kWRgam-1XaSgvu^mVKM;LY)i=l{{0_uF$1|H+%z z|1aPBvp4(W|8#xygiAm4?d*TUxqs>Isy@O0Y5$7qzQO;g@v-8L}z^9J_G^!@0N zYF$6;dB&dL^ZXp^d&c{-o@d-+%tMuabXE17X$J-0SKY54zfbWl=-)f|KW(QEE4`-r zp*5N61!I3!ji-C}%h!722RFZ;?D+B0^V!ngFWo#|e0<@6K8eO7#@o}KK0d!+(gRkf z)}Kw!BTW0l!qo9;kCyJV|4YvkOnbd_r`P9A&(}-OcN~`ThMzk>v2W7njZAg=__Pm9 z`@eLjJzu(y@0WZ%Pw1a~f2P;>{lB_@&&2DWo$`MJ1|)rKx(5v!lsI1g@4D*_3I4Cw zkb#*cm*2Z*{SOZg^Zxo|4G#WKos*Lj{9oM6|5M|ynE$87YvKRYY{&np*^d8H%m1nI zeE2_gZfG$U)=aVb#769X7fL;^ZTJ!^hq}UPxm{_)_cYOsS64Ug8z#f z|EJC^9ufSXdRWo$;Q!Rjr^ElLt4hm)|5MK@DG&ZnefG%0;Q!PdkN;CMuMYpG`iqot;Q!*r|Ecqe3xfZP8~>+fz9RlljR$1?-?;IAYFy{9k-L z{!h*NzxY2r-c<96%>RoU|EK2h@PBdR|J2+s{x5F)pB|6v!~eyN|5M}N@PBdR|J0*w zJz4x;-1t8=>m}p=)ObhypBg`B|Gq5I_`i5N{x5F)pE~$C^M7it7ylPG{!cCcr`U{=9zp zKQ+D-|EK2lv!8Ex^Zt4DOL2G3|I_t^`GV&E)OafVU)=aVHNKDee{tjg)Z@V z|I~QDIahD+>y!V}^^ZBHDEPm)Uw&+z?~iYLZ_(OBkG5;@a{GVF> zPc8qaW;^r$;>Q2QjsJ@q|EI2)RTTW6n)O=oe`@(ZeLlyTC&T}#xqkcKi8kBi&Hdy5 zv_FmiQx}*|#Q&)aXBB4fe`+3o^1tT#^>F{IzL;$MpRSkd!~dyyeei#3*5k$hsd<0k z|J3q-YWY7k^GWf4YWY7k9*_Bd>R~o-5dWuUz9{}r&F2^Yr_QxM5Ac8LKIXykf9n2c zjR^Dq)Xc}k|EY)BcKn}uWS9So8~>-yx91c8r!MI7e`@CcE&APczFq!LuTRy5o$LRq zM_t@G|4%Ldr!GBtP+0$0J@mBP;Q#hK@MyySsTXc;4*pNQu513En)ROWf9iEz{%^xk zj|TtOxa+y#|J0jpo)`X4`#0NsF8p8I_&+u4&EfyzX8vE?_`kSoe^}Ms=7C;3tkQd{ z`M=+nm3!j>55Kn58^6c;zx>P}Ke(sM|FH%T9&m4$|5G!64*#cS{u%yHjSs~CskfPD z!~dz}|Ki5~#f|@q8~>+fz7hT}Zr1&N2%;>Q1} z@p1US9bbAZ_&*x|r{?*=|HX~}Q@3`_|5GzR5&x%NV~>yjQ?Ir2FPl3x#x zhyT;{;ob0mYCItRPsii!@PBdR|GNA2F#k`@`SE{hd?o%bZv3B`{h9w4H~vr8gU@6B zU);?9Q!|f``G0YnKk(-M%_n&Cct5@J2j2De{GD{*)kNd}bUmz3jQ>+_w0VBa|5LBC z&kz1jU1OgI{GYnb<^$sY)H}>$n&0rp!`l@+*OF-bpYCU~ZO8w`{jXovc-Py!PxB?- zte0&5#GCI2n@^Q!n_uP4+S1AIrO?{aJf|J>uPLKE>v1c{kd8 zDf3d^_!67X<<0K{@qc!Euee&++h|7rW=N0$Zvr#@%Nrr`h7H?C_8{!e|=`ljIj z)N?m9*zXIE^Yhbh&irb3*SFa3Qx8w{k3Trbd%n#R+&t^!cAambtuMCY!weJ4c8T_C6%$(fd|I}4S9~=Ci zI=dh@_&@cncYlZP=XQNRu6*nEXcQsE_q3gl_nQ!yn_R=fdpZBg; zZTegH2zP`ygdA0-1tBBHuIVIKQ-PE|EI?5;s4ZlO8lStWjp_0{&cPP z0lU7dvu^R;V?NKkg*QGB|EJ@(nJ>iu#cgW`de_jph~ce`@9f;{W2t|EU}7 z{_uZsPDM)hyPP=Y-kDoPrcgaZQ=jo#{a2T z+Ip7wKlN&xw}t;x*KBGE{!iDld`(U8f9g3)R%Y57PxR|O+2dbb(KTC@kjVS?Z3k2kKzB+ zcu)MFdcDm@#Q&+8?}z_W-S!}rGMx7Su@KU zABX?bcIMyV|Ki5~squ06KQ;T~|J0n1`G0CW9R5$&v(mgQ{!cCcr;LNdYR&WE|Ki5~#m)M^>W$_B@qc=} zI{SXb|EcTk`}_X47k6L3eZS%Vw7tgWZ{z=TzE$P{@qg-NHJ$!Xy>a!1;Q!)g{-2ul z+wp(uWj6osyIWRP>E}gD&39)nS>?TCMW_GM{)-na3I0$0w9T`{|EX6$F*o=>_4!jy z4*pM_UGTNckeiyTdc5^?@OguWe>rpdWi8&5i;m9Rd0wmcl;UGDb<;L`<5_+*c1xl& zC0o7w7M&3MpUyv^^rYbb)Xdw%|EY(W-@*T>S+DoU|4KIN|LW)A%m>5&#f|?{=T{yd z{GXcndH6pyJ_-L9H~vqJ7pf?FCeeekpY_IX;s3OM@z~zM|EZY|hyPPgtnQO}^MAUV zrG0@nQHsHP?gx zQ}g)vKQ-I&e`@ZZ`G4NFKmJdRpTz&Exj+1$n)5UNPtANf=KragPlx|g8 zbbP1()9YU{u1DtT-@WhK@pSk+Mn&r|5FFgYW`2n`w#!8#_!?()U4mz^25J-2mfm8|7tt$ zAN-%1^Wp#E#{a1~e$w)PdKXl6&i~VP{O_8*|ML5%U)l0+Z@z!V^IXtBIX^A!)6!lm?ak8j?bR!ZqG$ zf0y=qpSPX!#Xe%#=gjj<`@*z;O!uULNnbc2<;l|5m+rJjORsO7?(}-M>DMdoq~!X- z19~QXUcVm4B%Y77|I6u>e1D|ZGfuC+oA!z6d57uwiX|r`uO~eZFx~0(f79zD|Nr)X zeUlzGz20xy`}H&58o!^?uOGeshxhJjt3M=oKlwj(-|Qj5|EY%#9UAD z@F%x>DZt!M)+>1ZB-Wy+r|I_v3-|&Cx+`@t||4%)J^Z(TNG3NiN3k!;a|5I01R0sd3zQEQmV*a0ca(-Fxf9k4{o&HbFJiCn_earVh zy|gm(^oiYla$bJ$e|o-H?-~E6X8qhVAHT?t&nqkr{!iy0QCu4QpSrA|B=|pdX?}5- z|EFet9{x{_7sUUmxqkegn)QnDf9l*}o%8?HBS#d3`G0C2pZS04l94u#!2F*YkB9$L z^Z58bHS6`_|Ki5~sjJOdFTwkbsV)!xPhBuIH~2qw@w5>cn_u1Wx6Si| zzbmr!f5$EQMWSu~wRfe>|NF51U2o?9joajM@4*#bfXMPL+r^m+^ z;{Vk6Ec~Au?}q=28~>-qZ{h#c_^qYA-t^}9zYO_-H=b@n{u|yLkN?y41rKKaPaWp- z&3M)Kr}2M!JbW7dFK+x_-1t8=z77AU9)0Gp;Q!QP&a&6b{GWP~`8E7s-1t8={to{a zH~vq}_2K{G#{a4DK+OM(8~>+fz8C&4Zsz~R&HTT(@qg-Yew+UnH~vpuY4^|kKXrw9 zNSpuP(W`oX@P7Cs{GS?sg#T0L+4F<{iyQx^=KY2LiyQx^=Jmw?spbFFr`Wtm*8kP@ z;YpeQr^fdknbqLO)BOwUy~pDn&Hrit2{w-n|EI=tU36xx?@!-y(MIp_wq7s(PuDZy zoWd~wPd)Lh!r=en#{a41|Kk35?V7~)Bbrtxy3fv4-ps4R|LJ<^$*-^Q?fAC~ezx2j z|90~S%M$&_Uza9&<-eAAbG|KybvN?~U;5f&-_CrupZ8qkjrYR;`SqMroLO1BAkntX z8~GQ|5Y<@5&x&w`oC)45BR^hng6He^Zj?5{}(s@FYX8adA~n@?7!rT-OcB#>8SgB zJB|O-@$!FaK5zIxHU1X=r^XL5|4)rS#Q(*O|5M{@8D|h(HB?P`UqEgPrINZGp_t{@A4@_g8$R^f8}W-Ge0}_ z694mH?&|x({J%V#PqgdgtE-o9X$}5QUAwm<%>Pp}4-5aN=J&0v|EsQVdnT;^tKMSs zyzqbOrhP94|EF%T-@oJk)cpP(|EK2n!}vdMn=gj{iyQx^-n94S;Q!Q(&%PS`pLdu4 ziyQyP&-n3w_@=?7MTx%humV3n{_c^ok=}T$hhH1+`_r`t<#{vj&gO4z8E<`0)- zd$S(l5sQX;;}LTX4EDwk+Pp4r*3Z28vf5rK=6z^%%3s; z?~OYi3;u7rc{BWD^AOEM`WRHjciyQx^#?RsZbbU1bPtEn?|Ki5~>3IAY{!h(3MEswc=b!a|3*8D&1&-01@ z)8nl-e}n&1*VsHQ{GWQOZO8wq`Ml%*)Qz?s{}=bFNh|&Sc69obM4MmnX8lR?E#9m@ zY5v8#>6sVsG2RU}@6Y^ws~_=dXR|I|x1Gzb5uUTpLJ@PF#3*VhOCr=C~S z5d5EdgKfwEsn@RFh|g))=Vi^()xrPi^`G;=qvrD(eEW=RFSYNpmEK>=9TfbZ_RkE; z3jWV~;86TqyLUw%^W6OSvlnsxVcv^v{W1KXuBXYog?)Z^sawr6;Qw^KoxAr1|EF&0 z*n@Z5sot^wdHe6%j2W5E@7pc=I_LlC^Hbl}>HpM^*zeo%f9l2d=bxRgT*tHiFaA%> z`oH);^)_3t7yqZ;_5IhmKJT^{4+Q_G?KJ*Ry~`T^r^oNG`G9u6zJ1?IFZ23%KWp3V z`^9_L_g}?JdGCGWO|IXY^Wp#Wc-?YCaPG7dQS-&HBFhzqs*#>U}mp z5C0c8{!h*Ny7<4i@qcROMdJVB#{a3AXKMf3n}2VC|I_xZ_I|?usaf9_|EFd?D*jK+ z@%DN1uD9dye|r8KI={cYH`)2{f7(vt|I{se_6Pr`ZZ;2y|5NjQjQ`W))A&DildY$X z|5M|$@qhY0sWsT5&WO}q)8_S z|EC^s+VtT6)R{XT!1w$8WZQa=_Wt)?SihZrA5f{!7j6H3zzH}g{Qe>Sr= zc)?}nY4CsQ6*eyn|EFGSe;(og)QdKD`aks@ix&s~r^ml_-n`)d)DJFM8vLK`hk0|% z|5I<;*6IJ$8(KF9|EFGWjsH`xZEoT7>%FR>DfmBaU(?hQ{GYmhV?(BP?yf7> zyn8=Be_`-{y53VxpP5;B_eoXiJ`=`fZkf@`yXV+Z!T;(0tH%{(M*h98Z@>4U+il)( zfA9HEJd*kI;(^|+4I6_0)A{Q*b^1SbOY2sfcbV<`v)=EezsyOr&1dz-fAxD{xHn!6 z|EKF?ej5HyjSt8FsaM(hze~Pf?8npiKRthVLj0e)#@1iP|EbrR-@^Z?*W3GL>buod zdjHp$KdY}F?T!Dl??Z2V=@nDPCmR2!^R2T#zwm!?|EW11 z{}(s@FK+ywTK-Sh!|Q|pQ}g;T|4)tYo7R54A79_RBZL3*^V#c%|5Ml6_XGY<&HB8| z|I_(+zuoxhZB_cdJ z|I_(vy8NGdgKfwEsquj|OYcwgf_oqEWRV}CyIztx)m7dQS-&oAo@GyhN9Y5bpeU32h%YCItRPmj;} z@qg+X`|pXL40yWgtpD!(_m#}woBbd2yz9*G;s3Nh+wp&D{2uH7dT-bi{GT45^?RBB zr)K?i{GYnczK`*LI(}_UUGRVEHMYL*&YsKsdRCj)zVeXe-m7fh--*BP?lr5|We&W$ z!nf1-Ki%I-^M3fhxPNxnYVT!>7G@s3WKE*Wr>yl}^>pX@zq-Cz(>wj2n)P`X{jRC% zx|#E;mMp%#dU(OnnJ>K4>^-IE*vxgWwIurOXIj1G|0W!m7yKZN|5G#XkNJOUydU%b z)ObJqpE}n(5dKfi`nUMMxbc7bc{lzC{}(s@FK*WVRpXJG_I3FA=(o4-N%R-%_Il&b z@P9hK#Jn5+PmQN~@WE$&f4o%7cb-f1yVvgbW`F#jjxQc<^Xfi&A<-Lu_o8=^t?&Bu zyDugB&L14`9zD8u@PGRGD2@M9bl|I}>9|EW1Y^Z)dE)A&Da=lR0_sd+x}e`>Zf|4%(; zOy~SRHQVujapV8gJpau9i<|j>>flYy|Eakj=Ktw>IX~WW#>iuz|Z~FS*y?MW`JnX-{xt|07>~4JS#~*&;+gY!- z@B9DoW*#8^PuD}=`u%_Uc6>1YPxsIF4gN3gPd5HfqWdlX%o~5aVN#}A`_uS8HS3$> z|Keu;pRT8P3G@Hdxr2LT2F^Le_s<)WoOj2(zSs|>=jWw8-0;*q!14Wh zWPZ2eis~y`4+?&7Oz-0}9XDO+o!5V0X5=@ouFgO8;NSy?4;YlWvgg&loyPy^cpCqw zPOncqv2Xvx^%f0G&U;IDLI0%BOLy8crtdes|H!_{d2#9eN2I)Ap?RtBFqgzjPnhH#v{-_|)?|xKHx^F(@^!u}_~qiO1`kT0eTgpyd6eJMBU7 zt@yuJ@Bc#Zf2{Y*{J*$a|5u%zogMt2TK+F?{GWQ*u+H^=)y(h1|EV?qPc8qaF3-sd z{!cwDuhaj|sj_vssl zhIxVXSa3DZ|EC^a+Uft)c_kym`oC(<$NIl&t_T089-KQY_&@cqg3k4S z)vOnb|5M}RSpQeedb!O1Q;!;v7yO?ZkBR?N7ufvCyGDQ0dyK7DedXmBdso?d>i9qH zpEGz!@PBIjB|5Kl4o)G`1o@O2q|EJdaziNCR{!fkP!~d!AUHCsW+m}?n?#=eUOnl9o z?KU6XTmDbS%m1nIefU3byFdJ2-1t8==VSh#n#aTcsZX7mAN-$s>gl%LuK7PTkB|RT zvwki9PmRCB|HX~}Q?oz*FK+ywdh(h1!T+gQPZ|HG#wX$b;>Q1}nNP<0ziK=o{!h*I z;s4^s{~cbiAoxGFWSvfSpQdj z%Gt%i|EZ^*Rg}U1spbFT#{a4DX!t)hUJd`JW-~{_ub5upY7b zKlSwUii7`CpJuNQ{!h*E@2r{Q*US9BzcxJTjsN>%+auo0|LgJG!`}F~;jhj1=JPQA z?S~S5-ftdE^!0yvz?;tp{!h;zjsJ@q|EK2rVE;+?db9uAgYWTXJN{4i$Mt;ajyruj z-f!encX$`s{7U?v_NVcG>cVq}2mcp0{!g8Metz(OYUVHE|J3<5-;eo!>Vk_(ga1=c zzMwq#KlPLgJN=(}`bAa2|Ea5|RW64mI<>@PBH&AM^jz{Qe&Qr)GU%{GS>hg#S}F zn$N@kshJOk|5G=ZcVhlu+|2(|*LV59xQDJT_U+s4{F8rJ=)KM6o8kYoKfVwD7kAw? z!@couFR#k=#=rgH%^dGt<_C{BEZe)y&X-*_)Egg%|6`3IJR*(%Q?s5j{!iU*_mBTm zYyIE2ZGBJQzS-tIjlR8S$C6{`1`kN%|33TH+~5Ie{GWQuORon1x8Uu$!T&vLkB9$L zKV#Q}|5I=6@_%tN|4+TsydVBAZv3B`^?vbxapV8gJpcGVT_3&@|EHG!Q{(OMe>%Ry zUjMQK8Q-6Ik2^m4_ipWv$Hf0>e;WU%ZZdy&_fa4D{=6Um@~8jWt><%%`8E8Xdab>m z@qcR8$Ho7}UAE&FyY+hE|GsG z{p0_1KQ#VN-C*->3}+K zKJPsqtnuDt$ItrhnndIObpN~Ue$1yN8vm#5tpAJuiyQx^W*(OPuFiXtc|iQ1wl{bB z8t;~UVg8o)X7eZbKi}WJ5AlEMwOh9a|EFHs&=CBedds}I!T+h}-+W#0f9h{tG|gVm z>Hd0795<5h&)xdI!8h3Vp?B}`V}k$F`{!#jE)4!pJ@~Slga1>{yy4#9|I`=W@mTPG z>T@5TAN-&Ck|nEx|5MMNzascQ_5DvS3I0!g#}f;K|5M*RZ)xy<>IL`C4*pO5$SrpS z|EK$(d;UdupLX^2RbzwyQx7g49{ivBn1Q|UO}>9_MOpBFdjDN<>&^JLcJ&Rj9}50Y z$1iMb2>wsK*4Aso|EZgH?hF1;y`^n8*RxB_{6G8szIV%B`nNl^eao}^?Z0<38TF>; zpT`50>3W(Dn0L>+yj+bRGcV=cX6wD;|FoU?bND~?c6&eL|J1B^i~m!1*!t}FKlN6d zr^oz1^){Oai2qY>59{f!^k#i`yWa|3{~lWp*j^v+y$4?5_4CH>+4q(Ap4WfK^Wn{W zKU*K#oArHd{pd=ae~X;J0j z%}3$?)XeY1|EZhJ^RoW0dS_i-@PB&0&As!^;Q!PYUOW?@@B3Gcvh_A@c+dNkv(FCx zPy65b@WXt5{r&q5TQ3;@r$2A6Y1tY4pL%W6&fx#zw!eS){>%r%|NU#o1W7W|)jjXht?|5LBD z^*UMqSH0BcW#RwSi_EX!|I~|Zeiifo)blqq2LGq7UE3J^pL*GX)xrO%=R7($_&;4g z^ZoFD>a6PG;Q!P)qf5;*_wnsxPMa9~pSIuk8$^&_b)z+^?&0w-|UU=`ty-h-t3S6i}%O>sqt+1KlLi}aQHv< z8uPU;o;cBarFp!;f0*QrPqpt)?*(?g-^`xsz1WT)clN2?%%58`__RdZ_pLY2UrG5H z{`@hYZs8GUdUHJfPwy8R{}(s@FK+yw?uYew@qcRkCH_y1KV<%&n)R^pe`=1$|EckI z_`kUEe`@?4^Z#@`ygvB9xbc7LdRuQ7|EJ?OnSaCosn?qa#Q&*l%nRcGy4(EcKW_D2 zZ~hMdr$1ltpZLGH@qhaJC)bPrQ?F~@n(4dlF7NqvzPoqa?Y+d-oBqp+d%RcM^LgO| z_a^%FtM2p0^HtBd-y84ORPuoL8hbqapB|sa|Ebs6d_Vl3dcFO94*#dd+cE!7U1#UV z|EXKL=Ktybo6X~4;nb{O&i_`gZD`Km|MdJa{}lhH?OY%JPtErS^Z(S%HcuP>r^jdg zU;Lk%^?&hyhrK%|tgo=a8vm!R+0>FL`Ac`Nv;N(W=KJ>5=D+cOI$xdrdGK!UMTtJ; zi;KNC+IIY(u8+q5>3G)rW&U5>_&;6Gs+x_#|EZU*UK{+MdiAQc!T-gL|5LO6FaA%x zYUP>?{!hJP*|OmO)Jx5?2zaTfCWv)pPk)Z{}yseqx(99`K|4 zwtM6MF1U4vHy-D}m2HVGnzhp#|F?Sju0;Rm`1bBL4|H3}Zg0F0{_lp4`N1oeSM>@0 zPtE$J_&@c?u>*tu)6Y*wj2RI8pBgWP|I_}=ufzYT@qYL}H9qi5-+bPiy@UT#Pq5?he`@x}|EYPs@PBGN7XB}8{GVF>FK*`lsYi_I8Rq}RjsH{g z{Jy{bXa4%r(-yzu&FjJZKkZNB|I|D_{!h*E_&+uKd0X#AhH^Zeoe z;>Q1}@qYNfxLN;K&FhckH%m;>Q2QjsJ_gpZP!a=6 zHuLpO-CaGPXJ*L2Lwx(_lxM^!0z9 z-%GE*oAzosCnV?R9d|;~uk|qx8DC#+pQNu$cY0o4dY)c-{$6_i-QW|BPCQ<^vyMJ0 zv3i4>>V;z7tPMc8{LN zCa&-J0mz)*w5bo@$1pIe{y@e)4p%ekfa|>Z_gQ=+@3qMfAD|5KL60*|3(h! z^nY>V|I~#;JN=)!#MWD3{-0X&|J1{?bHe;THS_!Me{nPaPmMR4^VROg7qR}Yw&!JK zXPEyNH~uef{9oMozqpzI*YIhl|Koi4KQ-5n|BL(TrMG(H8S#JGju*uLsr#EZ!~dy= zm~X=WshOvC=&YN(@lp6cZO8ZF|J3+I{GS?ci2sWl|EFgCR@VPjvpy^9|Eihq$NWEa ze&O)o|J1BkjQ>;f`1n6H{*v{7)g$tA!~8!ro)7=0#{1#_)WyTHg8x(F=a~Pe=KY2L zQ;)RoQ~aO0WN`oB|I~b6;{VixhxQBpPdy?(C-^@#9uWT*H~!Dt?jQdbcj3+F`TK|a z>$Ch^Z{DBG|I_|iIi3Dbos&B>_&;@dZhr88aWnr<&HID-e`@Ca;s4a*@{7X!zqs*# zYJA{726Q*`3V$)ga1>PoStJp&-uCUUp_r6_&;r@@qg+{ThAB&xB8exo$C!-O!n$im>mn18qDTATOR)vQ1J!`p4% zU$h;HCj z^~_HHr}N_*!}`Bn+qvGb{%=?FeA#??zhBz^{h4?986)}cQ|}7%gkk;PuH*4MHs9X2 z<9%%Yz4s)0KJDMfc~3U)Xa9cATmDbiONaG;yUtJJ|FoUw|I@`b@2~6i!2^C}{f z!vDpM|5Hz~^-=ME>dCe~D*jK+`EUPyjeoxBQ$Jqs&Gq#^sJro+pZw=K-#*^v2flLr z+C=03bbjUs;{W2t|EW1Y{x5F)pBhic{J*%F|EE6r{E@-`sVAK`B7^^noB4lg_J7Id z|EcBw;PR)+qFOISBLd~)%N-@|4-i!JRf2G->&WQf7)JrVR7((>dFg>ga1>r-Y@h2 z)YC7h2>vf_=KrauUQ`+UpSozu;LLwbyVSRjKD9^ie_t-08~op<9S;Qmr*3K68vLJn z>+ZJT|I}fgip~F1GjE0Ye`@B>;Q!QkKm4DXd0hBEb&LIe9{;D_Y(5JAr^YYg|J2MA z!~dx_m?y&jshiD5;s4^s|Ecj?tpBUtY<>*?r*5h0#^@PBdR|J1DKI^~+d-gvjGRt@xKo+AG5qle}O zAGr0ImoxQW?C0C@g5NLglW6>(_Qzl0|M;B+>l@>*eqGzco9F-jw@>iqep&xF@07=b z55ynZe3nGx{~mbu@!$iwUe^Crb3gb$b(>uu{!hKb{2l&Jy~!H?r^W-C2l2<_^~L|` zdT9Kgx7{D}|Ki5~>3love(`_WPUHX7-2bODKK17Q@qapA{!jbM|LOUxx8w1D>IOR= z|EK2s_&+u0$N%Z|;q}1(#clJ_yxYy|;s3OKr@j98KQ%tje1o5#Hvizg$v#hOXTRY0 zN8|r=e+}kc@qfBM8vm!p!{YzcTW!5w{GWP_`49Y`n$Ii#&+peB5C0c8{x5F)pBg`m z|5IBgp?A>bfrp(tQ z+Wd`oi}^oW56!!=%m3;6HraeB=KrZT*m{3EKD^ZT-@9R>z1|mi*E}}YJlxsd58nK( z;Q#b`UOIDJ@PGP#$Te?*|5F!CC=LEk`~S!2X~F-gdzc5b`J;aR>a#Bm{!iOazxq3w zKVRL;&v*8B@3r3-9_M}eqfZ6@r~U7nJtz1-^yZP44Z@%;s@5?W_jQ3}|p0AV7m=^q>I&M#py*t;B{jE3iGwu2+v_Eav z@6G4M?$4X~ruaYIKlAJGf9mb#>F|GQzJKiV=Et|a^cvUG-FChBKRy0Vo8M=zpLg2< z*2Dd2qV0aY@qYL}9gkPU|EckJ!=5-i(RRPy^>)AbKkeUSz8L?f#`od>)c8L9Uw3!< zKlOGyAM^jz@_%vT|J2Rq@9=->R`Y)L`K{FZv+?e~SO}-urCuf9f5!zApYx zy~TVW^Z(SF?RxNk>W00~1^=gRGJlBwQ#bG1AN*h3_WtqhJ8ixy{!iQSv-m%C%bw>l zUp#Dw-ygky%`WdI^R@R^?MXEA|MYy+x3`D+f9krOJ9&Tl`L~#-!vE>W>x29L z)6YLY^WOD+y`NaR)ZWkis`UD;UbQ^4d)ol-hWc8*PrTRKysYoc9O7Nyven-2S>9`H z9$LxYvc1=v|FZ8NZ}~snPovGhD|l{%Ur(LQ6MSl3zIVgc9rpLDLhl;;^NIC;bv%v# z)AhHSN5lWATg-Fe|J3q-YW&~*Rn=AcyfE+XoBui58~-=>qdB=lq znc%(1=2hbVbpEC0&+vcV=JD`<>Xq9%{hylq!T-gL|5Gz>4*#e7r}2N@c0c&Pxb6Gd zuaEm(cIvs_JRkT!ogd$Z|5M}n@PBI7d&d8%dHwN!>UDPfPx@Zs=cn!Of8IPE{!jbU z_&;55oqc}se{tjgyzTRk|I_jEf9efQo&Ha~vANU#shPKj|BD;{r`MnT@qcR0hyT;x z=a}Dz|5ISlYs@PFzidp_}hYS!Du|EXDz7yqYbo*@2Djfckn zsaMptg!O-Q{VVHQga6a^HFcYV|5LB4@AQA(=9O9dR>!ZYZwmfTz0MjNr(SRVkN>S^ zy{T#kGILT@BUMF;|1}5+P=P~Hu%4|@qc=}4Yr;6f9iE>Yl8n% zYyO`a?}z_WuUgjW|I}+%tj&BnaCOz2H$7H$eg^-iX1*8xFK+x_-1t8= z-Vgt$#`pa?yThCLVyE`r!k9!vASIjsJ@q{}(s@ zPmQ<2|HX~}Q}cNEzqs*#YUah^|I}6HC-Hx3?hpSL_u`9R@%v+a)I-mFHPP3f{F*oO z4}Vtix;OI=Ck%hX8z0u%{|DaquwKW#>CNNg|Md9se`@)^xbc5#j%WU#8jpzoQ*(XH z|5LL*F#b=?>w*8%>rdnV)ObAnpZ2Hme`@x}|HX~}Q*(XzKQ-?k{GS>hhyT;h%kgpe zKW#s)vRCkb>KW$u@PBIgzqs*#YWY9)B%2qB|5G!M5dRl9{!h*OkM)1!?s4OPdGr37 zaOsEM%>TRL+`o9s|Hb!*|5G#X5C5n0YyO{_*Pr=+YCItRFK+x_-1t8=^Y-w6apV8u z#{b2Q|5MBV#f|@q8~+zK{!d-m<^STw|EY^gj|ubt)Wv1T2LGpK{oj2D4yxAsu^{i* z%q`;%_AVaMJCoDV-38{Os#YH2=dbFO^mLUy2PAyKh(1X#m2TD##{WHCcX053H2zP` z{`kLN{G-$V;qUN&$DD5_(fl9Y1plYT18#o*THk+E$|I(IUv=+3iR&GmTF*7Tz2c;# z2g~h|T#q*U_@t++J|^kUs*X->?|ovj2lY*Qw6yO_cX~cvxI`|I5uD9OnP2hYuSX*8f#AkMDse?%AWp>*4>@csl0)#m)M^ z>Jfwc1^=hU8{+@er9%b<|EDgp=L`R*W_@h@pSmDxU|9cGJuGWbnE$8F89Fe`|5Gzh z4*$3B%`b-ee>DCtZv3B`d6@V=wftY)_&@b==H>8z>XU4q9{x{_ufzYvjsH_Ke-Hl` zH~vqJ*Tes*S)UjGr!Fk)od2hm|5M|?@PBc${;!(#V)1`*|EcqGh6MkoX8s`lPtE*2=KrbjY4|@i+edG^(3^R8%>UDN z=Ii1A)c895pBjIM|5G!c4*#e3&jg#Vi2qZM9yvVtKkd)+zx>bV`0+gd%>UE&NyTNs z|EVVym4^9$>WX4p57PXfy0WA+_&@cTrKQ3Dsm~}b&fx#ltj~-8iyQx^t|%=G{!h(% zyYcr+X?ani@uKneam7g=nC?+U$@PADKgGxM{=@&ZxoXUh6Mgq7ZzX#E**{7& z{!jOZU%~&yjsH{Q&Hixz8{T*{{GYCe`Fi+2HS_iGe`?Op{6Dq)pPKcK@qcR8OSbvz z-H&I_hs|gA#y{Hp_C(u!cW->3&42gi@qc@Gvj27Te&5dXhyT<4()ho)@qcPO-1O1= zym@}`f7(vt|Ki5~#f|?{;{$EJexhyuzBls%e=~Qd_as|S7yqZ@c|81I-1xt^@qcPw zKm4B>pN9Wa^LY3_H9iUd7dQS-&EqrwPtEz6|EI>!G5;^_4GS7N^m)VM-LaKl#2T-lv>5 zGSlnv#fkoC$s%vgZ`Yn^`)?y}`9D3r{GS@{hyRNk|EHG!iyQx^9(!(a@PBdR|I|}# zeOmmVdh&Ti8T_BRVpiw;KXs{H5B^V`Z}*4)Q;)RyfcQT(^YZY2>XG*O#{a2D*z1k| zQ?ouV{!iWCJTd-HJ;+{9{GXc73;s{d=acn+^?kyZjrrzpekP{qcUx|5LNRFZ2J@qb@2B{!e}O z#Z{T6bFT99ooVy`etO*%-V?r25d5F^&mDhK@PFzV7gT57Z9TJtpHYYTa?h;`{_oD- zj|UIf{`_;n|EXKscLx8b=J!>s{~I^{PhD&CX7GP%=E30q)V22edHi48_&+u4$>IOv z#{a38nNPs~sh6Agdatmmoyc<_H)_PrGRpSsn275-0+r!sGm z=>6r#dUHLKJC5#{Rro~kfjs{<-zCxZ`(JOa&wfAb&H3?v->!cm_`x-HKASJ&+t=Cs z+Y9>|5G>E`vw1}^EX+~xG&?^Pk(UPzjy0?d4029`bVN|y~^D> zANw~x`hR>o>(w&Q3t&7elMQ*fcJqe#KlQGz z`G4w0d;j47)J^vOH2>j`$NLNar~7ZQ^}z9eYSyR3|HWc!u_Cip*np6@w*eDHtjYpO@EzWHu7^Y3h4srQhgg5dvj zzJUdme4qIC-nsVYkNH0x|FzK*g8x$wIQ{J4|8)GxGiC(;7dQS-`=5I9Qq40m&zSX=E{!h*O zi~m#Oz3_kPP7iolx%wINfp&iH{pRazfA6N3%)6Wa)Ber2J}&-G&HAZr^e6W|Ge#b&C^us`-ypn_&?un&p+$`s(HQe zf9j_FFY@`U)cdX3ydVBgU2D%j{!hKho`3uNdpFqe_&;r@@qcR0Z{DI(pN~fKe< zTkY>t<{=Voe%X)5@7ed8H}`Mff8HJD^O*mq`(Zs|{GVF>FK+yw8XwL4KQ%rO|EFet zD)ay1HoxnSzt6s3AAYUb`x*Q9B9pG#;=RSrkN?y2LF50_@_%vT|J0jycdq}duJ7pJ z{pr`Ud3#&%f4aV{w*EH$PrY;Vmf-)?TN|5#|5LXuo)`R|`mt*+5B^X6&C@3Y|EHcg zzJ&L`pMUhM3xogD`|pA~?hO9V`-x@2|EX`TX=S}^f4@Fz>j~rk^!J%Z%&*}8)Qiox z;Q!Q1Hf=HQdvKM`w`j@g;Q!Q5*?d;!|EZU*stNv2-C$k||EGT3JPY&x)N^f~7XDAY z+~#jh{+};b>He46yg&Q=dgE`H|EK-uEn6S_pZeaVw*I=U|Es>>w!4D=Q=fXnt-=4P z2TwkY`PIJvsOhH$|EK%E`g`9A{!jbQzw@rlXUFyR>uFoFHuyhXZ(VIY|GuV5?;qxY z+5BzqrRE>;f7*YA`LiPy4fXBJFZ;tK+1|{jGk@>B$voeGKb7al*KOGz{GYC`$$TCD zPtAJs_&@aq^Lh9`b*=q<1OKP%X=~jX{GWQe&4b&&rraN&d2j2luk>c#8~#uC+i0E- z|EF%U`GWXA^)mBw_&@auyB_?XdW{|btFe>3*LVJT>(__(!~f~}y)N7yqZ``tg4{p2q*_epvq)|EJz)kB9$L*PE}z|LJ&| z`G0DBAM^jz_&nzSshJOm|5LBEjMv|ek#%UKW*oD{9oM6|5MBV#f|@q8~>+XZ=U(n2N!ua)pYtl-B08CPXDLY z`oHSc_TMi@u3F~zw|af&`oB8=s&$>~|ElHx)GL;+3jR;Ma_P!2|4+Sq@$%sR4moFT z@PBI;FAM%py<**wPC)SCaN=6>*hx zPc8qa#(&}e)OarZpSoaFr~lLA=bJZV{+}A}#r(gx@qcmS|I|Dl{!h*I;{W2t|EW1Y z>;J0pcdY-b#^2%p;>Q1}dA;#}apV8u#{b2Q|5M`!@qhYxIgS6*b{?Pkf9mN~y@UT# z<0+Z{r^Z|2|J1zSnEw|y{!h*0;s4^s|HX~}iyQx^=Kk@2YThsSKQ-^CWvBi%(Jzkq zKizF!7ysw`TeJSJTK+F?{9oMozqs*#YQ7)ve`-Dt_&+uCM)7~@k>(Nce`@w;{$Jeq zKQ+D({}(s@PhC-VT$ukC_sVZ%s`dWo@n`>qDWum78#7kF~-(5I)zn?chZ`g@RZ|sNK|5G!+jQM|RJRts0jTglKdE5G*_`kUEf9f1tUwFf>#{54u9+3HeapV8|@y!R~|I{3h|BD;{r*sls7c^KlP9i*}?y*iwd)Y|5KNin71+i=WU)2{}(s@PmRaI|HX~}Q{&D4n0t-i zZ>f2)x6ZuUyQHKfv+vHUyo-yAGxarBdY6~j`gX5gk?8yWetDv=?bY3Qu20Xp+#jFD z|LJ;Y{GWPsaY68ZYP=xx|J2MsWd5HT4~hR%vp@b%jW5Ihsqu;UKQ%rP|EDf1C<*>g zT~SmP{GXcniTFQtetv%Ne|rCn$sZB?pIZJ;`^*2SdA{*~>TxAynO7>#^5=7OVR2^r zx6bq~FS7L)&HrhC`9C#&u4H~vpOep*)We=8qZ96aHK)3Q6) z|LtnLTUh_MtMP64KOK*!!~d!ACiuU&@qcRkA^uN|x5NL%jsH_~KKx(YpFRG%_f(tT zcl6TN5Ke ze`@(ZHP09RPc8o!H~vq}@%X>E@qcRhzqs*#YCIhNFK+ywn)BoT;>Q1}nO}(iQ**!g zKQ;G*|5I~5{9oMozqs*#YWyMoPd)K;TYujCpPKXCd0uOWnX=$x@k^&)*3#W)?7ZOrbUdC8{}(s@Pv>L3Ui_aL&xHSr8~+zK{!cy4ywq!NY)tgJcQ<(B^YDM# zpZ@2K>pM>Bzo>IP2J0v8TIbE{h5yt3%u~bvsqu*TKQ-5X>+scy#{cPl+1_W;O5e`? zeSG=~Z_an%g5}kHdfa&>8T_9b?}-0X;}!9L zYOVjP9%KFv|EI>w;s4ak%ftVvPqy{0@qg+`%ttlR~ot z5dWv<{eu5f^L@blKQ-6K`oD31IPz|9*864tpSH7JG5$}@{hYV)JKlJ~2Rm-_mjBcK zlg}><{!fknJM^HNe1H7k@Z)aquDYPq)+4yi8~=Cz*lWCJTv!?WpUyY!8)d=&sYjoi zmHEPhm-+tXXAH34U!K!pzvBy{fX3I30NlaBv;>A4-j|M4^GT_;~%{hZB{nXqO? zhkD2MPXDLgXupra|Ec-?6aG(Kx9hpgJ^Lqj95?szPLH?urA*&XCwb$c@PFDLAB6u? zv%VbuPmKq}|EXC|b<{zl{CqV2PmjkuHvC`Q_&;y+5BNVdo(un{#^?3@NkKsoU)N#s7VC{*%G~)!Fld|I>CF|EK2l#s8^!e(-CF|EK2tjsMg0&HEew zr`~MuZ~UM3=kf4=+Ri*G=KsZw|5LL+{x5F)pPG4__`kUEe`>Dh;9H(g^bvPF>(_(d zoBHk^Z}vCuRsFA|8)O#c0B%1%{)W=pSsO_A^uO- zzp2arsafwE|EK2tf&Yu!{++;H1q$|@_%vT|J2N*!vCoo+xG?kr*5)&ari%V zvu%I>x=VNK^Vn{`PybfM1>Rfgo6WP+7gg8x$=I&2_5wO!}Slvd$=yuW7tkokYwKJd!xg8x&G zd)R*8XY>EmvzOQ6HNBU$?8d*f>;1%ffcQUkYg?!PQ?J_D5&WNez0E5#zq3o-XpR3< zx7hqM{GS>>W&7_`tk>H)LUM_EB5x@Zs)`QY5O*NKJkBQ z<`uI3Z`}AlHT#=)>3)3ke|wLb>|JlKKmJeGOXL64{QC#|pPIj4;Q!QkLHwT@?}z_W z^M0r+`EI5DKEnIynEZRZ8_nPs4{qTQk=AYvK)U9?t{GYnPd@TM?&F2OG=htKF|Kk7R#{a1s?E4e{r{?<=|EK2s z%>RoU|EI?L*`IIT4SV+R{`B6_<^ObjH2zQBV&Biq|5G=cCu07ey2I87X8m9Fve~nP z|5M*_-9^FwsV|;6kb;s4YNH?{=- zr(Uq3Iru;IvJE!R&-|b6pZQz(KXvokjlutE|BXvm1^=ghWbWg^|EaIK?)u>W)RQhe zKlnd&`RUVw|5Kkl^Yl#r*L(W)-u39i!T)Ld>?fZL{!iDls+xp9| z7kM+U5C5n0ZL@iM%>RoU|EI@i-W>itgR!Hs22a zr{h=Jd^`M~dcAot{GVPQ8vm#FXKlmQ;Q!*r|EV|GcKn}?ue0mH|EV{c2gd)Y>l(KQ z|EI<;;{VjFkBk4)_2K*Qe`@(Z-7n7<{!h(%y7)ge@Bd3qxw}e#esO>H=a+Y5Q>Xva z{tf2+nE$8VVC(DR|Ki5~saM(g@qcR8+r|H>SwENcf8)mgspbFT#{a4D%lJR_3VS~A zf9h46HV6L~H~vq(!h9h%PR%?({UEz%==^hpBnFX;_thA^~!Z&{a;Q!P&U3_8ifBO0Ig;Pp`|5H~D zJvPk$QQj0&)a+u{!jbkh46psu@yan|BIXT zf7Q(U!~dyE%57ei`9C$j2LBf~{!h*R_&+u0!~dz}|Ki5~spbFl{L%P7HNFb}7dQS- zU26Z{nE8KkGyhL5|EHG!iyQx^mj6@Z>+pYSw&VZQ_$}uDskvU(|BajVf7R^I`oC(f zkNJOkKA0!R{697ORHEx95D4=->4IhxbTZ ze;EI#^W~ej-1)_S`gXn_27Q`r{Gaxh|BL&IAO4RYkN?se-%pDT^pE^6cbN%1A@qcmS|I|4-o$LRq znGcBn`~3r73jUAA|7knx!Lt6Zn)z8z zapV8gMJ4&c|EckS_&;@CQDN|Zx?dXqr^W~3|KhGU|EFdi8~!hD{GS@1hW}Gnmz8JE znQ)mm-f-NtmwMyh@PE2K=F2hvPhDPF68xXKpt3mlKlKRveFgqcJ+Y)H_&@b{n{R;s zQ{xTse{tjg)MJZFga1>HDJsd#8u$&r-r*&MnUhaB-#gdl*)ji5_ls9!{+}A3$ojuJ zAFl`V|J1x*_&+t?691>;c|GudYMwv*pZ4eZWBp$>^8s&v=XBqn#{cPf8vm!p1LFU5 z{J65>%(U4v_Pktnc=fFvzo;HxUXu8}U_IXW`zJjQu(~3-|LCf+#QteN$h^zkWxwgL zH8F$tW4&nnpPJ_j|EI1h8xZFInV|{3Y22u+jQ#tQ4)w@W?ep6IJ?{eZdH6paUo;~( z_&;^w^kKpOsmDyu4*oB0{GWQF?a%zb$#*Xa{*Mmp|917{>A9IvIY0INY5bp#m;Z|! z|EI=_;s4b5IQ*Yl{!h(3KK!4W^W*>2cp3bkn)QY8e{tjg)I5Gw%PZbIKK@VJd3^j| z-1t8=>+$0M)aB-R@PBIjA^uN2#nunT|EalN=KsZw|5I~+%>PrfKmJe6_2d8I#{b35 z{695b5C5me1L6PT#{b2Q|BD;{7dQS-&HBvvKQ(?4{}(s@PtE<||KiS+Z1wju_xq!< zTN3^MP<9{Cb(H7c_BSMyKnR5Dif!DHWy`W`b;*rpY%slp>AeI9H8fL0$KY;Ry-SvR zk!`sUdO8Uq6%HYtoInCO34!FjuV?#z>zR4Kb^N_q>#W1IX7=pavx`-Jx}Ua_*LdTN z@PB$g(D*;^UH(s9Y5wo?d%Jx5Z1YR_KixlG5C7M@e_rr^YP=o(PmP~Dw4kl$(Zd%9 zug83|*2%5jr`deB@>wn3r`Yj-cuuo7-tUSlni7rw)A8_A_&+uGH|)uJZ}~r+kNjWU z_`kSMEUQU0{x9B+|5H!0^?dPv>O%8;_&+t?4*wT7{!h*Ny7u4R)9w1$_fp;^=NAP3 zr~UC@_&+t<@qcRO>*4=;J3rI^t>+Vs|I>EXqs9Nlz4)KcdKcL|zZ>^T_Vlklt;Ug%{;%!XMfXswtb%A|MdE!|9Io0 zzMc2?_PZbP=JRR(qYrzJH{ZwnKi!_j|EYOD;Q!*r|EcBw;>Q1}@qYL}^(1@#@PBI7 zGsgd^c|GF))HCe)WBy;<%>Pp}KN0_@mj6>1UsM$QpStwo68rhZb^iEgTvTf79bDr* z^(=e7HeKaier9g)f4cpRk6je}-`VS)3;u8G1K$Y#@5Qp`g8%z`$Clv#_?vY6U(dFk z!T+h(tkMWlO z)A8j0)OaxbpN>c4|J2N5!~eyN|5GzR2>%!N+`36UmkoV3ct3t$kN;D1Jp7*;uZI6q zZ?ySn_&+u4rQ-k8cqIIv8ZU?cQ!_sg|EI=N;s11gcsu-`y2tj%|LJn` zhhhESQ}3M@eBXB4pY?y$TkUxGKQ-4I|EJs2_&+t?4*wT7{!d+P$HV`rYwddD|8%}Q zAOGl+>Cx-I!>&*Mg3q?9x7hW+`O|-RZ?@N`c@^(kJN_p-Kk{Z?;lz>u?ale&|8%@| z^LqF{HP7!qPy2PE@qh7l{9oMozqs*#apV8I&ClWg;>Q1}SDUB9|HW;7!kg=X|I_v2 z^^E^h^M1wu>H6XwZT&{y-h`*SWR-WL?a%x_-M-42`G0DjFZ`c+tNA|spSs)pu=x}3 zI-6I?{6C$4llf2lpPJVT{x5F(U8XnJAOENAyua{&>J8>!nE$87$Ke0e>uj+T{9oM6 z|5M{#@PFzKn-_@x)BBP2=kR}Oet(buQ*X2N#q9Upe*2A$Ey4e3dv#My@PF$0%N7Lx zr@rgiCxib}UvkH-tUvC@zxIN&ga6a^Ij7DF{!e|P`3ctlRnI>6?BM^@r<{APt*5rH zZ$J0aON0N@_KUB$JTq$lkGJUa>e8#O%#2w18}EK|?+yM>`;WBsdGUX`UXvP{g8x%b zUa`{7zhjH`f3R(po$qq*$8EliJ->eYWj6l?|EJs6uGj z*1N|3y)v(|MX$fwtk>JDUTNF$f9kCFyV9HWVex;y-8>urQ}cSl|EZY|i2u|1vK}@5 zPtAJO_&@Ex>Xp~+@g7vB?f5bCCEhFT_RRnD{jy%h?fQ9dwEfN7CK~^z z`(s`p{x5F)pBj&c|BD;{r(R<|8~+zK{!h((Li}Ic_ISP5+x46M)DhmB?f%TSd$ZoM zc^z-o!^QvUdf*N5e`-9U`551S^~+iRr~6;^Qr7>eH`v!l_&@bVTTj>CzvX&;;)m`1 z?Y;HY?*;#-{oBoF;{VibHh&NQr{?*`|LOg+&OVRue`>rb{!jNun{V*O|Cv|tUSr2M zd(hipSO8G{9oMoKlS>a9l`&pxgPjGHS;j>e{tjg^!Vy_&Hqz3*!)-g zpPH{H@qcPOHU2Md{9oMoKehaydd2qb!T+gyY~CO1|LXjh9*Y;Q!Pei=GSqPyOT_Ukm+1@=zgUmg=H+@b?{CcOBmMR@_U}3VPq%Nh?f5@6>&N2%yw`2W zwC*u3(fB`IAHF`o|EckM_`lvZuVwx(?!EUZ^5d1-{swG``i3??+){g zHXq)b`@{d~`r!ZU`%B+WU-9GF-b>75+25ymFE!7G|I_Vj?dt*jpSoe~WH;uuMd0}{;#*!X1-W|S)%cOIvzd_|EK4V zo^aB&-Yw?&o*Q_5qCfoL2Jd#8pNap|?P>gW6{69Uu4%?3ZQ@7jk@PBH&AO26T7akw}PhDeP@Z~;p6Mfsidz;&jc>h7) zPUHV{e0(4NFK+x_-1t8=^ZM|A>Q?)E8|MGTjsH{E*?Q&pzqs*#YJ4B_|Ki5~saYQw z|EI2RUy;GO>G8||sW~6~pT7TRJ>RZd>}NA=&jjCx*Bf;9JnyEqj^O`%duw~}e`@(Z z9Z&vG&HC*4Kiz+o`9l1kn)S``f9l$%whaDHy}Y$8_&;@3OKS%Ir*5*(*DrM}^T*Rr z(~v2CuFAW*rap7^ZOgr@Z2jNk-&*dEZ`so2nT_4m-isD43I0##zhvR!F#k_owPac5 zybtUAc&+nZ2>wq$|NO?~R|fy5pC?~8t2FpO^)Vw34gOC(G5_G;|I`(w{e%BgPuS)E zhP}Kf_&*x|r^e6V|Fl1i|5G!+kNJOb@{x5F) zpIZJ;jW@&psqszB|I_uuH{t)(+#dg@#!KP<)c7m>pPKo3_&;^tlmTJ=-?*9or{?ze z*S_lKgWvk#h1b0CdH6ry-x~iHckYefPVCS8KRrHt8T0?*#{b2)fA8JzCmR2!{Yxtb z2mhyLz2(cczUljqviWta|EuF2J$X==|EI>!;s4Z}5B^V$55xbdr`fza{GXcr@qcmO zvHE9zejK0me|3H|>;I}bKK@U)=lJ+PHT&cL)I7h;|5Nk)%r^$=j;FM z&HDlWr~SD<=Kra4EBgfhr^b8Y|J3-pk8l60ACI1M?ccn4Jm0?XWABQxewj(9e&Wq` z{GXmL`9C%9Z~ULSu*Bv`n*URCfB3)neDHtTjvvJT#XaxOpLv%SAD;RA-Os)8e)vD_ zkMG0(#a-AhQ>o9t357>wI-gJW&;$19-9E8@@PE4fxba7X^?%j*WBP~nf7Rng_X+;b zduVbVUD~Imd+brkd4XyFhiAk8E&N&5|Ka_Z{}(s@PmPbm|HXayE7yAu9MmV_A&wlJ z^or^8$s3mRdTAe+o>z!hjD5zWp{d)awx=I&dOhE?_e*=dbf?$P-Cd{W_oY2wx_3AK z@5sJ~Bp!cyz1_6GOP_yw{$cw5#~hwKe!A25pYHVjM<4pt#QElo7@6qN!;A>QaP+9``oHSjG2=4K|MSkx4gOE}hbP4UX?xz$V}t)wPaHQP z_&;^U_({S4saa3vq{r^|+m9cU8~mTP=jDtE{!d+)dvx%Bx_|s0{x5F)pSpCs{XX0L zpBm4E|5Jx~X6FCY({{x5FU|5fAD@PBbL|Id4(t*>YPPmQ<3|EZa;cGx>N_~Q-p z)%NLa&X4(j{&>x&;s4akv%~+XnRkc(Q?uSJ{x5F)pPG4f_&@dWWfj5ysb@~D4E|3& z)jVC^g3En>9uNLckEf!zB(wK#FYVo4TAKOrfZk@F9{x}JsRlRlgIG&ZKCb(U%boA>)GGOc$b?`!~f}gn1^@x;XhAw&XAvZ<5BQ` z+MmY%#m)S`xbc5#yr6x5;P+44_YdC8D=dEPhlxJm$3O7KkJDD2 z&Hds3)F;f&&i_;6Bk_N69|HX~} zQ{xHoe`+2N{!fjU#Q&+8Pl*3hbAR|hHTQ@AQ{x5ke`?Mj|EJdczqs*#YWBzf#eL@B z4gUOa|2bpUdvpKzKfRu5{9oMm_lG@y{nC=)?eI-Ees5Kxzxa!l-uOf2|LOLukBt9Q zGyl)lNAPAI8~#t*r?+Zv3Bm{CRnqO^fQh^Uoijnblb9jR*Yosv7Uf=CkmBdOS4#FK+ywdaT_){!g7} z^Zs7{aB1Rr7k<7Z(YCMe&;8r?D!!ezzg_Y^?yQL!n|+?>W6BnIheAs1=dGmh8|7kn#U;LjMkBt9Q4?k;s=IZAk z@@DFYf*~-{8k*JN{3Pf93^6!T+f%&A;RS z)cE&beBr#FeX8aK?|1Xl*98Bku3EM@_`lUd?Ptn1|L>)5?FjzwyFYv`_`jEIy*cLp zsWtyk&H7XLKQ;4N-g|at4{O-q{qQcWr_bo&XW9qsd2J=W;`qmp_incNFZe&--{ukF z|KhgaFD2T3|K!a)GW?(Rr}2Mk{1X08jbFn5so5X@r^YYg|8&0ce`@(ZHJ%Rt7dQS- z&3dc&KQ;3M@qcRhKehayn)AW`#pj3rQ!}p&|EKFuy>w2-$a|Y@Md1#&D#$1UT?l(-baUcuV#Jcs)POYN89gzz43$g`(bZ9ime~l z^QS*&{UGP_-){697G|L}k6X7j`NKR;i4J>vh=yk78sapV8g%wNR+ z#f|?{Z?gHP_&@cA9ohAN)p!*ApPG4C_&;y+V)#EbUJU=I*9*T7$N$BR|5Gz>3je3u zGatl$f9~5GJ34~@)BZKh&B6bvU#MLc{Ga;XCmsp@Pkr_M_Xhu`zUa1Fga1>Xa?`cJ z|EW*A`TF4h)U$5BCHOz}nRkD~e!siNR((EQGWY)A|I}AJ@=)-9>a(ADHZ$~$pKMXj zS-8j^-)mcRytxgX_INgXKeMVk_&;rb!8`>1FK+ywuGcd22lziV>j@q|?y4>Ne5u~F zHTXYulX)flpBnFn|I_PD{!h)nXZSz0=Kra?!g|2J>sGHe56J)2>&;i0hbz(fW&4U! zbz9F%!T+gQPu%wR?R>uD|Fj*?ivLsNuWa6u_iFQI<`2B_efU4^PvigM#{a4DhvqNK zbiJ9!XU|Wf?fLU&KHYEjeLK~cUz#IRD|I_}fUwn!8m){?4??3Mq z+ja#1r~PUCpU!`!eSL%fQ!{VTuD>6@-R=+nr`yx`KQ-rr|I_<}d3^XkHLpMXpN^0B z!~dx{AN-$s)y{7P|EJz;kH&(v@ zy?OrkU(}jt{GT3QlRbaT|BD;{r{?QN{9oMozqs*#>h>+$Z9dsf@6KK8|7!aRn+ItB z{`vNeo3;f1r}rbx{6F=I_1XD<>Mrwu%>PqwG{1%aQ?FgMCip*fk9iE6@9W!Jo}VB5 zpSC}7=XJsV>GS5Avri2EPrd(?qTv7315cX~{GWQ**_Q?x^p5Xt~Uw`2F;Qyvx z`F!|$i*G!(B=|pVzy66uVg8@`u0@T(|EU+)dW-h=6&32m%W8uEQ`c122LGpCYW{-t zf7N&m{GT50d|RIp|EGS`*5k$hsc*RK;^6;u`}{Lb4E|5sN6wfW{GYndi50>Bsb}4P zOYnc{#~yt=_&+uCsPKR4g*JZ>|EJeSjd>sY`nf{ykCu)V!T+f{?fJ$3sq3syyndv2 zz0J$R|LJ(GtJVhpr^e6W|J1Cni~m!zzV0`_m*?GR$GfU3-@9qeIzF$wTg=OiES{8T z{GX18r^ElnjsMg6vmPt{PtAI*_&+sX3;(CaAL9S?`NR3(|Ki5~X@9ok|J2PkKM?$QixJIpIS z()DnnC(VDvyTv>&{!i!AY|k(LPrbt4@AyA;XZy+w{!fkH!~dxpJ6DGJf9hKMdldYi zx~8)$ga1=En%~3!sT*wm9{x{{hk1M0HGRJ?|L5J-8T?=6GtUP9*JA6DXjxV8f9m;*v;I%VTfAs#X7PiyzW)+i4|u<;>b#qG z`9J+U?7nNR3;s_(Kfe0(6N3L!mkjS0{GWPk{#V2LzXxtwoSpAyzK->O)%c%d*RQG2 z{`9KWwcgD4!~bdfRGZg_|5M{{@PBI7^Thvoo8Q6zsf*3~;Q!QkBj*39nJ+i)z0H1p zc%}Y7-r|kN+WXb5-uSA&cK3MW!G77f%^RPE|I_uO@qcQ(75*=7{GS?Mh5w5i|EC^5 zbzty+YP=TyPmMps|LO7J{qTS4vT6M@XFc|MqIcf?hBy1;|Fl1i|BD;{7dPwws_}LB zKb;S4zkl;){aO3{ocCl~Ul;$U{kdNFKQ+FM^?%jukN;Cw+Vg?`Q_KIUS--dTjko>$ zxc>vT{WQ_|zxe#|e`=n8{9oMNPyRB|BkuoIqMy6v9dBMw_&=Qw&(Bro{+DlO{^Fan z-t*@5Q90$;iEb-+-<#`s*r?xlv;PDAf1BtJzVbV7?*HsPfA7up+4)Ito{yWiYs{Z25<3IAb554h&-+bsJZ;p@u)A4Bh zpPKcJ@qg;+_W6SUQ{zeTe`?RoU{}(s@PtE7a>_a|HH2zQ9@yPf;HS2}r|I~aw z;s4Ye5C5me1J0fDAOF0-3*!Iu`IuAMH~2sG(ItH{_&@ao^M8vU>FvDyK4Jc!wvW&0 z7v}$|$BZ~E_&?o0er?gJFI1}2-fwq}_lrG4-oT{KV|`ux-wj=Rhk1akuZ#avvp@b% zJ@Kd`!~8$>sG&)pmtLQB-0;E4`%kSGeEjgF=Q}oayo#a8d3EVduP2=D^y5$aw?X}q z>*1z-U3#8fdOqI&tG`Qoy!7*t-k$b+>G^x%hbE6VVo-AX@YFoWVIz{SFFYXr@8F{Sg8$?7ivLsdddB~$IbZyrdf2dG znPay;;5~Zu=*;HXy?wOJ=Nte2{l1-ffXx5X?b$wX|K2Xl$qoMR#Q9$ep0GIA)<3lQ zf9is9dBOjwCyX5z{GS@%$Nayzng6Fg*1RF}|8)P%6U6_i#}a1Q{%Pp ze{nPaPknl!&9D2*Eq;IWJxBC5zU%7Bn|(Wd+Ld2RbmcQQc{5LK^oAR~XWQ}ce|kJK z#*eojF84O;MT3ZD-yb{!fh;!~bdjoPx2z|EY5)<%Riw>Viq*Gx$H<9>0hGQy1pj z{3i2%>Ph4C!~8!r$H)JvkDibl{GXcjiSd7Gye0lm_s{ia{-2uliSd7Gt{?tSx0nA@ z<0J8Z>f(Zl!T+i8kj(#6^Zeoe)FTS=ga1>HE}R(V|LOkmo$1N(yynRAha)0JE z#@j06-T%y8{!cyP^rM6SQ;#}x4BvnF{_=m?ju*rKspbE4 zf2^;G|5ML8-MozXKlKb-51ILYYOVhpH~vpuXx9_}r^YMd|J0lh{x5F)pPKo5%>RoU z|EK2m_&+u4+uHY^{`h8{KA!JSz41hQw{7>v=lyKmHg7y0{!holD?ap{t-c+fbk0w= zcys?_f3rE!_&?pA<1znF&HZ)kyUF)wp4r?(HzpeYr{{-yKWhv>-|(Jrb}m2v@W%Jy|8#$>4}9iVI(<9+r+yvY?2rG`@!5|5 zi~H5zweAnLRy-zm(HgEIzP+c~8~?Ze8_T_!=T`HRD(|s&{E6=`^UgD0i2u{^xV`Zr!Ke0hyPRaeB=MrJfHYKHP0vhPtA7xpL&9=&y4?z z`}Kd_?mh8B`}=}JZcFr$IkzVI)u}go7tSfPzc0MW8}Enz)A1|j6lM1M{%E6ux~z2{Zl_;~!^hKHWduJ`-&Rjhy1Q@7vq!TUW~wIujI_1c$qGC#q$Z?WIs z;{Pf(%?loI&BiUvU-0g<^?vbx+P=y>4E}Fa<-Dx_v-w!~Ki06p|E;v&=i~p>Z987c z{BGN^-pu=Z^pok{c%~6K(-QsioGIS?KK=3qm5Ijx>HhIi_`kUEe`@Bjy?0%a-yXk( z|I_)^n|~T&^Z(S1=J%NYr{?&FbmjH%H~OrM2OxXr6<)%EML zO+|8zdw9{;E2`N99G zS)UjGr{;R#|Ki5~#f|?{bH4b$xbc5+ zV*X#;_&+uC)9`;fpUrl?@PBIgKQ;3x@qcQr5B^Wh>jVF%?zYb-{GWQ0eSVpj@@D-^ z{GYbd_&+u4f#Uzvcr5&%p6{;pTY~?K8~>+fJ$3uM^={wP6a1gHFSGeo=97H;BJ(Kr z`+e`_t5*mAr~Ru|tqT56UES5iJkhQCJX~g;u-_jBdM|Eo&n(`2xc5R^ACdKcb^C?( z`%vcpsh6x|zRMoI|044T%>UEzm#*6w{GWP}ttXHFQ!n1QIru*vkNL9rKlO_4ZNdMk z8?Etw>Spuj_&>ki_V1CcZ@WdW7uMUw|JlssFrTz;$BV)Lshe#c9R5#TXa3XHD^Ik| z-`lL?@$VV_PtE5Y>;HP2?_>U7-1ZG|M(2k=#s8_fz4?GrZ@WG7|J2X@BPH;s4YeAOENOV?AE{pL&H|AA5g#ciDFQpSEw@_EPYFY96m$ zf8UPxyR`m#?>4*t_ujhIoAr(He|mp(+Uo)Tr^c7s=aZi=z7+qb`&(`P@2vlM!uMZm zuXpnY-ka_9y`uVg-@kk3OXhtSdatqf3;s{ngX@F;Q?K2;Blth{2J?>iKXtpEFaA&6 zX^$8Gr)E3;FK+ywy3OV(;{Vhgc7FIjZ~J`3|EXJd`9F2nmhAe!apV8gtL*cW`G0zU zuGzdb_&;^0eV#J^PtE$L_`kUEe`@ys=hxo#-e&XT@PFFA**u4R9(b==vc%?n{mFaj z+_{+#KlpF&yRW}8_&Q z_+$Az^)9ZQ64w9K{$uU$kD33c9&Phzng6HjH~H$zg8x(Ba`TPB|EZTQSs47Ex@Bo~ z@PFzJ=5g?UYSzod|LOHWc+(ZocLt}XP&*L~@RV((7-_ZI)B^OgTo zQ1}`FjZbpPG4p z_&*&V&yW98H+E+IpZ0ICd42dlHS6)>|J3y>HwOQw#*?xBudXlN4F9KYwe?*ezVQOT zeT%JMjsMf_8(UWe|EF$fSsDDFda2FB!~eyN|I_go+jjh4-1tAeKJkP2zqs*#>UQ&X z_&;^4c|7L-shL;!=Cil>@oD?|)SKha8*{sNjjbn)|I_VRANR3EcY8P4{Jh^@d5?F8 zt?!Nh)A@JW& zUD@)q-@eW~9sbYHuO;jM^!YFnUPhaZii?{y!sAb-GKm4E0 zcX?gb|Ea5L>%#m$_2R1P;Q!PM%$JXfz>R@PFEWM0vm9|J3q-YWY7k^SSVUapV8g ztk;SEiyQwJH~uef{GZORpkh$)f9k?1M+N_<#*g9u)Oa-fpBle6eD588eEi&V|LkqN z*1ta3>D%#K_&@!;QvNS){9oJ?&Uz)$hpu?VkH_ute|miKf9mPe2L}JAo;J-qnE5}o z{9oMozqs*#apV8gTp#?O&Np~F^M7jm7XD9ttgWYu|BD;{r)GcrpL(`=v5P+XvESdx z75y@Ay#JOrzHQRmKk>$E;{SAh$4wm&{9oMoKQ-rz|5I1k@$i3YJRts0&GU)>Q?nia zr^c_@?_a&~n)p9$r}2Mk`M`QiWK#{a2#y!b!$?8+g*|EXu;d(Ho; z<^STw|EckLBisJR&j+7(aMeE&{qJY~ndm>v{nQ)(_oJ`>%Nzf<ss^e`>s6r_KM18~>*sH!17?)H(S_1plWVJ?_Zh|J1{d?wk4a zuY3CK@qIU4_k~2q9$|O>FTGxEy7O&4Vf^2;hxQ5nZ~WlHga3;g|EHdCRG;Ag)VrJS zmtOC;XynkOml&1olTto#>hR>exXPoBO5DC+XwrA3=Le>*&xn49C2l|9h~&JwwEs){ zy4`ioz~nr{;e-1n?l0}zn7L$Us*v;@PBH&81w(s ztl!G~KQ%rM|EFfY9R5#zlFiq{|LOitHlKz6Qx{Fh`adG(AB|J2+c{!h*N*7!d)uYczMsf$V`W=c*!CDHNcYkGa( z@{*+YORwk4de8Cgr&UxY`uK|EcGeq?_pd0QzL7D$kmmPC-nE$7q zGGkoue`auk|0_8;C-^^gnXS)jU%&QvoA0x)Z@o)xo}GRD>&?7B`})|Md4O9lw0VEK z&IkWy^R*L=|NHuHmj%Cw7qt1@zMXkh_V+u9w!iO5w0-^WjemJ;zaRPi;|GsC;!SVO z|I_*4Veo%y{NK;ZzVG|f_Wg@D$9wW0Ht%oO$)E_Tx^Xn6h|BLtU+F|qlcAY=I5C0c8{x5F)U)+0s)a}jv{p2&7_qXeK z@_%YPBK|LK{GXcJ+usNJ`Eq;v`$2CWKmJdzXBz*fW<6j0U)=aVH9imjr^fH$|J3+F z`}v4B$HV_=JAM!U7dQS-&HTVMKWpvz?ee9;`!PQd|EI>k;s4^s|HX~}Q{&_Ce`@Cc z;s4Y#Y~I_{N%h{$w`2aF&Ij*@|5M|&@PBdR|J0lx{x5F)pPKn@_&;@657_*l8Xsog z3nd!=r|mo*{9oMoKQ)hU=DQ30@tkmGUgqLI&-cdfG5=5d)A&C%^B?hl>T-Mi;Q!QP zY&-r>oooIL|EI?LG5;@a{Ga-yGqUUd>h(JFw5mUE8=JN>ur{?nv{}(s@Pd&_DzxY4(2%F!B|5MBV#f|?{;}`LN>gi`q2>wsa>jVF% z=J~|`sagLR|EDg!z~)1m|5G1h^Z)RFYUcmVx%L*nzRdso=0jgg^qQ(0y^p(~(0(3q zz4!4KX8oU@pP6=h{GYn)q!GdYsmIRD`afIaE%?8iZ2q79e!9ng=NmlV{Mu@MKjOXN z#q9h)ZSS_B zEQz*f{hw}+2g3iUTerOu{GYnr{2u;Ky~*~+|M55Z_`i+jo$!C^b#^|d49xXrp4?5R z=Xm1*@qaoVjsMg6;-i@Vr^dVC|MdLemGFOR&L97$#)IMi)Oa!cpPJj_|I~OZ{GXcr zXYJiL(Y79_cY{5DPhEGIcZ>Op71f7$v;HOi&t?n-Z%X6;)bf97JO=(xjqjZJ!G4Lx z|7kmq7yqZ`@!-~{_uZl*5k(isqsSizqs*#YF;n+ zKb;Rg1^=gRvd3rt?cHjRAOENAty^9W{!iVp4PW|A-_H9P|EKLV{!fkn!vDpM|5MBV zsqugI``_N}Hs8vApX|?XYj+Qy&)yvyw+8>G=bz74`~7)hJN{4GvtF*$yTRt~m={R& zfaznl>hq*__4?rd;>Q1}m)iUy{GWQ6dA=i_KG3_`Zjb-d{nPkA?N8(X)Q#rHS^w92 z)2876)OG8b5A@m=9j|8Xy5RrR&6~Fb|EI3s+!Oqtx^e6F;Qw^JSD5Ev{-1hP&vvfA zcl)+&!T;HW+Ta0Ke(PK2`Es}D_0?wH$Ud)pf7<-rW*u*n&4V=0m>(ln{ z*8VjAQ?tK)9+c?(@oDD6O4WEp^LE~NG~3@BUuVxpnXVsg&#yOLZOEs`dvp5{D=+t6 zXP-CtKi%JYdwt{o)NIH9so6eYdWYX0|2C+)+Zzu!s-o+blZ`ZT8?fmTPp+pZo?accd`=|TM_4NY&@5B2ZO7yBjAM13*k-d+b zGbdy7lf7qLb_4U3y^Bw~fceYb6{nxY-)DFi&YEq1Z+?Jxzlx&Z|8#zR%L{}5Q}4y! zr~moj3Uwb_&lmrv?svwi!T;&}C*E{@@PF!i9(p49KlQxDHNpR>Sx<7xodf-RTFqbL z|FoU;FY$kRJpO{g<29!~dz5m@mWssh8RFXJ21=*V?=}{GYCGjm@LO|EZaGhyT;--9$NInO+Lo^1|I~|ZeQf-ndP&<#zW(sz&o{4!|I_^~u-oJR^!i-VyfXMd^)j39 zhyPQzS>ylIEw=wBJHO_~tGCAg>G%yTtAhViFS7f?|EU+-4FK+ywn%m?5)NS_u#Q(*O|5FFAX#P*l z`Qra{e$4yB|EW9d{g40C{_=luv;MF4ud~mSeSZ0*?@w>o`BZN=w+H{H+spr{@qNty z)4%7;_s0LJ@qSn~{X9YbFYeqw&Z{WfdtSvw-B(vKukXn3KA-5D_nPmwXZw49=x6IG4zOEs2+u|zk+M2BY)Be@Vvg`kG4`r(V1$>;K}$|EU}2F9`lmKM%X_ z#+!owQ(t=4iNXJ=^G9Uo|EY5d4i5AG^z-M5=7E_1r_L`M82q31A745k_&>GQ|5YGthoZGBn%pUzMIPhB*1Xz+jP z^2x)3|5KM$4h{a#+x!*&Pv?VQ!vCq||I}>9|LNzQ_&etRsquUjue{{9XM0=s%ZbMS z>3H&gYW8RTpPKt){$JeqKQ*^!{$JeqKQ;5)@PBHKkN;C2XV=qyzm{m$|J8PU-Rhw~ zOtk&}F46Y;y+nWfd2i$Q@P9hqu~Yg7|EFfYA^uNYK7By&f9l{7ZT?@}_&+uKerW`F#j8n21})BAz>eE2^#`{Vz#KaKy38~+zK{!h*E znEw|y{!h*MG5;@a{GS?+hyT<0$p6KS|BD;{r-q7vlfoUU<^K6OI3ix8wiR z<4XEw^2TN=4;r?#;)7G}sARqJW1D+>T+tC>{-5t}ee>cyeE)*H!!nN^yr=j0+=DY! zPxN-~&_0NU4z{1ZY`;(cm!5w&VQ|uyRiyk?xvk&J{J*~E z>>E5Feh&YqW*#By|EklzF1^0*?&kkZGf$;+<^N9~nOrY6Jqo^=sjWdu;Bl+eT?}%=Kq!bG3y2KM$G?<8~>*so0k*(pE@r; zyZ&$7tpEGyg%0eRdasK|5J|}pI!e~jfZ3YpYC7l z|EkAK$PfNcom-Ige`@>{{!fhu!~d!ATKGS|zj5P(|5I~+%>Pq!KKMU1>j~rk;>Q1} z@oB?quitjqllukV$Nal-uV3fQ`QiVxo#WyE)ObJqpN^;be`-7${!cyC)|18mshQu0 z|BD;{r{l97|EI=6J7MaB-qnKRm}9 zKZyU+?P>gPs4JHL=~p+A44i}N#oIpu;x|Ll(Qz1jce>hrwub#|EC^XR+9Mq9#fK> z=XZQ@((Bp`0Tvo$t@|0^%I^+;#E*JI`;_`bs9a`^ia z@1o=F{rk~7JwJSIS@1>$v&Upg{{1WOiM#xtZqNFM_`kUEe`-7({x5F)pUwy0hX0HE ziraqbE&r$O@_%Z!CHF4<>z~nU7su8 zebE~ahyT<5JRbZ0)3@{d;s5k_@rU?7HP-|G7vCQLr-+Lt*|EK*m z|1WO*U))7+F7)$bfBc^w59f>jQ|FvHHuyi?e#}|sJQ2QjsH_~eP-o6zbobtOd*_?~`^}&`y_pAi zK=JL~CFd8|-}8OlyYzyI!T;&{;sf!2apV8gGtRU1g3bS_PdvXc%>Ps40r7w8!dWAO z|5Fd1ImFgexWczz_Uz@s{~h_r3&Haz~3vpxjp{Rk8i(!Z`h+O(fB`Y$8RzJPmM>y|Ebs5@qRqHz>iOV ze0#okch4)q|LOcUZGAcTKQ-rv|BD;{r{?~jd17>;?>Tvt-#?EZ|EKGV-(vk=HQo#V zr{{}#ia)<^h;Qfkcds4fy~;e8`5te)U-!TP-gvQdPwnT8Km7EOK8ZFD=aV<~Mn>{vz}L=Dz(x@PRb`PrcQShyPP=v-yPhKQ&$w{}(s@PtCkG z{9oMoKlNJkVfa7w8e6{*|EFGM^PB2!`o~s19vc6rW*!s%FK+x_-1xt^@qg;}t=|g% zPu*enkN;EGneW5@#f|^d`8C+<^>g!o>PCCM@PBIj3jQx{{GXcF2mUW^{GXcl1O89V z{`fz2hxt~U&*a^1uXpns-b?KE_`kzXpCA13GJAdD|J1ym@qcR8zsCRdc6R=sdc!N< z3G4r=nMa2I)A?*Me~SN8^Ln=5)%o?~^=`h&oA;;vKF^!a5BvR~H|J;TYbM&flsA4d z-~6BMkH-J0@h{B(Q#aW>I_CfB`E0Pp|EU{oejWZ#y~aL2ng6F=zxBo7|J1eS-^?d% z)#pLAtzT(=$s4a-^|cA!tJZhppSHU^{S0M!T+gO*!?sAPt818{GT3QL-*F;|J1G9b_V~auFZNR z-@neh67&Cby;s`#;{VjE?fT;X)LnM_i$K*3q@PE4f20I@9Pupq!r|vNijsMf**>3Ce;{VimH~gP^o%t#JpPKb>@qfC0 z8*F}_J-^;~ar^hSOwTXA__Vysy*VHIeZ23_`w9Q2ZYux^yc#r|EKLV{!h*E@qcmS|J1Fv9sj56&H0`E z;4OZ>c)Oo<+~tkO!~f~=^7!$8>UP_X|Lg6n|5M|U@qcRO>*4>@oi+~;|EFgCU;LlW zZ>7C|@PBIgzqs*#>JIyQ5C5mvJAeOSuV>%R!-ol8x_pckS|j+D_yD)LWWcga6a##VYd-_&@c^Cm*wUUVrso@%ST|>yG}r z_jC7u!@SNvz3;vLYQBE)<6m~;HGF+jq5He~)*Jcz2k#p$yMnKeyw5-NbpC$Ad(bJT z@%5GWp~oH{{GZM*@1&W*|HX~}Q_q+^GpzrsK6lRfVf|nAsW*Qu_&|7M$K_3PID-bPr*H^0aFzv=}x9}xfNuYa4ThyPRK|M7q7PCGyRpSs=72mhyTFptOjzv_DPaIF8U zUToW0|5v@#?$7?-z#Ff3eCc%W#HzUDdcE_&@ccmKDMOspbFt_%=Te|EFHsv?BOFy*_L0c+CG(c*z*{J*&I ze>$H0pIZJ;E&r!pXdV&&r{h(b=fnT0t8G3a{!hJpm;cl4*&qL>$6ICd67S!5zc)S; z|EGWdX#Aggsm%|>|EZhIC*uF&wtw#`^zT!n`NtubKb&a%pZ2deZ^`^WHGXr!oX5Ob zpBMk9^QG~B+P~U-AoKs?wt2eV%=g3pX*<3T{}(s&|KhfPfBk&%g7`l@p8EC`_WQnP zEA;aLj(6fw&sAXj@O?DaPtAI}{CC{=KXtQtz5`dk;N4>05C5m*cQj`GpSrESHTXYu zT|;~Df9ghiec=Dp@_%Z)AoKs!wRPF~f9jgr#ti;X=f^xi{GYmNS#{>hdzO1IU$Q)N z*2UG{OBXK9oN!Ey_X~>_hxvax{&VL2@PF$1dD;1Y`gzy`H{BBapZd!4W(WVLo-lGi znE$69oqrI2UtggvDDThT-+RmdX*qF+1bZEw6H>;LNZbWP>Yd^^7H$^4%u`u5?!=xsZ{OZ)uNoBKOy|6e5< z|EJ@#9sd_M^Z(R5UgrO)@sq!Q?L9vp{i7|v_GbTWUGFCv|EJr_|EckQ_`kUEe`@(Z zHLsUrF8-q*pB{hupAtRbxDUK}J?vZZXK&^?;{Wu1zysp{)VyEtf4V>3PxwDI{uckI z#_vA$r@#8`+5gU8{mr|uWI*P!AAH=~=I>^I>l1J0@s)1)yEmUV_&=RbUP=Ej|4)rK z#{a2VpBMk9o>+Q#nEw~|BenmkC_8*v@Ope6t$zNqMC1RoKilztYCg~Ke`@(Z9dB&0 zt(R{8PtAP5^9S$YJz~*Bu%zD`)F(A>@bF}( zuTR?hr8_^)0dae`>C8{O?7fttTBf>k-Et=1WF?p7o>S?W{+fXnTFd zjhBqOY?uH0>p@d>%X|EbGn<^}(^^`WZZ|0bO>I`}_z;i=|- z_y1Lon)QF}>s#+~^L+O8uQz@U|EJ^A_&=S`RGW8)|5HyhFNgnA<5igd7dP|&yid;w z{x5F)pY9J|hyPRK1Mz=qd>j5xjiz_p|EI;K}$|Ecj`_g_%s&HAq|TvP3hCv3fad7|yM-tvFC9<=?f zQewN!Cij;A)BZI6PtEP|e>y+r&EfylJYV=fwdVin_N?EF|5J1QnEw|y^Z(R%IQ*Y_ zoShH;PaU3boBtO#{!h*IzpwKtZ_e+K?k5x7^70djE`RfJZ@k?P-uY&tulV3GZ`MEm z*FPTho@MXgnbK@qcRhKlRKDitOhX z*ZS*&KKF*Jy-R0i{h#(fa>kLt|EVu~_Ojsrp1N*+@PDlT%ltp}s-4?1m-d|2Q}kih z`>iu?!TdjUyZ!#@jWs9tu*MAQ`PSQfhim^Z%bWEo_cQ;e?X8=(WiD$!p(iush2Z;` z2l(K7$3?v}_&;s$uz6_sKXvDpmxBLOuP|SS|5MBVspbE4|9BkyU)=aVHC_q-r^Ykk z|I}?;UkUzC$EWds>eV(sjQM|YGyl(f$LpC}wv6fFXY%~~e&x1TGtYf|w0EcZLHwWg zZ@0&b|I_`q+wliHJi@zc`|H8~>G{BSm7X}%pC5b&{!iQS2>3rW>(S!>)cB~kU+(Y6 zr|_&;^K&Huvx zsqqx}KXr>W{x5F)pBlfw`oHRC^Bed-b-lgb@qcmS|8#ye=4U@Q|EI3A*E9Z4&HPII zpSsOn-}pZ@uMhlR-1xt^@qcRGPx!yM@qcQLhyPR8n-8`19laau`N#jgRJtH|z^)hH z2>wsK>ZR`l|EFGK9+3HeYUTqn|4+Tnyc7OU_qX1BsI6b=*9-rI|I_uO@qcQ3E&fl< z`pEb{HS<03f9egkKmJdRf5|uhr~B`;&o}&^x_RRce2?!>-< zH|+9%>PFii|EKO)zdiUrb?1g1!T+fnZ9D!?-Mn#U@PB%|4R(I4|Ep$wU-LuWb>;)j zBY8J$*%thtu79ifL;Rn*%lst%PrcgSZ;x!6u|=<^wf6ad|5G!6to1twc{3jl|EJq; z-R1w(n{9vmpKgzD$Nyw<~{qsFTp?!ChNH2zQfbN%su>aH!{%2d3cT@qg-e`}{M%Qm*HV_do0Z#*P2e{;W^^gS{{G`{VK3_4me;{`j2h zy!rP8|L5mx|32XV;>Q1}+iW}jPu*(o5B#6Hd2`nP#f|?{xAg1?{!h*M;Q!Pcwrsb* z2Uy~dXZ_}FydJ#U?d!Xr-&gC+^;mj%qc`W5Q_||!hsOWudabnc!~dx}H*T}%V~yXQ z`G6PhyTO~!JA1u(H=2LO|LOKL{!h)vPWq z|EKMbFKrC|Pd%@`Gx$IClDdxI|I}5DUBUmU=bMjV{-1i8t@ml`gIDPB)O2<+AG<=Y z59Zmi{%>!u3G@Hr#{cQ|EjACA`G4v*^LjZYqy6?B=HvF?C&#FBN z>x~C&yFSmG^==<8$@i`@e`lXp75@2Rp6&CpiQdgCH`x27(3^RF_&=RLjsH_Obgd8m zFK+ywdg(6zr{;X{f9h(xJ^n9l{GXcjckzF5ZR?gga1>{H_wOvQ!g|x zhW}GHnJ>ftsacN~|EFGLUXS^IaWnr<&AdDOpPoM&|EI?D;s3NhjsH_GY3vOCPrbOI zBlth{eDkQx|5M}ZnE$8aFEJm8|5Gn+?zGQ?YrJdi`1n7)e(TH!;{VhQ_If|;lN)`1 z8vm!`EpO@y^Z(R%Mb`gSFSYrE%>Pq!KKMT!zpAM-_&;@xT_60Pn*EO}yf4xJ=ySgx z56}4f|MYg1`9Ayl*{?^H`M!(3|3HQQy;*L@e`eiWZ#>+#B@ZSV|EK+{?fJ+5sqvtv z%y`5b5Bk8kM-z?z)BA_xA9w6G6OI4VcIJWN|Ki5~sjHf^{x5F)pPJ_j{}(s@Pv^Vb zUJv*`b*;T#@qhYx!19*P;Q#dV1MUz1r>-%-hnerVg8?PkN;!-pBj&6f1jUd`}w_hX;EK( zzMp9O`M-BTQJ>)d^z%9SKXp!N-?08~+^qkr&Mh4r=Ktw@#+D5U{!cCcr^YMo{p!}< z`?vXb_&;rDejENzjrYR;>HhFq_&+tC3;(CaOWE&lyn_cb|EKLV{!h((KK!2=zlQ%) zv;Xj-SN(kGujahwU1;a~*}&Jmi|ly6Kj;nbNt1^J|EJ^8_&;^2c`*E+n&UJ7PmMog z{$JeqzqpzI7dQS-&GGPmapV8g93TG|H~ufa{`kMR@qcQLzi#GF6OI4VcAh`{pPK#g ze`-7({!fjc!~d!AqWC|ZU-{&tg8%cjj!`6`_t?9`pBF0y=(uGZ2X^Y&vyJ@-1t8=p9iPy`ANl9`&I>yS6JFVbKl3k z&F$NM`*+_?zxDS2c;f}}e||h`{GS>h$oju=D|EHG! zi~F^EzEG)7d$V+>z1Z#=AISW_m-gH*_`iZ71B3rl7Y-X7{GU4Q{nG0Jr`KOid#v<4 zzuonOqmte*J>M|hX`h$&f4iG^H>6*3p4?IWlm2g9-=t3)-#v z_PGO+`==jI`uR)yzw~^+-Oc|S**EC}(>PrLGCn^uxA?AYdz5@RcsP92QdcycW^)WV&kNJOUyc+ZW)OfMG{&0mKPySEG#|JY1 zPmMQQa@l3xCzg~4|EJ@fP?Yt5YHpAJQ*(R#pSrZXDEL2hd1Xlk|EHc+Q5O84`UIPA zhyPQ{|EcBw)XXQu|LOTGC@T*BPtEz^|J0lx^Z(Sx+Wz=IHS6Ev|J3-$@06Y8=Yx;L z|LOiYKK?Im{9oMoKXqwoY4Cq)t|$IaeM~`N@PBINJ;oj{-D%I4_I_h0CT~A(QquqN zeo7qQ-fwYN7L8#(bdRmU8NA>0^6?q_`mx7MPVjvbPRz}G_5F9f3ucZD{!iPP_g8q* zuX5boe_v&AGG$U)=aVH9iLa7dQS-&GGSn zI$zqp|MBhkI-8H~&Ev)Y#ka@*#f|?{bN}}DS&7E~X*<3R|EI3B5cze`}_{?+4gu|tJ$7t`~KCNaGf#y7)Ahj*;s4Zl zzuHqa`~J+wv+uvXXPYm>|LOcsvh#i5@QsQ4Uodn-qVa!v{qlU^|J0RdWc{BSkHq}H zxbc5#`9C$+8~>+fJN{2S)vh1@PmTYwpN}N^wly7z#{b3pQ1}xxV;6wfvu&>w*7M^Z1zm7dQS-&Hng5HOIsMspbFTw(o^}JL~`2-!gf#{xAMd z`{TRte{r+^uU-$V7d!0bMZTSRhWJ12&wM%jpE^7r=Ktbm{a+oA?fAdA@qcmS|J3+2 z{9oMoKehZ{-1t8=*9-p_H~uef{9oMozqs*#apV8gr=LC{_&@b&r{xF#r{?*?|HX~} zQ{yA?e{tjg)XYc3|HX~}Q}g(k|EK2u@PBH}|BD;{r>8U)U1EX{J*&Ie`nWB#9>k2Y)kpSsnKkN;ES8yBB9$Zt=ZkML$aS^S@l-)i%p@PBGN z6#h@g>$K~M|5I-=PlEqbZ#I8||5LY_|HA+2_0_)1|EbxI|5LZve4ugHec8Ls=1HAY zy7dQS-jZb0y-?;IAI^Vio z{!d+FUKanSuC@70_&;@>9S{HKy=(qo-1t8=z7PMWuC>?OZ}xrL8y|@O)A`Z(KXs#d z82q2Q*&Z+cPmO26|HX~}Q{(;ce{tjg)a&f{_&+s14*#cSePaBddWCsCo0sOzdYa7t zyLIToT^{gto3GR8+wr1L&8bWD_rA5vDYX5Pt80@{GWQQc|ZK09^Y#7Fz>x}t8eevl=Xkwziq>|;Q!S4KIZ?aSJ>wz z^Z(R%Jp7-U?f5@`f0@U@|EcjZ_&;^G%>%Uc%D3wMyw!Z1`6urtYy6+KGjEUif9lqa z-NFB<+q<{muX?xJ{W1Sf_t$3Uga1=^b?*rNPmT9s{arR{!h(3J^Y_uf6Q0I|EYQZ#R`Gs&sjffsT~EvVO>f)h zfju8(+TLmNQ0@8k#)ISkw7t#VulPST^VaZxx<4BKr`}-yo)$k><@@vcxAXC4UfuM< zZtr$`e8)fjsyEkb)-T`k=6c%s_qJWXvmgAMH`inApEBh-KW>lzQ*(R#pPK87|5G#H z5&x&&U>*(sr`~9<5B#5+^=9q;;m!KG_Vs}`^YvbyGsPR9$ojv!KCF+-{696XhgrWo z)Awh79sW=E$NW0{pPKFXKXr?}fAD|mPJ8|0|I{n&@!|i}cv$?On)#ymKXtRce^~!F zZv3B``(yr}8sCclQ*XBOz2mdR-W%-wZm$RL6`QtaJ{?}0=*`^?-ki@pC%1TWzV`a@ z?y&Rw&mCRf?e=-M{eU%zo?Exxd!;?!_ImTi`@K7{$FD!1Up3#};Vu8C_g{<6C$-O) za&_m1Zu3Up@m_78hgbag``+#L`8WK=A9=T#2ef~Gy_?r>cq`aEd2d2y`& z8#n$>-Q9ur`J?yxme%0^w7uFq;3qpj^6g6(FE+pPiFbqf2K)NNyT&}=oc%uY^O^hX zGd7RwKZ*Wu`5qN|{I@TlLJ2mhyj+U8~1=V^s{k@=K;st!&x^Z&FRKl4)Q;of+!Vf**-UTj{B z`G4BK$~@YEqx<{$Ewg!afBE|WZ|3{i`r!U}8oO5W_c0ZE|MK@u_Vu$jKF_|s_HJ6a zCd2x_x_)dw@%oY8ctHH0ws);wAN-%XbC>^9GanHDr)EAN{!h*Nx%j`h@qaqsW?K&z z{}(s@ueaA_w!K-DX#4uWoArvB|EJ?O*!slpPOR|l%;#hMUmcIOuQ$B$efU4!p2q*F zSx*=L7dQS-&3r%npPJ{B`G4vc%!lFs)C??-eh=CSa9y8qhx_RN{*T<2YH9uWVh*E{n8@qgOCrlB+VKQ&%)&;4%kr?M# zHh*wO{cVZH|LOR=|Cs-$#v|hY)I5ItU)-lYc)vG(5dWw1;rinLbUoz%^zRLg|BD;{ z7dQS-jqk+&sd@e2|J3+K{9oMoKfRu-TC@HyZv0=|_`kUEe`xvL-*?-dsnGZT)pkDkKQ$hd`G5L(0iT!nKehZ{+}JqvQae8XtzKsDkN?b{?_Fc- z&*T5JoyPyE>uZ~W|5MjiHw6Eu^Q&Lp6#SpMq1t?)`9JMnRnrjspL$t!edfvos{HXS zUsjv>$w$4tY)N+hpY~t8BfE?Dq%0o#QkAPy5r%|5Fby>l^%^dX&vCWB#97>;J}$|5M}P@PBdR|I~Oq{GZOR z$mZeU|J1W9hXntpKDlCW@PBH27xVwr%-6&JsX0FWFK+ywn%m?5bUyen{GXb6ZTP>q z@qcR8Pi6gI9goKU#f|?{mzpQT|EW1Y{9oMoKQ-rv|5I~*_&+u0hyRNk|EFeu{GXcp z$N%a4Y5bp>|BD;{cmF+A!T<63i2qaP6=diCY5$4i z4-fPI)Dy-X8vLJn%;+P-`oHQ?!~13Mf9mu+zuoz;v={sTTHh7_xAZ4j|Ht~Wtp6J~ z^Z(T8Cg;Qz*q8IyT`&j+{N`Sq_xNA_&;@F{)FKF;>Q2!_8kAfOmE|x{x$Lr-=1q;?l&jj zo@o4^ZqNDP|I~P?=2vd@o?I{~_&;rDJze~t8jpzoQ!_6Q|EHc-SRDMHn)QV7e`>rH z>;LNUjV~$;^Z(SW|BC;M8~>-q6P|p`HQsnb`+c%EUh%SpS0(z!?N@qp|M)*0FRyS? znE$6Pom3e7pPI*q|5HzySeR*i>QZm6SJ(PWyqRCu{m#YSc)6GM?d|DP%7g#Y^_W^& z8vLL7H1l|@|Er#DUJ?JNX1*Tt|J1C%d*Sfj=J~|`>Gg}pWB#AIsJJZnKlP--lFa@u zos&4;-#<9pyS!vl=D!Z@?P(R2!T;(0<^R-NpUZDL-5)=F)8f;-xjx_6d8#+p=aE01 z;ytrG>;L?CHjgs?_hGbo+qiRVJ>j?~<|Vyey79d6{=DDg9%&vpZtkzG;Qbz3gEM%) zqN1GO|J2L_#Q&Mm$@;$;BZL1_7oL<8{GYn=%Y2S14aQ{x9~-*`Lf+~EIux90}`r^cV*|J1C%i~mz={olCp ze`@)^xbc5+eceEXDL{!jbU_&+uC|Lps7KR%8B)BW>!@PBH2CH_y%^~C?F<^R<9 zHvC`Q_`kTB|EHG!Q#1bz|EFdi9{w+G{9oMoKQ(>|{}(s@PmPbn|HX~}Q)~WT-1xt^ z@qcRhKehayTK+F?{9oMoKQ;3T@qcmKe|yXSY5R2Zpj*xVsX2fApPKW-|EckO_`kRh z{6D1K2b5i9x&QGaA}U-;LJ4W4x9KyPB$GBF351$JfY1Vn1Qihx5K%xtdPy&n>3t@d zNhZCw2?C;^S44^kiVaY&qFAt(|MPuMe$Tvn-@9(sU4PfQ>+)TDpMCZ@XP=Wv&S#!? zPqp`XmuLN-wx4@h*8i!QCpZ4ntNrtc$9wb_E4=Y}_&;55@_*ho-w*#6H~vpuYUhXl zQ{&a}f9mO1lx8lq`G0D>8~!hD{GXcp$N$BR|5J0l;Q!P-9{iu0*AM@v=Kah3zqpzI zr=EO?J%8r^;>Q1Z<5|uBsky%Ke`>Bz{GXb6p7=jC=Y#)KbH4b$xW9VCm;LqR_4?%l zcX`YIX@8paf7NGRo?ZVpZv3Bm#uej(|5MMra)SMS;phDL=U!Q6zmND?@AI#k6z2cw z`k8WQ{+~K;_UN$wuZ}n1oFRO_(QRvD1`l=Z;_UjrW@Li@Th`Q=dHV5r-PQY62k&Q- zL4*HO^L=REy>q+mJK^B{m`{QKQ@7jqQzNI&?&f#O@qTy}{GXcdXYqe(=FQ;$)Xa0i z|HX~}Q{y>C=Far{W4?@iAD?LapU#K<@qcRO`QZQ5%%8#ksoU*%_&@a;yFLC--MZ(g z;Qw?!YivFr{!hK>(E7h><`d%oyv+x&{;wKO#rnVMwf6lv{!iUuUIzcC`^N*~|I}Uk zz83tSUZ1slp9%g?y}mo^|I~O2{GV>m{p0`CU3R{#|Ev9J*8f%Wc<_I5L!~9$NWEavt4iaKXuFAr-T1fv)%lGZ*R25|LOc%?E1w2sn^)NEBs&F_&+uC zCT%{FACGyIHb1GS?Rvrg`Tph=&13a!x3={ez44;>KkeWC%-4heQ+Is*`QZQ5cs*Mm z()Y*v;s3Oq>lOc}=K8_^sk@$Hz3Q3+x*lo!@1C}Khp!D^>5YHI|LOVUc=*4#@qcRO zo#Fq~%tOQfsqtmk9{pu+d>;N!+nF!6z~=wO&HO(#^QiEDYWxfSPmRyP|EW7|9vA*k zk9VETtHS@OnYW7nQ*Sxs|MY&}W}nCSKXu!I?E1fPVK?--!QH%m1nQc?AEbW}Y7YPtEm!|I_Qk^@jh88~>;M+YdY${9oMo zKlNJMj{j5Raq)j@-tYLoxbc5#*8j%;sax#!_&+uGkN;D*+Wz=Ib@TS!!T+i8i1y#U zo#zk#r|qn#jsH{g{vF-eG}V88vHn$2n>Y8j;ig zYpUv*Pwe-%YDHycUD@CL@hw`pGIQe#|MGr(*)sd{>jULF-`f{e1plYLdu1IzKl%2D ztDA!V)Aq&99l`(U{+F+@^ZoVFPuu#D=l<)s^5Mr+1>e8Y{15(5y~=zL z{x5F)pSs$PciX{}{dhbd7cTDOUAJ*#rf7a&@20I=ga6a{(8o3n@W<1*WlQjXdORC9 z*t|FMe|rD!Jmmk>yk7V}HQvvD|HgZb&ExyWPeyvL-L^aUKOKL)t-s6szqpzIr^fr? z|Kk4P>xF*2&G!3MQ`Z!GZ!$lK|I_)bvH5)Xzqs*#YCInPPmTA(|EU{nUf_K|{!h*NviLuB z$NEkDewv@(T3f%>=GS|(zAFAt`_uS8b;J4%!T;%cq49reydVBg`^*2S@n85qbz|GQ z%qRO^=l8#~Wo_o!w-$IWxA|%|-`9Jo^&@wG%A5C3>ql?&3kc_3o`$&r@Mmx)A`{8@qcQ39{w+G{GZ-`o#w~ze`?l`wcmH~<1?S` z`0MXYH1q#-|2#kVKXt3k3&j8F{#b99`G5L6XFXl~pPJ+2|I~On{GS?si2qa9+2;%X zPhDl_i~m#C*zxdxx_RpfPU91Pe&PNfUYKb7pZ3@Mzqs*#>c*Be!T+gS+B^C4 z*UzW6V_oon`t!4XU03jb>N-1r{2ykI-yf`Q?Fjx)UEkap=KrZ1TGnOof9hJhp0IFg zj>mtio9uk>f9l4ztp8Ip&yV?kakKuf&JPc`?V~k4+s%XH|FnN&eM|6vapV7V`?}hO z;Q!RM=KWazSNpH7tqJr0;%5C{^|DnJ!T+gOR#t`if9l3V{!jltcI)*w1plX=d+EI3 z|I~d3^bh_|JtX%(g8x(JjyomzKXtyXSBd|N8~>*+9(Pjke{tjg)c6j$#{X%% z{GYnSJP`g*&3wQ!e!JH@Z%V)5|Fj*y!}`DKvF54pe`@>_{!fkP!vCp*_cH&d^TY4q z|I}xmk)8h+H}n706VDvV_d9;PvNMKc?E4?@@)<)ib1r%|(UZ>nx;OrAK+V_7^?eQYB z&KLiu#`9HHyyHF1=5Idu*w4N3Za3fk3-8I(2bf>@rMKq)>3DcS{GXcJhi2qYF-|wm7_sf5Mb3^cR z+`e$wpAwD#)BfBZ{}(s@Pd#a3zYP9QT{hv=4E|4zA7uVt-1xt^@qcQ~|BKs}B-W5F5QRoUul1Z&%*!R z+I38r|A&Xe|Ecj{_&;^pbEP}&$I`wl?f251emrR(c(_h`x3rJLH^zP=-9rW>z2D&e zNe@_X>i?|^`zDW-)O^15dcLFk^h-P+>DMpq|I*vj z^8$-g>rJPd`I7PTUp6AS{&U`_WV3#6ynovFrTyQK+~j;f`g5Oq@Zgd;#|Q5>upl@1 zKlPxZtp8KvdGLSg9GmBN_wf4_$6=72mh!0r}2O4 z0-K+Q|BD;{=RK}8^TOq~`|XXU#{a3AcZdH|=Zz~2{!e{|&5y+YsZTd=ivLrO z$sHd2pL*;#TTj#0|5f87ng16z{!fjE#Q&+M7LN`7Pd(n|IpY7+_%r;Unt79~|EuR? zLViy0f9i=jql5p88~^8Rx5xjfSuYv?r=C(&k~wGgRo@#PtCkU{GXcb%>PsKd@=t|&Hds3^my@+_&+t<@qcmS|J2N!18QPk&yF zE6PdiKh}J1e0$da{@=PVCpWRZUv6^V=xO$R z-29);Z~R3C!T-gL|5HyjZ^ryT^_02U`G0DB7yeI;r^ElL%WS<^=KsZw|5MBV#f|@q z`~DYR@aKd5SO4JK-tvFipT_@r+xgqyk9>d5-~Rs8({{f0`&HiD9{;D?bAR~1xb5$6 ziT&;GciwnB{GVP=8vm!pzcK$$jeo=c#f|?{`UcJAN)e(kr%*V*5{z1fcc)A8Ak|BD;{r!F`DiT_jceB%GqJRhw8tCs(Z8~>-q z_u>EIX8xa=`Dpk*H69HAr^ajH|J3*{{GVF>FK+ywn)}E9#f|?{%m1nIbND|s{_6J& z+x`8Azk0U1Ezzw1tNq!|{694w>x`$HeSiAY7n{8CefC~YwEbPd`&`>@znkU9V?E;o z=Kpkj?r+K|b-q7+!th#e{NLNfHQvm7!~f~_7ufU3{J*%bn_ubs%m3-~h~wk`)I9%R z_}ePKJP|?Q{&O_e`>bl|J0{nRvP@D z8b65tQ*(d#zqs*#YOXK*pL)u??EF79-Vgt$F0$(b{}(s@PtEm*|BD;{r{?{G|BD;{ zr{;X{e{omNx!0d>t`Gd5UOyWDr{?kYuK$uZ&&T9lcX*$F#n{aCFW#PL{GaX*@3-?q zxB7PZKOG<6hyRP4`G4v&=4aRcRhOQZ^?y44Dd!Ch{_phLtAhWV_r%9--qK~==QLLa z?{{Z&*8iz14(tp5PmNE(|NZ>@%HaRn?E9_{A9X?Z#ot~XykEU}K>VM&(Y`;!|EX(j z9w7ctU1#6F;{VjGc6|I_-1t9rmw77Y|HaMxKQ$h3z@N&!<^OcP%$LIdshiDn;s4Za zd$ayejhDjzshQt3?Pv^t>b@)Fuo)G`1UTdBL|EJzy_mBUJ8~>;K z?=bIY-!J;>h4*9rpI)ENL;g?QW%C68He!h1p80S1KOL{lycYgX%{)Km|EckD%>RoU z|EJ@#ekA@+z1?n)|NG&fs^CfSE%-k*>oMd1)U1Dr|5Gzh3je3xd&vK(nJRoU|EF#r)J*RjUV3b-C*(S<$dE*Q5e>#6W zpnX5++nGQ1>T?fyGk?tHrFr9p)|K6zX!AP<^!{nJ?dE&Do6X1I|8##{hx}jM_&;^4 zc^mUZe*AXxIQTz3o;LG!=97AkZ^yIGH*b#5{6C!!UJ?JN#tSk3Pu*%>2>+*MJzduS zRX3X_G=Jrd|H1!hJ6_5BmN&P@|7klO3IC^NJN{42dcNj!_WR?r#{b2Q|5MBV>G`6~ zckWm7`H%n8^~2{O{;#K>vG>EdiN^nFJMSm_pPKg@{!fkn!vE?1m`98MQ}cOfzHhJ2 z7Z1q))Oa`ipPKoltpBTSvG*hE|Hh5~)AQA6e_rAL)D8Qd=JoaF{m=YAZKv^nYUbnO z|I~PG{9oMoKQ-?c{GXcjaq)j@J`W!J>DQ;|&$AZudyB@r>fLJo691?D*^d8HvmO7Z zZn5VF|EF%Y&wu=%8b68uiyQx^#;^UVX!ul}&lbD>?ayCtd@l3DGZ{r>9gda1bOdhc4hfBc{Jud(+#{!h*O6aN=C{!h*O z2mhz${e}Nix7hvHmM--BYc?-@&9h6qyUec*x_pH<&zF4{@6G3nec$iR=aGGX?~Omi z|LOVVeDQy3`MOYncX|1Mk4691>qi!B>B z2mhzuZ0p^c&n{Qvt(gC(+tc_zb%*&Z=Kra?%&Rf~Pv_rk^WgA*YJ3*{PuoNaNjW@&p z>HO(_zZ~d~f1k~#!~f~|cxuPqF#k{8Y_AXgFK+ywTK+HYt2T^IY{&oU{(1fJe`?MD zQ?ouV{!ho-X3rP?Prb!_9sW<&5kR--g-Vtu~(y|EK+F{GXcjS@C~5 zAABhOPtANc{Gaw`9vc2nU2Xo1`G2}zSRWeyr*2-`nW<^H#;?Z)ThH{bw_e-Rt!p!v zPruH)-nG|jRW&WQUZ^`_>xbc5#j?er*HOI&Qsd>IXc*PRGKVA>~pU!8sJznPj z>CeNe&JDr;sjJOT=KrZ1&119vZ`}Alb$v@m@PBb*b1hzg%5d+=ux9-o<142LI>V zZJr?W|I~QEg`eJ2u74lK_wAa$H_<ANzjIyU4sE^Z)et z@p1S+HMhtAsX0FL|I}>9|HX~}i|-%*r{?_ee`?mR#s8_9*N6YpTv%y|4+^R z+xMT|rMCXFeLw2W`p?Y&)A3nf+16L{?ev1vf8@>efdA9}H2zP`{p0_1|1|zj&FfMA z_nyZ0-T3ZXz8znO|I_jCb@)Fu-WC6+F0kX_|J2-``G0C|kN;DTood&Y`M&m)PDq@pp;F|LO71oRXdY7dQS-jqkhc^gotg zer;p$e#{rd|EXtB>L2`{`nRydPd&*zApS4zH_iX4 z@qYL}HTTE-KQ*6M_&;@_eV*a}biVR`>f&)HXYhY&J|FRa>ioj2|I_jEa|Q+fr`G&G z_2K5@&FnwW{x#;w`}BV^`X%S*rPo`f@qcIE{~y8s;qmZ)apV8g>3MvI>$LAXT&I0s z+B2rlKYhH(1CpL?Qval%Onbky&r5r}|7#CFrB~wlPy4y_@p4b@o!I~Xdi$J{lJ_^@ zwe#!NN(_J`ZSmN=F9g$qWcjD;e`n>5b8J)a+y7NXP zZ=W-4c;f#0k4WBr(3nxd|Fw)dA^1Q1AoKs!%mZZoUp4;k;br$9eDj{;gZE>882(S4 zQ=IjGaWnr<&HO<8pBfK{|NC+Gabcbx$HV`r^Gb_@|5M}j@PBIN_u>E4_$U0I8efS2 zQ|A}v1plY|FDl8;Z2aLJz8$}~`>3Ag{_ua=pYy~2`SHx-;s4akzr+8jnfG_ivRe-R z?BB;uTRroQX$3{*kM@4f8=rXO$Xk4W=H(rC!RNf0kI4K#-T$b9{NVp|{JgOx!T+h5 z?}z_WGv9B^Pd@GUN564QPme1p2>ws|7Z;5T{!d+yKP>n^bzZ@k;Q!RcW3&Fx+nz7{ zpPKn__&@cef}-I6)Dv>^Ge^C%z#kut|I_wyV{(K4Q{&CPQ+%y&r(eJFW8U~S=KtyW zqTlPf+P4?wkIDS~m8-mq3vz=0)BgB3{GXcjr15`hydM5f&Gm=>Q}g`e|Ki5~#f|@q z8~^8R_lN(}F9)%{$uPf1=I_{!jZ)HIIn@Q!}p)|EFetA^tDEfBawE_&@EBZ^Zw_jsH{g z{NVrM#{a3yFD}ZQ{O(u%^`U?HwvhX+2=)053_EkEU;Z^!@O|8zWjp8futccJ+| z`~A2?+x&cQd?Ef%x2N%capV8u#{a3AM~MGZpKaF%{!h*MQ1} zd3^Z4xbc5#ycqs3Zv3BmhRwIb|EZa8i2qaL^O*k^H~vp8|EFgD8vaks{j>gW-1tBB z*_W8lH2}c^m_tLEY)Bd#mw{OSC+1~{cjsMgBcsu-` z&WAo={!fh$!~bc2ychmYE&mrc{!h0*&%7M|PtEz^|Fl2%$NWDv&o}-rZv3Ba&;Cz* zxTo=o4JWPi?ew-GE4*2+82_jD=Y*@W^Z(RmUpY4TKQ(?4|EFesWBi}`^ec*k|MRxz z1OKPy`NIFH=a}#NOy%Q#KC{jD-PiV*H?Q}qEsuJib#YWTJ#!vCrH z{J{UkjsH_~ed7P(KF0i?n)98|?<;=)yuSE9J>R^(_`kUEe`=l&{9oMoKQ+D+|EFdi z;NoB1=8YG`|7rWo`QyXz0uW8InF8}0kvpZ|2G_xhb#|EK%w zvh_3Zf9g%enmC;I-acD$;LNb z+#mi=$7B6T{GYbd_&;@vc?r|W~p|EW1Y{NL=Os)PSy-X8wX+vZQ<|Ki5~ zsW+Qf!T+h5AISVa^(LD)h5u9IYw&++{2u;KjR(a4sqvurKXsS+2b+K6z0R%&{GYb- z`r-f7@_$A1tAn5A`my;t2h{C$z1n=9MC1Q-`!<^gg#S~wnzz9JshfA~5A*-jE%tuH z|Eb${XZ@d=>l6Q{#%JLF{Cv!B;Q!QkCH!C9Hebze-(ttd|LJ)6SNxwEf7JPMw|BF> zzW6_FZ?@ML|EF%V`GNR9b**_i{9oMWrMy|sICoN~ce~B+`%F{2Hy*F+s1|ShQNLf- zAJFy3`r9_2>VU3S=KI;K5ARNE{Gab{9uWVh#`D?td5OmVX*=sp;{W2t|EZZzhW}GD zKMVh-^Wpu1|5LLbrhWhG`{VQ4AGjvb=Ci%=E%-kjAKzmB$dAW*zxY2LA3uZt^WL6a z|5x3y;{g8YfIe@y-pogNGwHP4L_&+s|m;b4` zUhscvJSF~5-MBM6UhgLJ#P~lwU)A<`h5w5i|EF%W^TGeAo9uk?e`>rK{!fj+#Q&*z zKJb5P{5bwk&HOz4pBfK~|MS<|u2=kD-1ho=bA99gbbA{Ar{?;>|EYPs@qcPQpYeZj zxQ_&;@v`5^qC_qP4P|EXKIAF#)JsUL5J zJs$j@?vKX*sVnVz?zieQiEh|+n>UYt*c*2y`jY#;;$3eZ4gaV6r}2O4COba9TK4)%y*<*D~rm-u2t}m?wJ4yTM+6Td&-k{h9x#_rLs~w|Ok{{l2|r z+b-Vke*2c~+cWRX`lWY=dB3$k{I&PyJ$o{ry8S)xjk|WSp1SvjEn73cX#TVJ=IuLz z|I_2yX7dM`{}(s@Pu;p}cjk_N9g*l)pF7gK%e>t9ile+YY}v-oU*-PzY`gt@=8gBV zpWnP2H+1pyop;;TEqtDq>+`d1(g&z=y7@2l^Je{An{Vys&wM)kpC12~b({J5xLog-U7L6E`!n8a?EdZN>qO)K zbo&OIkH`E!HS_WCf9jTX+rs=mJzs5IJA(gHud%;RG5=59Y4iB-f4Y6wq4|I6_4fGi zf9mF~+4XF|GQ&d)yI{PExe?e9m4w!c4lRQzAu_`kSW|2J;d|5Y>Z4F4B5 z{x5F)pRPyt$N#DEYxDo>>O@c4{W0(Q*7o549(uhx%(tv$|JCNZSpQdD(X=-BKXs+`j9WhEkEi;O|I_1R zUL5{U%{(~#pPI*u|5LLa|EF%V`GxpD^%|R3i2qa9ws!>or>UE&>YB>n|I{_LRT*Zd>F0xrii%7}bCdV-<;yeQ zf2i5Jc1hO%>EFk0n15~Np5r%`>)%(;I_Hc`=La@<_qBOW_V4HA+JE4vj|Bgx9$C~Y z_&>G$U);?9Qx7gaF|%poc0WG-M$-;&`9JMHc3l6=*oSxZY&S3Su`ljUH2zQLkEg-^ zsqr@WKQ-%x;{Vk0e`@B5;s4ZlK>PkA(fB|8`{CsB?EF79^YQS1I{&g6!!px<^pxKo z5BS*^pZ3Q8RXzQTH}n6V+3~eRzqj^TZ}!Lk>HKK?pPJj_|Ki5~squN=yzZNc{_`c@ zO7zgP{?l9jPmc#5hyRQFvrm1;8_#z6ju#VsM#p!(IbLDyOWvFh{!h;z^YHM0IzHX? z{40Jw_`lcoznbVHH+?VB_&+^fd?5Z$&H35)o8HXV!~bc!{GS^CXX~dWw&VY_o&E8D zYCPbQk{^4Qng826{3qVr|2qqQQvS@`rr_7;x$}PNE&r$E$^WUxP3xao{iC=2c;oH< zzxv`k-g!39^4+I@?wxP`vG2}bc;n~J?D(ZOe(u(q|MJGq)-U>%H}8*c-1}>9-XHis zoe%F1{GYe^!t>_+)*D}l|I>DSApTE{55)hedA#>t{d<2t=wHqGgSY&jo;LNb_&nzSsquNt|5I!JpIY<()Z-_f9QXL#J!~8!TuWqWb?Bhr|8`}11^+i} z*sx5^4G$dr{k#)`?_+-8(tq6V&AdSTpSBM#$P4~YJ*>De%>PplDa;S+|Elp;_`kUE zf3H>?AN(Ia4*#dd=Q00JU09qK{9oMoKQ+h4|EY6E4GaEH&HO~>|LOhycm z>GpUs{GS?si2u|1^87OYPurQ7$oxMwz7PMW#zW%&bbnlb_&;_2_@c~F<8ScBn=$`S zx5qCs|4+?4I@bSHGoO(8e`@CS;s4ZlI{aVU%>Rp<^?%iq%!}dw)MYl0lKFpX{2Bf) zZv3B``IY!TJzq5bPuuaQ_`kTB|EK-&miRw4^9b>O>H>TG_&;^7%`e3Nsd@hJe{tjg z)Ob()U)=aVZ+rdme>y*|2mGI!eC)}i-|pU1)e^iMZNLA~Z8N)q*PA+ND8C=#ea@@`etz^GJ138y zFTG1<=koKXx7PpF@yh4q2LGp?c;Top|4%(>?&#qE)XWFO|EZ^3l$*i-*_xukC*tk! ze{tLI-*_`W(0)J18*ga8zvEqQ^W5y``$YF&^0GJH5C5mzJS-m{GWQZT`%}QHIK*seZbET|M$@TZQk5J{!jbU z_`kUEf9e@_KKMVi{9oMoKQ-PA|EHdA9t;1cmj8IG5;^_JFe^S^Jn|Hx2*N% zc&FXF##{bRuh%)Y9sj4si{by`#{a41|J3KqD+&HjE&mrc{?FUaZ`I%Gy*a-F=Ku6~ zc>eHz+JBmPG5lZL%>RoU|EJsIzZTD~^6fky_&@E>{o()AY{&npd3^Xk9goKUshKZ` z|5MMg^Tq$ECtNu$^Ywz|-eu;?elU5N_ni6J`G5L6nSEtx@PBG0we!RO>3lA<^TYqC<^SUD=zhev<4N&KQ*_<|EW1X{!cCc z7dPwwdYkXV|HX~}Q}cS_|I}m7A7#HE`6=%c&dcJovCzqs*# zI{#MNj{j4)nRmheX@7hc{!fkP!vCo|&0FCA)NAZ~S^rm!-@^aJjsH`xKIH$@Rpuw~ zf9iUhAM|G596!HW^CtK|oo~mkCxib}uiY8ub@_JuBK}X?@nQJCo_;d;KXse=Mf{%{ zpNRic<2&$w>QrR{!h(3C;Xp!jd@f2pIZJ;&FhW->*@Vr{@>skHCg{>9t8iV zZr-&w_`kUEf4V(h1plXQw(A-Hr{?-+{+}9;F=_XY{P>OL4euWC18?Rx?f=SaiN^ow z{+rCh;Q!RjyTt#+jsMgAwc7Q9|5MBVsjJMt;s4Z?=GpLnYUWwt|Ki5~shiAm{_yop z2XwvQ{mgH93o_0h5u7m z+3Sh_)BYRHpW*-18|?GR=7;(I_&l30=FR%j_&*&FkB9$@8~>;7vd<^x|HX~})APsm zj{j5he!&0r^nu|2)SY&J_&@a~^Hlgh^#;41@qfBM=4avmv>k7Q|5G>G`-%B~+8=Mj z{69S(HMSl9r|XHv|7m-LoiF}RU1`t1`A+XD`+T(5E7A7+d*l1eBP819Gx`0s?hKz- ziMIFeKAjJ@$N#BY%#Yde_vw6=+4GP8Q?IbskN>H8|Kb1CcwD>vWOciJ-ZTF%Zv3B~ zuhsVXi2qYp+WQ^Z z#f|^d>x<9B|HX~}Q?Iwji~rN@Y5bqJJ)ihL^*Zx<_&+s&p5g!0yg%@N>ScDl;Qw@g zH2zOrWv>tZPtD`CpAWqGJhq=Vyqj(Q8U9bl@3fzf?DrvjJMTCApN_Z6-e35?xSx7& z!BqWxQ)%1JKH)Qo#{X%5yeIxIZv3B`&lCKg&WG0z|EK2p!2fA~8vmzm+Gg`LZT_FS zaqIpt|4&_I&o};0U2U%i{!h*MMrwn_&;^ahK;;m{Po>n z^Y8ke`e*O$HjkV6f7*Ye%{RpVsW-Ovm{!d-Mcfb94cVxMGqh0^_zqs*# zdOXeBwgvyEZrHpz_&+uC`S5@0HRi?a=RfbYo3`@vp?AA^G5h@y@3yXu{Cw&6-){cT ze*W~v@7d3%-rH>+-IW*h^Io%g8$aKc>-|96=Yw~LHU3ZAH`x4g{GYmWQ1}<^STgpErDa z)B3HMk-0OyTg)@!|8)P28@2}jr>?i(7sLOlS&#Srubu1N+-dXH%>U_nVSQHopPKn< z_WKaNKiirAr{mH1Kkbhv!~eyN|5LY`x3j+=C%V05zIT(&_rw3`=Vu!Kr(SJ7uJ0os z_g>Z1Zu34Dcvn_81^?&!S2Z#p*pI)&{NK}4Zt&*zW9NLPeC$&-!4p=Pw^}~%v)-%B z7c&1($E&jY$N%Z^(9Hi+bAI^0xbc7LRW{EL{}(s@PtE$Z_&+u4*W&-w6*j+*`G0DT zhyPQve)m^)f5jV*hyT-d*5_sZpI*P!<_qzEy54GRJN{42@$i3Y)?0pL)5Csy8vm#5 zt8Jbi^Z(S|Pv>o4v|Lf_t;Q!)g{-1Y4OYnbc=I`PE)Kv{l!T-gLwNqEt zHwOQwUR~D^{9oM6|5I1g)`#_f)s@!xzqq#**Olwf^A*+AnYT`=_g+?6nK}6{J-vGM z>ddS+8hkt65C5mzKVsX@KC7wxs+%gyx7>Eaw1-x$%KUXqvvHD*uF#b>5$4uxS{9oMoKQ;3L@qcRkApXyLLZ9IO)OZ}`|EXCY6#u8j zJK_K0#{cQxOD9Y+KeqC#{(N$K`+g>|KmJd*FD=jdKQ-&;;{UwO2jc(Y#{b2Q|5MBV zsn4Q1}@rn39HS_D3|EJd*uZI6qGfxixr^dtK|J3+7{GXcJ z+G5;^_=emAS zUNo~gcs=$X*YHDcj@P{OO>eg2|8#q{kHTK-Rs|NB7y zcl`FHtpEETKldJIz7GGV{h6;f>$kt~?K8~#ZTaypy_x5C+IRoU8?X1o)4xjepSJ(n z8^3qmns>c9zi(ImCef1~|E+hy>3uV6?|LuM_&=Q=&maCz&j)@G|EK2hG5=4^dcycW z^^{3{GV9*?lOJ#LA^)f2;~VjRapV8gctFGqc&IQWr*Ucvhf88#sJKlO-FgMQ1d^QIGm|6@KM{!fip!vCq6=g0iNxbc5#j*tISGyjbFf9gD& ze}@0_`_CU4{GYZn{}BJDX8s}mPmMpr|EY8A^dVJoP;QyAaKR)=sakd^R^Z(R2 zd82~=Q!`I*+gmsLcIFRGTY8J1AC3Rh`7-Yh|EK%QFU|TtHQw*hT{rsi=-$uYaPYZ* zXFtF2XH(w)RHE^JI-io_(oE5{pYk48Iw3RviBEb@E18gaX!|F;Cl}cIy>DLcji3Ae zN0N>I)A{lG;s4akAH@Hu@n-lxb-DRb{GS?6i2qaL4e@_!w!i)0HHpUmX}kQN8ZY{x zf6w>r%(KJ)>G{Ur;s4ZlK>VMY`^W#OIe+|L-1t8=`{V!A91s5&H~vrO$Nu;~HS_uK zf7-viB;Kf_&dUk@Pd)zptp8I_we^AR_f!1%@_*Vs!R7(7{;#^s<^?kUPd&lB zAO26xygK}!tudPQf9Bipe{tjg)Mw4j5B@K1{GXcndH6py>(Ao<)c8RB-|$7P!AHvf z#f|@q+y4IHx7YkX9Z&QB)SMswPd)3xyfFVyop0xd|5F#(`QiW6n*XO}{vZBNE&mrc z{!fkfWB#9d;w5>(|EYQW_WNP}{PXzj?~mU29{itP9~%Fs#?LYTPmTA%|EbxI|5LLa z|EK$BJN{42cKn|j&u4$X_S@6;_wPj8@8=~N|EJrZXUDg{-~0A+?0U1`|MTYY;Qw@f z_&)q!-1t8oPyWx_=JnzK;>Q1}@ny{aiyQx^#$Vz8;>Q1}xjpm$;{Numb$)(qZ@Hv1 z(fB`|KilztapV8gVSQ$s{}(s@Pc8o!xBa(om;cjt`9HPR|BV~}r)K^k{x9wuKGM^8 zE&QLh;{ox1Y91f{FYZ0ls=b+ihyT-d8vm!p`{Do8ctQN1n(g>MJ^yUS|EXDz7XKGF z{!cy5=K10O)Z=a5AO25$rp=>!@9d@C9REX?F7d{%^**usT3(LLR?fcj%`BS^?JL{}hwC|_q zUq9Kq!@LUqPuuZV_&;^)wmrfBsqtF)KQ*2U|EFf&75*=7{GS?M!~8!rUIPE8X1*c* zPtP}v|5G#XkokXVwln`v-E7~_3U(kKK!40^MQlG|EV|a@3whsC;E2QTg3nA`rB;B$N#BWUmE|X##iD0)U2nB|5JCF zU%>yxjsJ@q|EK2p$N#B${qcWlt}o{Qsd+u|f9g&4{XFac9zUiw_`i)i_XPi^X1);f z|Ki5~>GrILjsH_O*gPKmpSsEB0pb7D%n!o<>3H}7{GS>xf&WuC+UtY=iyQx^#)snn z)c7R)pYE^Td>Q^vjR$4^pPKbH@qcROhvEO!_4fMW|Ki5~sqt_4KV2UUww^HlPtANm z{9oMoKQ-&O;{S9#;#2W|djGKgs{Ob3db>aTpSIKZKi!_j|9RW>hX2$3asAo%gT9^X z-M(*3H2zQf z#{a4L{KEgK@y+-@JwMFX!vDo>KEn6M*D(K2+nI-k|5M`+@qcQ~|I_{9A@G0NPUHX7 z?2rG`{^9*-{!hL#0ii2sWl|L1M~3I7+j z`3&!>t^4eF$0r*9r|Y}Uw&VZeX8m7vrJbMczgJzmquc(zoUs{I**}lh*z0B6C&i8b z)A_8i&nxqGllA;?J>mb<_1pFZ|EF%WKM(MK>RLNK{x5F)pPK#gf9eK%zU=+s&GGSn z+FrMHuU$Xur|9*ox7X9wWA(1HKR@w*+RpR0bIU7J^yhcQrrnvR-us#Nimsi(|LOQE zH|z@jPhG!pckqAeX7g$IKXs#B-}paugI%xqKXrw982q2kXSL0X!~d!4Ht!DpPu*aT z5C5lb-nKXRKXs#BfA~KgpWEaAe7ikg_&+tz&y*LhnySZ7U30HLoB3Py5sOKXt7=zxcnnng6G*-nhqp9;o)?(fB`Y zuh_JQ_4xep(8s*e>dpG1_`jaVw=2y5Q}g+P|5NjMh5ysfll(l!{697R691?Dd42JJ zaSyxrN$=%0?+yQ_^Ic(H3je3(dcptc{Z?<+2mVi8ZTsW@;>Q1}YwZ5yglpxwEy~@ zJA?m=oB4n0cAF>2{6FUF6Q*X5Ux1X=db^e&^T){Gay6&wc5NUcSA}=GEEHkKTB$dG#li>+v<4C$smvcb9p=J|(AmZ!lkIKfii2 zpAP@0+tc_z^;(-(i2qY}*gQl0pBk^o{696G5&x&gzv2JX&0X7q|5G<@*ul^DzP+() zJD<-zy>4spe|o-~Z9DV-)Z8Bbr*2rkE%-lmz1@DuYo&fX`hk}5-gS09_&=Qw>-jSO zPtANl{9oMoKehZ{-1t8=>+RzI;>Q2!{MgR?zqs*#YWY8PQ^)$?|8#w{*!ryaKXtQt zF8rVNXI>rtFK*WVRWpz7>Br|K+U6^Jv!3ZggRk($U*Z3BfAqtjyV|?n);qm^%E!Db z8e4+@)6dtdn_7eaQ!lA&4*pNQxV9J{e0nE$8!m$bA7|M#=b+Ta0~ zwzdWTr|tMa*8h$B{ikmAt~B3>|I_hl{GYnQ8vm!p3*!IO^^IBor*5!$gZMu+`yYMe zJ^uXBH@&15bpROlfKm1?Z_&;?M-q7a%shMww z|5H~rbq4!t45>z!|X#QJ^S1rxIC|LXi%4;25WE}JqS_&+ti&%R&r?X-RW($jW( z{Gab{jsH`#J}dM8)U3~n|5F!DACQ^c_iKKBtlzu#=x2L+)_}~3|LEz`v$E^|>h{y8 z4+{P-Zsz}~<^STw|EcBw;>Q2!^*`(MLBapUjsH{2|EcBw)SCaN=6vk?KfgWO@qgNm z-(&q>HJ%Rtr}Lxne{tjg;>Q2Q&HO*L{GXch$N#CvnrFlR>3Wv`Q*(a!KlP-kgM$Cl z?P>g<8qbIS)BfdlJ>dV;_&fZc_NQ~o-b!p=J?3q1d>;N!x0nA@*+o6tLh|BL&!>Yg4y_QcGiy^rwiV~b9(?{|)vruPT_@0OcB z=$$wGMEgFdr_)}J`F*ihIGmRoF*NA|M~~(GS;TloSU4r=DVs|5GzB4*#dt{J*&Ie{tjgbbjp5`oF$C zFF&*J!0iVY+2@pZ4c^ zK7RCkzx_z_eE2_IFFYRnpPI*m|5J1S_&+u0kN;CowRxHNKlPOS+|2y5=K1|G?-2i| z^I@Lk#rIz1=gWG?_jJtl9-ou+dF&s59^g^qW?p67%(IM}$Mb(_d}6#m*AxEFW_Shv z$NWy_|EVWW84>)SddAGWF#k`@yg%mu#m)Rbb=mAO!T+fzU67ssr)K^f{x5F)pBkTr z|5KM;oSpwyFs3cx|J3+2{GXcnc+CG(GanECr)GcrU)=aVHNMV%KPb`m`$OKWcWJ+0 zlxX~)ZjV=F{+}Ap#{56^Y`Z=FPkpYfKg;|-bJDZGZps=bQ7z|LOUs@qcPO9{w+G{GS^Cga3;g{}(s@PmQ0m-+%MQ^Vxj- zMBDGrd9&Uu{!h1OJzxBvn%m?5; zf9Q>8vVWiO=6Lu&J>PgLTi?L9)3*MBH{NLOzzyDbtP#0giT+#JdT(xz|I_)=_`kUE ze`=m@{GXcng!n(T=KrZR|4)6v#o76P>I*Ni`KRXp)c7g;T_A5BkInw}#{XS@ZDaRG zN4AE4p9voD<_2%(1LFU5JR1L}#uwuM;>Q1}dA{&}YVIHZr=DZ?kN=As|EFeu{9oMo zKQ-rz|I_P94}W*(tVg}4+VwH}l1IFY%nuH^?%_ng|G9^}@x%B(9iPuz{GXc7 zkK;2v&HO+7pSJVPy$H&pcOoQTIvL)&xJ-X6qN>|M)jv{9o;=n&AJ`kJQ%% z|2O!t>frw#ZKx0aPkopDdpG`1eYgGl{9Dh@@_yLQ1}*&qL>UT5=`@PBdR|I|Ew z{GYnbzMsecsqv@yzqs*#>h<>ex7_jJ8@C z?E5_LE_*)lf7)JcehU8=w|OaV=8L}Gb(eR`_N@QY{%zLyKXt2lBJ)??Ys}-kc+@rC z?dFe||EK-&#`r%qJ_i4%US*B{iyQx^uCVJH{}(s@PtOnA@qg-7cD*wHPmPzt|Ecjd z_&+u42jc(K_$cQ8>Ha!xJw^PVw&OeSf9iHS9{x}J(`P^N4eyq%=9A3->3ZPv6#u7g zH!sEfKXt3kSHl0PTg>0t>(z5SYkU5^S7$v}qV4n9dyzeU^Jd-)?flH&?bG?dy;{-@^oWB#Acmw8Nf`^nml*TDa&nFodcQ@7duGygAc{GXcV5C0dp z9pAgww&VY_y~_Ul!T+i8Tlhb9jhzqvPp{u1TaOa|r(SIHfAN3nC+zvd|LM?PiclbXw{tf>Z zH~vq(-sayi|4+^D_pHA5Bi^-Jw%fd{qrEvk{!jbY+vh$0FK+w!&%4pQ8vak)>G!|e zyWAh&x{Vq9pPKo5_&+s|AOEMu=i&e2e)x?3<$Ar@ZhyXcH`wE`pO3v8?elDOzqs*# z>gqKe!T+gi)^_syZ@yjrPuuZ+Z~y8_-_Clz_&?o0^Uv^q>QxP`!T;&!YkVE^|J0A$ zcGmxmoB4mbJsyzxe`@(Z?f+Oyd+>iNme&RUN5A*$o6FS;o3s8;`_uS8^-}x$_e;w@ z@4eVO82(T9S5w~{{GXcV1OKO%|5MjBv+WaH_PuEw4t*49sQ&*Y)#Q&+;j{j3HZ)~^Et4I8Jwe{`6|7kmo|I_CIj}QN+ zZaU=uwEs$5{~7Vp(}!m6%6-9m_LS4Y{6AeEh12_m`G0XU|4)st zWBy;<_&;x(k9hxUFZ=PCm&p7-oe%yD|EHG!Q!{@K{}(s@PtEP|e{nPaFK+ywn&Y$n zubT5`{-2(I8vmzeJzVDhX@4637dQS-`*XeE|I|g3PYV7|`xj3+Iru+qA3vo}2LGoX zH~Ey{|J23S%>RoU|EK2m_&+ti5dWthVIC0wryga`7yeI;@5BGajsH{Q2l0Pu_Q(IJ z^UC{#`G4x%si$P{f9jGcS^pO|{!fhu#Q(*O|5Nk$@PBdR|J0}3=L7yvT|O@B|J3-t zH_iX4`MkjYsmDz0liB^vzbAU=fq!_9n|NYo>BfJ0mzMR;{G;(--faKW@_#4##_5@9 zI==j$UjGT>du8x{YSu@`|Eco|P73}{?;rf%wj)32+Y3gXoO$k^o*p!$U&12{8Gu}=!|IfXQHS_=CX8m7v@u=iHHhf@wymY6%;905lUe8ReXPlldh|h|T zpZ0(0{Y!@=eP6m~rRK@a7?6Da4(H#74@~;AQG=7O$B0y?J>cOyUfTPmJ3ap}-Rb#< z>Fw#`{kIdhXfN6MfG4$?fAOCcO@x zD83#_M++XAL0Mh_&WSw+|2)r8~+zK{!h*EnEw|y{!fixYuoPmM2R{@)imPYC{x^uJdLdBmPh4!{aZw`Z{ks-Q|yd+?(t7!7bN%Pd1N-|I_X9ZTLSm zzU_#jYrH4f`qX(>UhQ2rW>jYDm*+?4GbHnawO1zksF$wr9#Jql^U4ud`t8S**m|LJ zuk`1i=WFC$S0uWq^>Xj&B}Kvi>HWYwz*+BK>f0xkjLFPBt*6V1Mg{+;*LQ4DUhscv zoT&-kQ1}rylZuapV8uw!feF{jtCO{ly!fXn())KHL1C{r$&#(uHIA`;j;6A=}@d zyzz-q590sScqaUxTJ!(ZyngsUHMhtA#f|?{^Zeld;%5Gzn%m?5 z;>Q1}@sRjGHJ%Co7dQSd?w9|tDbe^pZJ%O(4F9Lb-{Jq_#{a3A&xiku8~>-qzv2JX zVf|q9f8I8q5dRl9{!gv>e{tJ?`*x0RKl^**)9`=VAD?Hl!Mkto(-wT+*_RY&o|)U^ zjX%TxX*=ilYx93SU6}dGJ@tt`X;Gaw{;Q*=)*H_?rL)GH^ZU-O>O|xJbbgxu7dQS- z&Ah@vzpwDy^LVypdYbio-+XA5?@w=CvC@0i<;9stnpPxw{>J6r)66p#?qBA8`V~c) z4?e%t`}`}$2LGq`=XvG@@qcO_AO26x^LgQ1}N6*U-{!cyT(t-^BPmM3e|LOc_{9oMoKQ-?k{GS>xi~m#O0r7uv zKhk`+-``Z`ADaKu{mcKw{Z#Q6{Pmo6d6E4--{%wE`=(pH@qG9{-JZt(smm`L7yO@k z>ZPT@|Ealu{GZOZ&>sKgN8Hf;_uJaTJlUZa*m~ssKj}UF<~e*n-Tm+xwZZpY{l(ie z>#x1U`~KRh%pZna)ZO-O*85det_=Q9y=dX1nVa64-Oa!8KK=d;)4ue`L&5*4?|ST! z;Q!ROFMJ~SKlPWEE(!imeebG@u>P-(e}83FhV_5d4_7t>|EGT3{(Tz%r(R^=N8ta| zOKd*D$Df|!y|SqzbKl=5c~`Wov+s{>{@d-s`qx{`$sP-=FWV z`4^scx0LH7NmH}i|^`%CZOKg|E>^~TSbkMR3jZ@z5rzyaNR2i67ON89>o z-gqedU(fcv!T+i8eE2^#z7YSXW_@P-pBfK^|5Gzx$-W;>w0(c<&GGSn$2QdkABg9} z|Ecj?_&+u0i~m#Oz3_i(o^Sl0nt77=KlNJs{vZFR4)cJ_|HX~}Q&*e+!2iXK|NHHq zvi`5a=C$Dev>iWz|5MBV#f|^d?ePKlKQ-$U;{VjFKZyT}8~>+fJ|_N8&3w!!dp+;X zdan3C-9OJS{!iU#uMhq&Zv3D3)&s%+#f|?{Gj9t2r)GUq{GVR`HTw?+|EFGi;K|_s z)SM6gPwxjB|EKGDgUwUJ|HX~}Q*X5E&wPt_mpvYvf91W-=84&SEborZcKxdic^ zQ+hq*&HK&#jd$zTeaz?b#+%vvF7GCrch+y!XS^FX?lS*&y*EC_)(1_reLj2Rh0GUu zz1<%Fr>?cz z-+714|2y>gR&8G450~2fzeCNup-b+|`2K6{`p5t2_G`>{;Q!S40$U%}8=rvx)8or} zg}vVFZywIO&eo$hpXOa}pWo)2yc;^V1plYw)pu;h*ZKC9Yd7(HdRN%~_&@Ex(jE`~ zFK+ywy4s!({GXaXAMk%_ya)bI&H3{`b&dH6+de7TpO~!1SD3e(tmlj8!=69yPJ6x0 zV@}cbwRV5@`g%8;kH`P%crE5v@PBH~&#q_RpZl}-hd1lx+50Wg_&?p>Dm%V;tSNf^ zSDH^+cbm=sJ9Is)u*dtyf4)3Lf8H-OpK@gJ&%76}*^oKu`rmmkvDb4%<-fgGTK9kZ zsHwXB3fmw5r}Jk!{x5F)pSohrrr`f{zLgzYg8x%&n>{P~anQ!lgmQ}{piay$PA ze|nZTkEdwGoT+-e%k25uxn-Vrjs5)aec3<@PBId$N$C6`oC&CB>qo-UefqK zHJ?wl)BolB^Z8^xyIi-&|1I5dg!h__o6Xl8>D{(zbMSvU9*zHtyZ4Vin%Mug&SSjm zy1Ftieg0VQ`VHaz+tYS^ulh(YZ~PnnPv_TUjsH`(*yF+fshjNj#Q&+8H`jJ|-*R1_ zRp!s|f9e|ZgZMx1jrRF({!d+NkMEo_2bb&mskQUXId*8Gk9lR7H@@xNx)I*^wim7+ zmFT4l$MhWEw&VYFzTBSmfAxHFd;Fiet#d;L{}(s@FK*WVRkz#wjrD)k)z08r#j&Glj_&?pB{GXcjdhvg1)_-OGpPKbn@qcRO`QiWc z^I~JWt#5nP9N$jk|FnO@A^)dtG_QsKQ`fYu4gODEWquC-r>-+U#r(gx@qg-?x~%`x z`QW4Qf9lG*?EF9de7(B1Iru;ILR)VY{}=b}-+t2j@yfbP<$)W#7u7U|^?#?|Ss%RL zBj&SM|2J;@pZbZKrZE3c$EWdsYL18hQ!lM=$!xpk3*Ia1n}Yw-<6(Xw{!d+F^XORr zS6yv>kokXV{3GlCs_}sMKRtgm{!fkXWB#9dMSWZFe{tXOuLpell7_b6|8)H=HQ$H- zQ?InY|KtDE%kA~T|LJ(OHLbz_X?tC5TkwB+zw`Ry|J04<6`B91{To~D-xtjPsq30- zo}T$Xb(Q%z{GV=LZR_P$ZM6A+hkpKPu;&;5r*3S>`agAxJ)ihLb(38$)0Qst<6|FnNiWp@2vb@l4({6Fui+Tj1x zm8+|R|5I12tjb{V^z+%O6|v^3R=A6TBb&-u<=Ziw{(nH~jWf)0Qt= znHh3@o%gb(D>9{x^}hcq`~6h>pC4~Y*8izjELoB1Xm0ZD%N8xmeE%U^yY$e%PgOne zXz+jf_py(iGbdx~-;}FIOe$f09PblH4-V`9YP`qDk#g=ME?&Ka>c>a73M z?eRS=N9|8+pY!LQ#slI1v_I>I;{WvcOQsIU47%<~-;Q@$c=1;g{pT~D^5*u}jepvk z+rKdC8E^a){!jNuGyhM`@$r9Z=BwTJ?$@L4pZV3B-|#LiH;?z7=e+T6Pk;4!Z@ggP zwr_gl+3q<@~XySwD8( zJ1_Zm?(ZLkFZ=m0fA7;nUh$Uy)BWS~PCxQ{zMb25z2DQ^9{;EP<^STw|HX~}Q?vdo z{!h*0!~gX>|NVpiQ{(CIf7+kNhyPPgoqQVeUA!kx9KiR#-kSfX{Wbqj$7fz2{!cx1 z@~Of9so9SIiyQx^=6Lu&HLnN$PmMpt|HX~}Q?oz*Pp$QT)tt|TufOZ>C;A`H|Hhl^ zxntjNz440pKi!`5WBy;<_&+rs7ylPG{x5F)pBm4L|BD;{7dP|&)CCiJ2mhxooOELF ze`-Dt@PBdR|I~Ot{9oMozqs*#apV8g<>Py22Jh|ZspEQOUMcy2Z)e`>qV+vpSbRcQ z|5w*bQBL2?U+RwV{R_+Z9xiv}VEfmXC-2k$9nSlerRJ&8_&@mE1pXC&Ho=iBIyrHhb7N9-Rb?)UNHYK>kX&9SGv>d5lSS7{S&uOd%FK$@0UK_q?Er)&$~-M-t_v*qf_TQCN)3uaOay|FFC(o za-L+)u;Gd4Bi(qX`1!^U#a%ot=>=z9a#3RYr!KxY(F-oPAkn!gKX~%^yx{+4?L0Be z|C={@P?-OxzG%dNF#k_IZRpUj{;zua@ZrJ#sYj0<9sJ+=-}MgukH-J0hnUa8|EZa` zhW}IN+PpUWU!qsvb@2H7-ofYL`xZTUXQFrg*O$DRH;Dh!?FZXD!DFU<(YG@%aQvt5 z@Wzwj|8#uj0pkDS#{a4DQ_TO18~+zK^Z(R59_Ih4<^R<9H~gPk{x5F)pB~SQvBkmv zY5UC5lHmW;%$H>SUp3wj|99TKy@LP4ui^jHcrN^(dSKD$;Q!QvN^*k#Qx_EF2LBf~ z{!h((L;Rl_ABg|+^Red_{}(s@FK+x_-1xt^@qcmS|J1ymkIlWx?;ju7_mV3QZr*dk zw8u{Q{xm$@g0EcR&FkIOb-DL&^Ls`Ay4-I+(w<-ZpPql#v&H|#jsH{QGberPGViIj zKmJeK@tOEPH9nL1e`=mz=KraAy;%QOJ+*jj=F3lAd4SCS`~AZ9;0H_1XgBXKk;s4b5H~gQ@hsQgh=Ig$lesArw-gum6c6`m7^_KB}Iv(o}+uslU`6{&gv%f!j z;}`LN+MmY%shRh+^_GLaKl8xs@2}qYIsBjY$N%8})c7O(U)=aVHMeK}pPJj_|J2hi z$qD{1Zv3Bm#>Jz8|5H!5d5iczHOIsM#f|?{7ut6GpSsxm9{x{_SH%CRc|7<(HOI&Q zspbFF@_%vT|Ki5~shQ7*|5I!JU);?9iyQx^#*^Xy;gnbW@qcmS|Ki5~sZXDmm%;z3bIqIK|I`IGZw>#a=Kk=1aW8nb${Wx3 zmzOKO@qUYbw%VKX$N%Z}_(uGn`XcjS_&+_~x%T++e`@)^xbc5#j)(tKGw%=or@qjR z|Gn=m@xH*0zy9sT-rWAaKP>W=|I_W||Ki5~skuJ!e`@ys=C>a8$H(W}HE%rPJ;mPN z_&@DG$ll+~|5FdP_c#7e&3fg}-SeO~pC9!LAMl=J$H)Ka^NPm*sf+FTFTL?T-=BW- z;d{Kt+WQUv_y0(H?`XZMa&LQqiipw)A%)bP-Ai`Q?&*D}?VVmoCykI0NbkM(-V=Hk zJpuv=dQe~WAQn(TL=*+|ps%7F6;$}{YwrB+to6KOypDH#`776$bImnZdDgR@y{`4U zwLW;k-xm9P^UUu%cEh3spz_CT+mP)-S+2^=l_~{JotV&<^$sYiCfp#1piOmp`l0c z|ESqQ-e3Fris1i=Tl6Xn{vYpj#w+_F&g(o-Fdb5n>;r9=)Y^62i-a`_XIY(k~C zH_n|Ey?m&P^YA<8Me~1H<~(M}U6waf>O5t|(&*8i#m>`LudsZYLg&@1) zy?;*rpVq&8_nzSYiC6C3XV1U0y?yh+|F_egC)x8uZ(nWCv+Vhz^BT*; zu;-7?+wXmt=aUJx=ahr<7x^{ErVM{ z6T$yG{iUx4|4;mo==I1|f-e=G6@&D8xrv9%OzjWcY|33HT8z({@;Qo6aj-LMGJI?qXA2$5jnfh+{ zf9g;ESk=ovKllE`li_*b4)YUNl)UD=+k80uKlR^hd5ide;v?o;;{S>F+5W}<6Q8yG zuuB(y%lRJj+wlK1fA&BApP1u?|0jOHd^Ym`;*9_2Y|G>Si66A%hySPj`LOw-&JTNDc21waz2;L`{)RLD1^%D< z@3wkh_Jx-}a6#}3Z3tzH)XpO(MV_>%+8eE9{NHU9>MbA7Z9=&`qKHPKaKY95Q&IjkIE0^J~ zIZt1)oa2>X+yBm!SFdD$I!{}-20zSs%KFt@ubiiD2=jkd>%Vo)3g+WHZPhZ4uk)nU z@Nb?`|H*5X+wbEj60^LuSBht@TgCEK;#q4~GJb;b|I|Kr?Q-TG+Sc?f=bpzg4a8=W#1n zL~S;{QmylC%<^SX;S+B;kG12|^XGqZ9=~d3H0raTI8R!+GAccCS&f#TxMD^0{9{)- zb9{4dYF4B5O|$X8T-e(AmgUR&zO2#wSl+&Wotd9~KAf44y&vE_#`cH3Z{R$^&hO8U z?d|KIwqaege_p-wbo)HC+1Thj$KHpy|JYdPxm!2e_D^=6zkPe~|1|#vJ9h^EPxHOQ zo^Rv-iSOLKpW{`d{lCQWcJTki%MTt6{+~WC^UW`K@|~@|{DP+XgU(AW-^#9!3C_9c zfbYK*=GR!Qy##Og%5m?1yXC3j|7m{ntzIhrpLnUY;G{(0YX zCO`T+hkoSy7yr_HW#?1(e=!>L>}v_Wrv43Q{No?};+F}w&#yE7^r%aJ>x>_Y|EJ@J z---VhXZ$}g{v-8&#fR+v;b)J01|1Zw?f8v9-fAIgr954Jo zeIB;i`FGDBTGr}#!yCTR+8H0!?vE3U|EK==&G>)f19tz6|0kv$|1Zw?e`3bR|I>W% zVeR_tjPHs6r~945Hr^+T3w(P{*!exNN1^jk%TKdBU+1&;Jr?r+wEg$m`9}R;F+M8( zpP2FS|HSxy_^htDJapO`#2{68_i z75<-?{I$1s4|K){#Q#$}jQ=O5UM%^4amN1>Q?Hf!zv6v%|Azl3K5g}R@&Cl9j-3wq ze`0*DUQdnlb{PLp_p?V2p9uMXx}QFL@L2Hw#9NLY5B{HcyDg9Z=WMtvJvr|lu14*yR~ zejxr|obms}doTEZV)ifopY|VqApW0tpWP4R|B2=QiShaH|HRvEJo5i^e(f-S5dTli z{W$)gc(aX<|EJ~gHP;ku@^+Z~KYboK{`h}!#{biJ_@VfJ;$!CL;s1%LpNs#e6`v>y>)PKW{-68)^ymI4~kpCxMXMfKi|4+Pr`%dl$YIVPI=Z@{c z{}bP~aYKabr~9>K>(>YWPrPu|s^I@Uf9h!P|5n=l8UCMm`O>Aq|5N`JOBO}%tU2l9 zEnmDaIym)|^PP9y5%T}kf1$n4`eD`?Z=Y=Kt=>QD^Uv#A6Z}8@{jY6hM)3c{Hx)Pe zf8z2I^X*1|u~vVtqaG#se`4kTiShgJ|HK`w-Y@>2IIXxT|4&Tb-+S}FQv1?|dxFo0 z|95!ulNZ_izg`VbIm`c3fBAoL#{UzOzxUT>&n6iEPwn_U_Gl_<;&s! ziP?Yl{MEOY<8|elH@zLU=eN%6Kl1;yJWT#yobCB=f~o%-Z^!?O^CedQSKMIvc=&(f zp_VU*|0ibqdYApy&u940>A!O(Ul0FJ{bBsSIREYM?1;q!|BC&u@~{}UINHxK@wIHUXq z`}@(~y*=CN1>^szoqRs>|Kd#kpSZH(hT#9j8UIhreDMFo_{CrQ@xOfj%xCVmK29+H zpZfQ+JVN|GaUZ+>;s1#Xi(3T$PfQ+Q_q0pBz377fr}mQER>A)hSLP)1_qt@Yv%kJv z^#6*|llg1pDaG3>GSd^>C8JaD|KzjC{}UHyr3L>_+&4YxL-g#B^#4lJlJhCCudHg5+<*VC{$FZ-VXEJl%BlN5)&FbXHtGMhYm+=bayur^$D*uc zzF%H(((mb0pY;323{UdNVFMHUZ@|#{1Xp#diPomCeg5>fuMfW7pwfcqvS-&g*O@=N zeegxj?UZhQ&T4PZw>-dui!X9+M*HCZX}l~ufARmsH)f>=|4)2VPG<1`#929M!T%HI z6=X(}&Hww&rPl}l4_^)cPmC{x|0l)|{M8K?IkTY2|5H2lRq_AC_+j{eV)Fj*|HRa@ z#s3q_{}X3rWrh4dF@7WdpE%9xz2g6g8K3+=F+L#vpP2E<{}WSx_p=qZIoIVk`G0Ef zQPfobS6p6H9Q;2qd2aZB9U87{%KtOp4gXI}-W>j)7~hQizc`cs7iaSS#MF1i{}WT+ z7XMF79^d4S7a9K!|4;M7FT?*6hrB_n|EuE<+JK6|0nKQTo(MlIB$G!sJC}1E=hd8Q|tLw<|p(0QaRP<%g;+*pHkb4i!#Y? zK41S)lkb;R+9~*d;@mEo!T%Fi_RNTW{l#CNU%K$#@cXBxPj*!HwKttB2ioWF`@e9m zvi!ea{NfGgn)>Xh=zss*xpq)aWcRPW{^G&e+}}Ev49SV`|FnMc{_y|AK z;ZNcJ#ToxkjE{x?Cnn!+!;Hs$Jo3$2E_%$Fe6vS4JnCF;^-#O*f5ds9`9nWG`>-?l zd^4YTD8c`F{y}Hvx96n?5}fwN{m#tqtMA>HU^_O>jBoeq&V9{4vv(W)^Nc@t*F9&Q z$@lxtm(Muk)7|{SX=mE!{pgf4>wn=_C!M=mzT{2spK!(xoE=@{?j!S~=dV8Q?f6#s ze>$JYTbrJL)Y}>VnVKWc_QDY3{-3zMvC01vvwiq~amN1>vwYvH_dByZ{-2IF z`F^+O?)7%~Q&oE|vhB}9{dPN(FNgo9jhxex*^1JJ{JF~x*?cL^# zUwZYKtqDH+_!ejU;qvpF6O8|-?UVl}#&7=f?>2aQhWULP|GwTi-F)GepS{TV+xUN) zf0^Zp;{SJQ`p#d*Nbmiqc>$N$rO@dfe!;*9?% z4xhIjcli0i=W+NW^PE{8|4;qlyMH&w+gX0V<+Ghx{?F+%6a2G(-RjF%+Wx-8^8Pd) z*HipIdxjtUzmmb3!T%HI4s0F#KXF#S7Qz3sXS~7xYdxTO^wL9v&wsh_c$4qf|Hk0| ziQ5fq85KP|;5;>5@JZ5#wX^4`{hT{BWJR~N>+9UQe>g|EWD=nB|k2|0m9Du>8ifYUkXMWx@Ybd%>8B;QxtB#?(g#W|jGT z;Np8roa=5G8U66hBIm9XM@4g67CH}_Jv;is@B-(CdGn%8@8|jYC)wY#JLTj$PcxqZ z|4;jO=IV{n7jv_m7w|s z6XXBj|A}XB+Ccr!b6WrG4Qr_n>O5=x8uG)OXRKdNzL@j$wM)%k>EnFssyp$MoTo0I z&-Lw`u5S}p%*R)D9XO70tajuy@)_lgVKBxUxF?nS4 z!qkVJ)Ase4Ji_LC+_~qJk@#!gzyH+HHlNi#9&G#HdC<&p>`&*xv&M6Mb{;r;bY$D> z4t=Pkp6|EKmUWAguWe5)rm*!TOls&zhfo!l7px$2c_GGEAhfyWoV<=k`Xh-g9M zpPai}`<6u?JJ(HYj0V?VR^!W08Xo;@!j;bbri_aEe&dE3t*_6d5msNWm2+3?Up1g( zjrLD>J3sLMG~aGh#|HmT+YS^lj|={v);H+38NvUHGyb1= z@a?w-|4%%0{>_%|EKxkGurv=^PjP1b=3KP zt#h8UVLjKc8XccIwrvakpO#->zM=UC-hb}4y}|!e`}~~;?DKxW*S~nrq3GuGgM%xAFwJ1;(PJbHWG$(lAFAFcgV&aHJT&98X)b7!4bnV-?M^?iQ4R@?o^ zXYPH_d7JU3_aF83;d4;`SH}yc{;znu&Ub{?hsIy^rGi`tjLs_Y?SkI$rzkdpP)iy8qc_^)B)M#5?VN4gXKP%f`e1 z6YsX~Km0%O0lS~T{}b;s9}E9a%=-!C|A~1&0sl|D%ls_-zc}OniT9m;F!+Ds17{x& z{-2ontcHpsf%8&)K#Q|4;KdV7@E-k6XVnU zvb45V_h0-TApcM8%n$!hyw~P~|0iaDZTg>{&PS~M-RFBdA0V&I{6CF<`1rlS{}UfQ zd4KT##0MCAOA1T_lf3sXxct@^PJy9X%1f^!TCHQ~h+0!Qm|4%$?`h?*BiDyh57yLi*?GqY<|EKNgZ}su){RH1X`9)s{ z{-2(=;KQV?`eLmZ{{;U}e^0|d!T%G>{}apq6Vs0WCszJnobmtk{0kot|4+>N@c+bN zK9>I{mj5SK{@+Dz9{fKsz7GDM7=H-=PfXqz{-2n7t@wYMFO2^u##h4s6BpOs%<~&( z{4?_Z)DGkSi7RW`2LDf7RogE3e`5ST{J%Kk|B3PY@c+d4Y50F){6qY|IOG3`YpdG^ z|4&R_9sZvfKM?;`HppYh`aFB|<6XU5Cy|5Im{f2HzOXYv78=e*`jJ|O;|*3a_zf8s8d|F_{^uX}&? zuRUK)F!g`cpLYB|F?o0Re`5K6amN1>bA0jt;*9?%W_kQSaaWr!{-2n9M*Kf9`Hc8~ zVzv+ePvGQ7gn{lzt8{PnezevPwnNEmgi{se`5K6 zamN31w))!me{shD6Z82Rv+^&__=1<+{(&=}*Dv4lKhAufCk*+kb52!@==0tF=8O;g zbm8Bf$@`nq;X`NYF<*22N6w7*+^7DLVEjMrUwl9Ozc}OnY5uh1|HZlGQ=d53ls1ok z(-76Ey~_M({6CF{Z%zK6xU}fH;QxsW^R5Z`f8yeT>w^C$F3d{$XhqrW?5{5u{lCIa zNk1>u2P{uZwx=@neaZimAA%1^{a^9F%l}LD|B6!T@uvEA|3`h_lzP9Z`G2X)r*f+Q zmddHVV5-lSS}!-1Q|s%d=HdN2&T5s+%S){{oH~B$`b$#wXX^H(Zf~kTn98ZXVaGPf z`oF3C@3t?s{%zeAVc6i{|A{*c>J$7w@fBqS!T%GJcS-$UaaoHN!T%Fqoz^n=f8u8L z`6T~Oj2}k+pBO)k`oCiQKkEO+8UOE@S16`N98-GyY$k@&Clk7ynPp{-FME zoX72$?Tk-I{-4^(7sUVjTgLUl|AX=W#Q0(Oe`50M@c+d4Z1{g-{6PFaG5Lb{f8qgF zzZm~d+}Gxh|0l-3!~fI#@bmEh#MIw?#{54WpY(#P=$n^cWcvT0aH6;4FXI2HKkaX? zn~-4Y|Hju({a-Q5Q~y_tZ;AgW=6K=%X?%_c{$HH&|HQp5?-Bn`+|QOL|4&>}Qy%<3 zaku_Gga0QU*S$9Qf8x<~Rl)xgk1Q?-^?$X$hMT{5|Br_F{-eHd{Q6Ot;=kjo$J@!T zjdNah^7}J4E9p;H<|VH`J<80NGXKw8k}|HM58Wd#2(&UXKLUQGSo*S?VCyw*SScIE$RJ}~~DWtKJ7 zCpI4p|1Zw?e`0(;>i@=>`oCiQH1hxAZ28{_w%-T7zvyqjADpR&i~pzPVf;TazKs1o z@&5RG_WQ+|JT3e`^{3r_|9Ct8pZz{^rrmx&IphD??<;3~M*IEcjBkVgr}5c;_miP7gj&m2=jprVJ&bh&S5&S>( zA8PrB_I&i4MGGrre%tH0!o z54Q9C7ybOjH+$=Qk2~X|mA&zpGkJOVe;ObE3;$0{z8wCac!>E%_OSQ7j{vHZU{wag($Ny7*82?Y7AACgoKefa7e`4y-;{S=eTE1M)s9nz8Mwdj-Pv7ax_TvAk zKjY#5iHpn^J=1ZU&oAH3@Bb;<>fG79LYW|2>zeAdVH4%|1Zw?f8riv%A*Gk^mOhzvLx#LgYM4c zBmU-!ZqDR!lK-dm!}x#Vtj65v+%r|)zmt9cjQO7m=Z@y{+w*-wJRkMrKicxD{lKX6XR_n_rVJp0T&&Rdr+3jUwYkIhT(3jUvX=AyaOqdKS0$E4e*^L)#> z-h3|d|J2@dQe*J{#96oW!;kUyPGftS&$h`qXH+-*8t3$eYWy4L)(u^P|EKx199kCq zKk*HAeZc>VGyb2}-@c(F_5$IB{}c0mlU)zb>H1e_znAd; z#O;S>;wzui^%f@oPu$AB56J%$x3%vR^QWBK+wTMOtDM^m%p!lyIn#b$Sw5R{wvA`? zTc6YVI}FRBzN_=i^=bHS&h72{&FaHCr&+yw^K+a#S-pGneVo&+9sf_`cWf*V{-3x* zLz($-JG`Ciai>G85^R2+bFSV0|K_{Bow?q>Fg4pb+kTJX|7rYO`@XdKKP%3(`vd$x zahCb{mhbkg?@#+ZV|jPah;O#vQ~VRN|E#@IoMrDf+45E5qW+!ics=Bt*Q*`HGD@Zf%4A=WNU4|B0LT>Ja=tamQ|Lg8wIOZ_l^z z|HL=;Y-@iXxxu-)?VmrbY2|!b&yJkmHQGP0?H}hW`h?Gi^B4MM2mep~X~+K)f39~% z@c+cu4$KSwpZNMg1tI@W{2BZFkpCyX%?YMpcTu&(xb+~}O%&^`L7q{J#^I9t-|oPkX+O|0k}WIVt#myWcz({J){MO$+{?c)%TVBK$uc zuVG6T1piMwZrMV+UwYK%H(|wMyIwuvOkQU3z5n4nZT%|FH|Oz|CwlIgXPs}^yv~l- z^Uf2tZHneh{!d^3#2s6r!uP)EJZf`iC|8zS(T;@67p^^9H+ru=?z^YTs!07o~kKb>4LPKJ(o_?M(jS z-(LGnf?qxRS?5FM(>*i$bIu3M53~C>XY#7;{SN1~c7KBZr}=KT{^b9O@f-2~#HY+Z z!~YZWJ_Y`tnEJ8!f8rx{zd`<=wr`KMQ~y^?zAyEE#kAx9X@A4`e`0*PD`s@?{^Z%c z*E!7@e-i&s{qf=O|D0|A;s0rU_@nrLVtmk{H|IGAU)20RZ4c|i{}Ugv@$mn|d+q-B z$6ZT&dHAW%l_ePeFWw*jPkj7>|0gD25C2d1XZU_yFX@_K{6F>Q{u=*JOn>}8G5Z7m zPrSqKhpisH^I^+Nez38>^AS5g$^Y~9+x_C~-_?6N_uKe?8jt&J{68^1;P$=^&O5Ds zE&iXz!&k%qQ-AXN@c-g`)g5D;4_bcS?bYKFjQ^+c$m_%Z)BWw1gNK9vC*EX?|EK%y zjds6_|0mvHzkl%m;*9?nXZ$}gXZ$~Xo)=qQHuZn?`JZcf($xPI&sedH-yhB^=FbWKpW2ttn;rZ=@$}h~ zga0RpK1Aj7ydqj|M8V8EdTEUcj@c-1mEdT0I|5x+NFS^#Q-)DV$ zaywrg{6FoVlEQ1Fe?EPW9}j#J{J)=n(3HqFV6UXV*DTcKg}1${}Y#0Gz|gFkX+|KR^=f8+b%|B3P2@c+b&kN+o@{}*TcKe7BjG5()D z|MYfzL3=*x%y{^J>d*4{e`1!m{1s=~EuY1icKko>FUBMPPmF(u|0gCd5dTk%4~YLK zmj5TNv*q#s#Eg&sCuV&7KQZS6{-4j^82?Y4SJx)^e`3x@{J%Kk|B18A$HV^<Y>KRPvzA5!>RRr|NnBT z|CY-CuRdR@U-$1g)z3@if9J<_ZrMDs|57%1Q2>E~cIT<1UPn?&X9`gUh+1c44|1Zw?f8vfgP5z(8 zPs_FE$>#rwb93x@ulaxCyj=Txulavs{5t$UG5LV_f8vaS+~EJk`G3DW-`nx;KK$oA zXO_qR)BKeGCzk&w#*f7R6SF_?|HQQ8|HT>q@1=h>`G3qG|4%IcPfT7Q{-2on;{S=s zSH%AlXLT+J{-3z2FhBTzVthjUKQZ-a@&9~&=G#5~%K_Guwy%r}Z-){$HHQ|9hq6`j8LE`v3OoNN4u%C%L12JkGc5k)xdP zG4cO29~l2n+`XU)h*?&w;GJkYrWl`||%mE7i zUw-$@sA}(9=U*OqfAISXd*wvC&-}`{OaIJ}|EKnf0Zsm&SpJ__{-3y?6_<^PH0|B1T}&I0|oY_D4e^wJV_>|S=W7zv& z-cG(B{-4H!@&ClkAOA1T_qFV6UXV)FFx|HK2$m%{&xGyb2>XZ$w&zc}On#Toxk%Tv!4|4)oh zi2o-ZXwO6O|HRY>#{Y{m{-2ojjzc}OniRJ&r8UIf#|4+>R#s3qtejRK2PKm;{U0gda(F^V&;$k7iauGF+M2%pIH8%nEBxU ziOEmI|I_^N_3;11d>-)s)L;33V(OFQ|B3m0I1piOW^@jXE=L`OySpJ_F zKkvsyYrH=^tJ`X4=Ks%AE1j7?{-2iT^Lx$pOMUxb{6B3k*Xs%9|A|>1|1Z8g{-4@e z9{*2Fo*(|7`jg*>|EKl}yT0N7iK$Hmr4|M53l^8dPwEerl%obmtSjQ=OD zwEp;i;tKN#@&CjHql<(87iW7OpJ;Epy2d$gWMT0C)E_?(|4)n`i2o+GC2JTrQ0e13xeD=*KNr+wzk9Ouj-!9Vcz zXAVgV{-5?|*3eGD{}a=G;@VEW|6%+;wU>=55B{IHWJGE3|HMV+PvifIOGj6b@8#UZ z@{;iXbo|NJ!v7QZG=B>JPuy$vgy8>)hs>K9{6BHyowo)5Pds(eUG_Y~^8YTJU$a*5 z{KNA9F7P~iK63am%m2H;cUnFg{-4gzyX^UkJzsWSaqyt!8-3P!z2!aN{~Z~7D)@mL ztbVfP*Ep{;#{XOPAE$y3xZa*O;{S=)T0JcMKk+(yUWorE=J_H1pLm-+-@^YBQ-AB$ zJO7km^8a3}I30YzgZ6w1|1Zw?f8y;&jt2ivyyNIGt1tGZw{JAY|9f=r>EIJ?K7Jzj ze`21u;s1%ZTD>aj|B83m_EG;=%>42H#2YP71OHF!-(t^a@&Ck|&)#RxgU|c+!EH}H zJ z)A66OXngSh#Emls1^-VxblSk+|LOecF|s!Jf8v5sWx@Xwr`!FzJ%2kV?l?3(_zi|?wd4P(9mf9? z=QO4T|4*FV&@uRb&co7!|0m}9ga0RPYu7XUKXC`kyTVf8rX; z6UP4&SDWvT|0m8Jl^6U!an8tGe7NVdKH4qoBf-x%HB_~@tuoozW9IYpEZd5{3tx*8|EKo!UTuQ^C(i5>j&HS?@$moRjQ=Oj8_h+{K{(WkF0L3@EsG3|EKY?ySEPhpE#p;+u;A{`!uab>)`*1Z|dDT_=gfwpsQSL6&PAiEga4=d zqmr?;!T%Fyjp-T9-*s<|IB!DV;Q#6P^qxK{`mel4eSR?hpXNX0wu!<2i!=V8xc<&* z!T%Evx@&rL-)rZ6y!yN51piO#Ygl$i@c+aUS1k?xpO&Apc17_2#Ix30zM}bmI{#-| z{crp~@jSa{6DR4ht)47|4-Wslm92) zX?b+`f8yPiH;4ZxX8q*MWqFDCe_DRO z`E&Sx;(g|8lK-deA^)yyU}s+*wtD5x$IRFK@b%&Z{@mE9 zRnBZL^?$YgL&oI)iSaA(|HSy0_vr|HKFE{KWr@Gyb3Wu=#2De;N<}4F6B+ZeLosZw@yvp8p zd3ohb=e4``SYG(7THT+ow){B!KQX>B{-5)KgTen3ueN-6{6Fz}yWb}NPrT(wlm92) zYrHpik+;M6e?EW9E5!ecGyb0#|B?JZG4F5T|7rh_Z;1aV-gfv%@c+bnZF&4Z@g7?r z{-1c;-aWzp)BfMFe_!zb#JjA1F8-hTZ{Kqu_yRc%#*?%^tGV&(F21SCbd+yl~mlkpHL8+Z~G*2LDf=|G5k21piMw>y8<`U*Xr& zsWXO0ul#DK^Y}@FqECNwm-Faxy`!=Rc01P(sf=#jw#Rv(`Fe-v?se{FKHj&7?sM+m zyHoK0bbYVu(ZTNL_t)zCExTun=%f1%B>3Si2c0|hyfGR#=aBQw)mKGV4nFLhUvXVD z?)Ag9`aaDqzb5#9;=`}@h=zJKrw=j7kxjQ@Ay+IyYx@vOd1t^U4-uV?jl5^R5; zuhrl0XvhE4-{)Zbzc_bY^B)Pu|BJWd|HT>qPb~jWto*+?;J2 zIOG3`E4wrc{-3rF#{UzuJo$g(BJ-Wd{}bcOk^d(qKkzf#U-0qqrJh*+4d;CG-^Sne zO=t4iu9)zx1V1_Ge*n38UIf#|1Zw?f6lc{{$HH&|HSxt__z8v{~;tI<@#Qzh^|BEyJpSWAy z&B6Z@;~(PxiCG{1U!3v(#Pa{d_ck-;QwiUWnEhZ|4)ohO8#G*@&DqC|0gb}X!8HW_QiSaa3#aDWrSiWUzc$5>tGPLu50yIq%+^Vtuc~!R`)k<6JjTjaEfSoa(myr- zFO@S}CVjlT=Jx#^8$bW1WP9rPshm1~s=t@YsmrJOgsI%3W4pxsTBarI6{q@sX(>Kw zT8CsFV5$$8(K=cGI+b%eBz?oYwCv#jt**Z@_9q6wCU_> z=YskH(ed(&Tr+lbH0{VLZ|^dqG1~RQO6Sgl21Z}~!wTp6u3e&EH^0bbS?!}MyD#_l zvaA-t|I>U5({2dzw2x6I29 z{+~D_uORq;;_S{v!T%Fi6%+>lPh4UB@&Cl+#gYFfCQpv~zgj=_YpMS$#&5*`6I1_~ z{6BGSen!au6D$8ujIW0OCuV&7zc@eftC`O7|L*?b4W0)`{-2of@c-hB|0l+8#Q%#k z`F~>S$&&vUXZ%00{6Ec){X_nr7(Z{_6BC`O&rAJZwbymdkAC`@B;)_7y|i;-@c+bR zg_fUW{-4(0y|^&=f8wr%1)=`$mdkGl{vZA#{+}4%a7@-HU!L~$jU%0DZ(K9d*WaR9`mo)nFW2aA#KDug{uW!-JsZo!rq0WnEO^bHiI>dS6 zt+zz4JUYaepKR}A|LfJk&g7@ZuYc1gjZN^dTgD`~$B+RD9yMf8f~T1e93OAWxDg5N zT~`tOKXZbD|5wnhUGV=__kAGvf93rw&oS#)=iC1A{_ws+nfZDa^NY^p|Ka~> zd-415|HQOE+wQvwCjU?48{h67wbT|HR}=;s1%NEFaO{?{b#^r}ja% ze*8aiz0D8*Pb~j0&iH>~`G0Z7|BEyJU!3v(#N=O*{}*Tczc}OniODC#{}Yo>hW{rn zu;-che`5K6akk(8zQ6JP?C%54-OUHGzaKbLAGhl9C!F!A@c(rDSRVf`&iH?E-tzlL zof#khPxHa=!vBji{-0R>U!3v(#Q010{{-8;xifiY_d=zK- zfA6e0nehL_#bZlD{$HH&|HLKZn*2X8{qg_eO#Yvk{`h}le8Zm2YR>bHIQf00=Cl54 zNR@N`sG?}q_6q0DV@je{-!6Bq7+VzlKP_K1z9jg67r8X}e+$l@2>xHy_|oA2iK{1+ z1^-W6b4z*j@zLD#V%l51n(fT;pSd^7*H8Z8+PX~N9=P4obmw}TFaDqQ{{Y(_{68_* zH}e0)||KdjH>+7>EKcJa&%YnJ} zyy1H176WqZ`NXx(?fT`}^Ng#VTldNe{-4&@tiB-lf8y4SmVfrn6+WM=(e=Uq)A`)l z@(%I;oM+q;{J-yZJsteNF7s{;{-1dC{M)E+cV0YW_445VKe>#6kM&}3rPuzJ-LGb^?B@>E+|0nK0 zt|a(>;@*~*`xndq6ZaX@Irx9#zGDl6|L1IZsQ7>4K6ZV?{}UIE?Hv3+aq;+~;Qxtx z+4XLD^Ks|&dF)}nv-v~kbbVvI{qyP*Y}Zd`@_h0C)E~zG6Bm!lC$IFJu4k}af1FE3 z7vM)F*z(hyxj!QRPvceF^#uPCg7N<}KFj0(#Toxkj9-rbC+=c-$M}C@?#FC@CfNKiXYRl8 z|J0xR8T>zS_lAt%|B1Vrzm5MVt{w)z^^CaAd~p7WxgWy+6L+)s#ccU1G2hSle{r_{ z&SjS8XY;F8J8bh$F#cb>9sf^UWxt>C|HQm+hyN$87?8&Pb?(wX_=qv?!0~aeFkg}U zKP`{HNc~@(e=zlb#VyQlBmYl)v+Y0pKXLKEwBY}VS)TkqG41$&V*E(*|HPj+pBMj6 zjDLs!=kv3CMf-esJ9&$Cf8fmfiTAx$>s&c7JNSPZuXsSG;QxsW`?0-^-oK5#kAeTE z_6~MGivK6(_cH#UnBUV28s|Cl{^7^d7CHB@>*bb3E1k)k-tvvL2_9U((Ya!T*ah{-2oqY5YHNrL7@B?4InUl#=+f*#pAYXZe0=ng1b?&L7oAHj4|+u1fB5zkTb_8UZ$IUnJF?8~_nviT zeEdJ{Puj`qIH>Q8|>uX+h zPMa{u@*ZDz&Kg%A%}IYV!S?xeF17Z*R=wlg<(46q2l+eaURIAA|4-i!^>Ze2J@xjH zb0$ZhyY+(vHxB-=M&B=^=FhUcu7CRS%`r`Y=*_<#ETo@stf-L7k#XKmOJwHyKk;3=wnr~~skyf=+Ow1QSA2cTckhmd&Ti@3w_?v8?th(^SiM&KKh1ZU zy|01)C#GI2{$HG_|0~9iB>zvm+49ct|HSx}_DMX%po>h0v|JvY1DnY_Id#TCxm?fsZl|EP4{Y5ga? zQ0;v5_}x+WZM6yh*ZHnK--Bn)MsIHFo?!exZ4Z7Z{-2oqJ^VlMfnz6v|0h0p{A6@R zTg(5ua6gZ~hyNF6{68^1AO4^CfaSm8|A`MCJs$nxI?MmNFdmHmC&oX+{}b=ncOb(5 z6CX04jQYR2e}(b?#QV4Jibi#tT>IE3O@80rtvjM8ubJw+ecO)U|EV1&|4;Yd8_f?U z|4+Qh-gmKeckc=QU!3v(ocHYu{$HH&|FnPZ+`BvYf8zPOY=2n(pLq4o z9l`$-uiU=Pey>^n--Y9Khxygi{}s=%>k0XP;$=(jh}uuH{J#tR7uoe~Xn)K9yTD6k zObGs;c+vE65&3`O2@@Nl{+l-Y`8a%JfBU_;#d&mNx8VQj{2W$a8T>zS_W_-Q|0k~N zn-}~)eI9%C$q4?RxUPrg;XSsaR^KmOd$)_`?b+$vtxx-?{hhms;BpWAx6)7n%FFL%-U0vEAMmm^N>Jt-k;224qABhaE`pw@VH>SM+Kf zeRSg?=gQtUN7)}<H90cON-$Di7N`P3;ti6@&Cls z<9%cGeSZDJ=ljRhFV%keXAjnHzHvz%Y=57x)!*mj|B3Na@c-hB|0m8UxF+QP#Toxk z+^+EYkpCCw_bvZVoKtdL$o~_Qmxcc)&MI#e^8ezD|0gakZyx+VG5LP@f8x4|8-xF+ zzfaa)@c+c*590rcbE<9%{-3za>YI)__Mbi;jQ^+c$xp-oi!=V87(WaDPfYz){68_i z82(?J@&Cm5S@wL(xzO_Z?D>~7{+vA@OECVQ=8rFE&)2*i#{bj!qPmDiD{$HH&|HSxh_iF|0gD25dTjs z|1Zw?e`5K6V)=jKQu6`v|Kg1QC&mxN{}Xe(@&Cl#&Cfir;5W|Q?EJ$2Q#*bj{$HH& z|HShD;!OUZSpHv}@&DqC|0nKT*(&7!IotV#|0gD|5C2ch=L!EW&iH>~`G0Z7|BEyJ zU!3v(;*9^N=jn_`{+}4%8vjpRR(V5&|0kxM{6CFHJN}=T@$moDAIATSGyb0#9}xdf z%j5Tv{}*TcKQaFGvsXuTS|0x4ri)xydPDI4)W4wkI(xozNu9G@pKtinCBA%i-nG%y z(WP})&b+_&vup0E!~grnq9n)t1?rQ=xvoRfmnyJ)zj%9U9$#k1WZqgTr}j_f)cUjk z&bLeLpUSEJVe0m!a!z`3`?5PFeZ}02q>q-DncP1WnaRAUvQEkUNxoZr|D|$j9$_ly zw@WUc-8$(PrnOD_f~om?ss3N?jn^mUlgb4xlKFk9`Gk2blkKT_ghj2B^GWsnvTjb+ z3vSysxxd@BOCFDZ$2WCI_D|)1w|uJqm)kKbny`4y^Oa+648C7l`<&qaiL)~bga7AT z);IWn;%@b~1piMwWX$;B|A_|-9~JyR@r;H+!T%FC)>Q`oPdp^=y5RramDW7?h&|eU zCe;5GcWT!%)c+N8zT*FB`P}S|!T%FyXSNUZf5q*xGlT!9Eckyg{-3ku1LFUQ$tT4B6D$8O&iH>~_8u1T=j+2q#Q)R!@i)o;i!=3q#rT8N z{}tm8;{S=O%?HK*6Epr}t426ibQ=);^r7L-BPPs)jm_Cnk8o#Bm9pGGt(arwtvN z;JIUxzTomPqZ938x|9e1&m5r({$I=B|K(IX82rDozU_nmH{i_&g8#?g&+-4nrS%!n zq<(KY^E{$t^e+CxK5KTGh42VQd~9}xdf^CKV7 z?w_4|+w(}fzjp35D3|wdoT;B{_vg;|b@+eUe)9A1|HS0;+5NxwC*R8Q!4r)Cr~b6# z|HavUe|Ue!$N$s($>+oW6Ei>jKe7BjG41$&V%qKZlQZ+h|I_-F|0l+O#QziXybAwM z%>3~G;!OUZ7{AbdANu;>M;`jRGs{QMd@aEZ-+A5{Ux@rajR)iZiSdK*|Kg1QC&m}T z|BEyJpBTRf|4%IcPt5rCexA<S{_l*hWWSZ2tIR*KcWr!q z%n$!h>kmGp`F~>C@&DqC{}*TcKQZ&i{}baU;{U}N|4+>L_U!3v(#PrAii!=V;OT8Zo{vY{@_)dz|I}>G;*z^LhL~G4*N5{}WTMm-@eA=8OLqXZ%0SZ-Du9Mc3cjqP;|4;2KkN+oT z`^ovZt_avQRO|0m8FmKpp%G0WrsiTONtobqVuPM z@5lN7x6;Aq4^BN5{JvWA>&!=SrrveY!vmbjzx=`5{hV_~mj(Y%%ftA8Vtl;sr}sS1 z-*oZ!3eAU^Gr7AnKFAd(yC&G4$2)f$QxyC^El<5`{6BH2`8)W3;_`7kKQ4FfHMS)9 ze`<%x|GUUd{@>f{P6q!EUx)lZai#e@KQuoy#2$h_RdAN{|`=W>&*3`5RPvGZf|8)Lk z^tmzkf8u8S+w*+c&rcZt&z!K}x3+BTLVY^tR>Lc(U+0`@^$YR;KI(KP_<@~gOpNm1 zi=2z+Er^bF`}myNd#~FV{J+;%oe6&6?Q2&D|4%&Eo8@ z&IbQ)`jSP#{}WGHcxUkc#A6rS9{fM?$lGTJ|4%%4?#$r-?U;Br_i=r_VRL4L`oH2qGp0uGp81Zq*WWrN_+* zGrqs7CiITho_*3eb3n1xr~9%q^=3a={J3))%bOzqPy4%QNZaVq|GfX4jwg9`_zS+339B|LJ_`GPWT2f8t8>`>6jbuASH=_%RmWeGNa>p3mY`yA$XCD{D01e+h`%>5JopSGXv#s3pCU;IBY+k^in zranFXpP22z{}bac;{S>9qw)X5_|N!%V%{&p{}c23$o!pW#rRn^A7}F6@&D9LeP-+b zjJU+^fA}Zn_l>nzCV6s|IM4C~@&Dp%{hj%}ivOo}e$V3niSYsP|Kg1QC+7Dz{$HH& z|HShD;%xItwB!H9+wuRz_<8t$Iv?c!i96PJ2>zeA)8Mq=|A|WmWCs5)&iH?E#{Ux+ z_sqPh4&J<@kSb#{Y}6{offs5dTl@d_M92#JsOC`YR7O^FC7hibtIJ zee&Dq9#8ONUBB#1zUHvpr+j%dq45qI0(8pW^@Nd?x=C|4-b`K7aUsV!rS2|HQm+gZ~$2`}{f=4$27r zpW0#kKQZ~W_<#C-DH>Z5{6DqVjH?O$pSW&9o#jRT&6n>wp?h>y%a43}yHD(C=g+^K z`%D`WUDfZBS}hOHyXsTUeWx`1{%H96eCO>}9~S>l{dZWN9R8p9!2UzQ z|BEyJpR@U3_tax6Yt%#Gx&ev zT|2i$?eAIT?dz=mI{AOvUu*chng1u=uyI{<%MaH0{$I0pRq+3`|Cg*<7W_Z);+0E- z|0kZY;FjS3iKomR6Z}8%*s1-4|0focEu%YH?eObEP0!ZB|I_uhtbgm^|B1^7+#LKrag{wU z!T*c%sdsnR>i(dnZ$|XP@9c5zYWWG5KC;)jXaAh2WamET9{sX||EJ|EZTmj;%Klp2 zAC&ey%?iUvya>j4`&gjF=-FkJ3s;Z7S59-_G|7rZe{hItg zG4tR3<}vSIZR;m1Snb`qwT*BG#a+9$A#XUr_pBR77o}YO;{u}U!3v(#Q1&G|BW;G ze`1!$|BEyJpP2oR|0m{n;{S=OE1L)ZPh4d_D*m6C{`h}!#{Y{m`G0Z7{}ba6lK&TH z{68_{|IPeAG3O)of5n_%_{Zp7iNDr{o!?`gW=7Pvw&K$vnhV&TW%ie_q?9PncSNICcK1d5l?Yllv<* ze=n6&^Zru(zSRD?ZIb?8YJK4UgKtjye5rYXshpY**t&J{__b=4JpQTesr-eu$>p!< znB3nTQ~cKS^rWwunUS41Ke95-Pc#4Tn$FFG|JOb%C(2x~`uV}jZVY}{yUgt9+~pTJ zFC!zeOpFMJ9@c+aMCr=LkpSbt<5mA>p z%X~gJm*fTiZ`MDWe86<``IcO>?0IpAw3~zfr{#+>oBTg|B0Co{+}3s5dTk%Ux)uE&M&k2Y?l8g&MP(l!Ti5C z;~(PxiL(ps{p$4bK0baX{-4&z{PF+9wB!GY zX{Y}0UmtH4^8cuRO#Yu3|F7$3E^@cd#nINn5#C;#*W~|cyw=_N2LDgouGhe5`jZXb zzgPDG(dT|M^!d_%+)y{=npf+3cIzJvz4juP_v#THs~zI)m3?~$|4;L2?AJH(`5ifM zK!V5i?v`Nu+W7a)h??>Q*O%lcc)0nIiT>t0Cb&2^I{4<>=RfN5aPU(GW_1YupE*Op z|EsRNIrx9CW<3=Azg|7kga5ba`ws^HFWvs$iT@|gu==_9e`20r;Qz%L|1Zw?e{r7u z+Rx6v+vmaX{hw)m+Q+|pEx~&}dexcdC0S3u>dRN!-*55%G+&CoUeG6Z}6h&%5mRmAAw8`^%aAWAA4r*xuiAmj9>if$jaTL_7YU z)<--3U!3v(#Q2E#e{p``)$<9q_t%{9Tk!w1ei;8x%=13{zc}OniOCB)QSwzEk32E^ z{q2mOga4=b;OF4~iRJ&r8UIg=UxWWA=6NappBNtt|4-c4@*eR2#Q0g{|HT>qPb~j0 z&TstV5pQSxoj;#s{6B3!{+uoA{b9Rzcg7d8cX1Mo{}*2${-2oT$^VNp{$HH&|HO=s z|0k}t=STQ|;z4#i@c-hB|0ibuOx|(QKi_cai4)G$7ry+_BG1njbKQZI&eROSt$^TP3pKts>ah~Pv;Qxu!&DX>K6XOHo|B3m$Kgv6Zf<2!~YYrJpNyt@&Cm5jGfnyJ%41~nczc_ zCxic2VSfX?<(Zjv_~YdN#hLs+G0X2QZ#e(JnbX1d!J@VS;QxsS zny)gZ%YgIm{=UiIDo{J%Kk|HZlVk6q4>n06}odp*q88J1h_jL&!b%+dsJyRX<8Uyu5~TE2_< zJ@|iO{5|}?IOG3`nJ@ldobmrOKk^Ro|HR}Qc5R*ROup4GMy5HFZ)iS)GoQzszTeK7 ze9o_2(bk#g?f8E>UQNDCtBY*=7ynPkoB87ZiHpq7#QziL+UFVnPt5l*`G0Z7{}Xe6 zh5simt4|C5pSY%f8qbHly}W0e;Q#6TEbiGh_ts3!P-t^d&E|8*MCJNSR%-0}6n{}UIE=@tAxao&h-!T%GNjOiNPd-nBn z;_~r5qPH)9)wyIsuc*`QuQ-=Y>=T{M_`x~N2S4wv-7h*#JC~2{V)fw8ITu@A)RJRgJ*WLkeeS0|_oOraF8-hP-{5hj!T%Ev8DD1g z@2vjsh3ggm9R8oUpMBmw|Kq#Q`SHG`#PWDfCwRkGjwhJ>KlQJfXzM$0zi>!xCsYLgPdsc~dGPQ2mYU! z_Y3g<#Q1jje{shD6XO@+|B1Q2;QxtP9{*3w^$Pz_%=ZiaU!3v(v_ELa|BJKvX9>pt zQ#sc|sS8P7cb@qD||4;4s zLHK{-jt%_1Eee?>e4p}r4gXK=O+2|uj6d|5dmpUQ{^9<__MbENPj)=2)ehV7bteDb z&X**c|EKY}p5p(-8UIgQH=td}|BEyJpBO(7|1Zv#ujcEc9sf`BgUSCB;~$d$7iaSS z#Fds;W9L_mxZ3_+fd41PpTqx)Gx>jU#{Y{m{$HH&|HLKzvx5I8X8rd0^7g9w^x*%g z9UlqFV6UXamN1>Gavjv zajpGc$N&4Qy>IcS`={3xG!zH_FV6UXV(x$O|HM^xe~14kCV#N_?h`fB?3w)VUr(#+ zX1`bd(eaEk?}Om~sXyN7tZ}gmvjC*53qd0TmSYOUmw5s@>cxTnd|2Vm;TI|jsK_5H@~MW@71|{SW$Fn z!sX6oLkpviI$q(NH>@=HfBOC_Xe{UcuU4F6?{C=sp>uXaIq#1+=i2)m_BVZ*tBY(>=QVhL#Do_g|c|$M)j>*g1E6pWy##{H$C01^-W+ zH>E!Kf8u_Vh6Mjl+<)@W=#!tO`~3P%9T`nJndv-a_5|w7I}e*NF6xw%>pXbc=xEdX zdCm=%U-rAF3Y^J%9I&#`dEBf?(W5V$3AAW&DYRH| zEAUb%lv3<_UwitwXP?vGdin2{wOGux_Ho(IIeTB{vop`Ht##i0kOMQ-i|d^iAAU$? z?TAL_MMoc=`S;(NoR=PZRA!Icnw|Hw?^`x4Z*|`1#N#tL*>TPXpLAko)fN++4_mn+ z^Uh-voe!|@Y4HE_e07lJL*oDGdGVN2R|o%3eB9}4g8wI8amE?J{}Zn~^UUD?Ij=b* zjQ^|W;g!btf8sNZ@&7bEO#YvE^%otoLQW2y5|t4_)6+ka2z zGuEsL{@+QH)`jnP&OH6}kpCxUd-4Corw+gz{~Kkk3ypPn=q5?{}v<*fjee1-p~>vxU2nd6C!W?RI=F_`I8W|Hl7Q z{SV{+iFsbb{}b~(g#RZVZ^sM&PduT0RPg`AbKCMm{$I@G|B3m&0{>53F(Ehje`0(- z{J)s-|HMsWhi2GU?JvGjzo)NqCLivm9j@`?S6S0P_oAs|c zvpoDiO%LP$#f<+a#;?Qw6F1rV@c+c*GvfcnjQ{6sJ{tLdG2{P|i&@SfLw;w=A9)0diGO#Yvk`-A+ynDPH&#{Y{M z|1ajPzx&*eKg+B9iplm91{|EKlA_7-ga`^=VQssk^K4#jF`?37JoPo*hNppJp)5}Ze^QFf> zPIKCSO#7SZ^{4&9^!UVS-!IK+-!Gl#*JEVzeDxfaJl>3d8(;6E&Cf~j=;ZjpW5$dL z{@?ps_6z>s(9wCp{~I}@Z}9){0rCID)bh>n|HSiVObPzqlIQw`JitZuLxcY(o?kT}_CG2{P<@dfe!#N_GW|B3PC@c+d4e)xY{pZq_u{68_iAO4@X zsHDsPiy8k<%>4L&G2{P3lGrF8-ew9}xdfTvuY_m74!2#+SRk zW$*iLS=}f2aTQh8UvSV~3C91^^fl!bA^%TYUex9P#e7c3GM}Ejy*rOv>P(*A8|#-i zGrltZpZ2G$tSnRc%_1)^FSq<8^Z&H`*7C0WznJm=#Es=8!T%F;KJovwe}%<)!T%HE zbK?Jro65TUKQVcL&oA1|%kdEhpEW1J_uV<`zK@>VHTZsP|FU;y+-GfC&Drh#+)V!A zjlH{hRAF)O|1^DptuMZRE6S@9Tv<__;1=^U7#@HCvKgY7yLhQv-Q_JRQ;^)AAIS=XPoKJ z!T;0rF#ewy-vj?IX8b=fz6}1KnECPl#B4wQU(DqHiL*1t1piOmY}=3jC#L-a|4%&8 z{73vhG3&SYJ7;_z{6Ce`e}?}j#wWo46Vo4t|0ibrVEjKZ^W*=CnIHd8j6c)y)x8O} z@86v9UGV>Oy~6l^;_)*}ga4=H!T5h-`Umm<#4UC_@c+bYKly)R#@EFE6KAb|rK;?I z{Cv}&vQ6vl&Wtzq%8c6*eCyKRI5R%e>cehL@Z6Ofobl(#|I_-&E5rX2(_eu97qk8C zj6Z1a0tv?d)AZz*;s3>q|0ibq@&Ck3kN+p89RE*DIsTs*Ul9K)>>B@9j4zD;C#F8a|BD&_PaN(a^Z#PT{}WT6 z;Qz&p|0h=dpIG^SVthdSKQaAX_XrU$W1SudUe-$yjI@~n7Poo%Etf2|I6R;n&AK8m(P80 zu9xGdfAQTMXZ9cePs^i!5C2b0eS!b?wfThj3i!A9e`5R*{6E@U$?wA-!T%F89yR`- zn7ko z|4&T+FaDpH{$u<YsWbP#^{+Z-?fSCuK%K|i z^V)mg_e${Ux}MJTAK?G#da9f_H28nwGRsrI{}UJ6ct4gOB?? zeqVKp``h?I^H=}Fxo`c>!T)P$Ul;tqGRsfA{^I^$>V+yAWu z@7?%%=Q+=>3;BVJ&x-#iu3KCg{6BGnjc1GhCvG%f4*yTpo%}hS) z(QaN^AN)VLJ<_Tm4D@%ixo#OxpbpSan|@&Cjv%c_I_C!S>f9{!(r zimea-PmB*}{dvy#eB}SB9Di@#{MDVhK4JVnvHU+V{@?gl59?I@$n+Z@{;6~GvO4@Q z=XUcA%@69-{n}=}FaDnxKNCK{*?;`MnDPI_ zy#L_;CD{DG?)Bv}o~)Pid|}7WneXrH_$Ju4$C>wUJ3k4=|MT@(e>nbM%=mv|=Ewhw z8UIhr`#b)hnCBV%KQZ&;|B36Y{~P~L%=Y8|#f<+aW`6uXG4qrECvGsm0RK-+UXC44 zXUg&a;&S{yak2H^$vNM~ z8^-_B^hM?qTyXwrUXDLFzxSEWwf4M?|EJ~g{a??k&Tm?~*OkHFqdno}oQs_CxvshT z=gw6#N;3xx|AjN}ulRqOU;dw%`r(1~>%E-%=$w%^IFnb3|EKNY`3C<_%<~`qU(EP_ zG2{PdW1~e&4y(#xEXr(nksYF!QN1_3dv?{oENp zaQQa>>}IQPvgds5+-UX3Rz1FR=K1{nDVeN}2aNxx{U;ys;(l8=lMik8V^-HI^~>!& zw{fns@h5h9aa(8nnLR$-KCAkM?`!e@^m|!9W4QS)J9n2G+w-Gy)vR3eS$g^MDrXMo zes`|6_Nb%o*wweMd>VdAU+3Ho8(*%Wzw@Y>!)*M?0nX%A|K#_BoJ%@#_1W8_Y3Dq zd$eQ@8BpfOXX@@_Gta(Wp5TgWE1laHjLTedK(+JKh2w+&r{h0<@wDLoi6<=S$aLP* z;M2D*?Z^yW+2lNS+4SK5Y5Ml1bA$gUp1N#a@c+aM_uDi0f8xal?i>6+@g9fomzj9M zWWOF39kGAr;LX~zdj8t)s6#WOnx1^9oOpXUMmKQZm?_5swx6KC!C;s3>q{}(g{}apq6O#vs|0ia=Qrti7?^yGR_*-0W`E~ez zI-a$bUw6Vq*LXSp-_1v_bH*?E>%8^OjNiL+{k6`8mM>NKm)o*xUuFDW`#wLb_Bt5< zPducgXYl{TLrZ%F|4+>F$^R3Vn9oA~pBUc{|1W0zKQX=^{$I@af8wI*T|)k!xTLmE z$p7o+uJM0k#{U!J6WRDmS+x)29}V5}{sde9j89+FFfio*Y5wZEftfw4AMok%webH` zF8@zlXXE8E{;!yF{6DqN<9EIC&cn`3zs(DeI8%=Qr};JhuejW<7yLi5^8duj|8q9q z4*yS#kB9#kGx>iplmF-3G&J~s;)ZNa$o~`L`{Dn^jQ=Ob_hbBDac$Fp;Qxsk-C5jX82?YxQ;z>9#%IL;iy8k<%=GwwF_Zrn z^E%7_6SF+>|HM`Q$^Ub%>mB?*G5LF|3jglgOP=P2L7ye~5!7@rvbFXjvO`aY}vcl^H9 zYrfBJcI&UR2i|*BGhBM~4+;M0(oAzaJ^r7TS5ev{_pflFS=SAMf<}9GO~wdVA9T-{8T?>+QeB10J3{U*y}x*YCj5Nndqv zUQVK%e7t!2wEtH)GMNVmlmB<`D_#Cy?@_s7{9kdOyivjb`*uXX-~$$n7#aLO@u;CW z!T%HQGGtKj|HQoq56leTbmD#D(dHkve|Um3{uBP6);D=VYw-WXd)auUd;a`*FP}AU zZsv5=~@t|%_a;Qxs!$Nv+PuZRC9CSPy6XBIoxl~}%_`F~zsY54-?|B0uW z4@mx>xXq3?{-2n@`L}U{Ur~O{6BGRMP=~+#Fdqm z!T*aH|8Lz@eS-hT@x%Xn>%%VpkLBV2#Z3O6rf;ZD=Ji!tzGi%XS2ZQ`{Tj2$^7_W) z{AsSP{l9%d&VRhVY)wJt=XvjLYQ6a8;QKY#7V`YI$(*9#`_;Bs|8W1eHa&amO~LnT z9B<=C=e_C7_w#43d41FUqiza5AK$AFUHeyO+UIY({A%MRi}~9}{_NW~&H4kL`SXhjUibbB&h?g;xBRO=B^dut`;R|I{+}3s zj{HAy`}C6F|LOR&brc8xPaOO}^ZztG+mHVzrauJ#PmJGz|0kCJCzk&wX8HJkG2{P< z@lVMA6XW0E|A}Y(C;v~}Vfl#oe`5NR@c+at5C2ar|4%IcPfT71{-2osF8n_+J{10+ zc&zye_1v%ha2?bY~y+FtxG{68_r2mdc-{68_{!{YzNjQ%#Z&k#&5*`6LbIK|HX{|C#HRr{68`E5&oZ; z{zm-2nDPI_^8aGS|BD&_PfY!U|0kxtApb9B^8dutFZh3A&L94t82=LgPt5&||0l-x z!~csJ|4&T)ga0R{e;@x(Oga9anCk)mPfR)fpMIa1AODZ`>j%EvznSBQ|0kwD_pY<% zCm8=v+FiFYdBKKOrU zzpyUk0q#(`ZSeoZ1+6*3{}baEUh%unJ2gMQ$FGk3)OqH@y37j;KJL`?^!M-b&nA zd;EW%cAmCZWAOj9Jso>DWmdoSh;Q$>eOoj4&v?+eWv^`JyG{2yPqpRY|7m}j|5p`v zcj|mB*|RzG%DOw87ca}&_;j~BPhHkzD`eikiud^=r zg4AzyORFu9=gI`*|7m)BKm5O#$^R2iUQ!+WznJm=#Q2A=AAXiEzuBfA`0g5K`G2|| z<^RR})Mv{(b-goQu#Ml@sr!rR&F^t${9*HdoM$eo3;v&`?^xL7|B0!;@c&}Q{}WHA zzBK<&Jk9E3{68`N4E|rt<{vnd7l{9-av1+l+-BD&{-0R>pIH8%nBN2ZKQZ}M_|(Gx&dEo)_@{#FXRzi7Chb6Z8Cm|0m{o z5C2ch`zQXNnECPl#LSQX7c>5!nCbEV#4Hd0FJ}C|nDPH&w&N4Ajc;N8pUUO`iOEOA z{}a={ZpYIZp8)?)<>dF^|A|Yi{Q>_^Tx34pRfjKY((ixCq~VtLw!d@Plo6Q^Glw?4 z^u$#mpRaUsZt(xa#S@1G|4%$<%CO91+pqHJhfW<4{6CfB3*!HYD=eRE$Nv+zSYAE(e`1~&@&97R{}WSx%(?ES1P>a0 zt8=)&uD?COH;=i~nely(`t{w;j33;T-`UMpA8mQl{Rw`u;6dl`{mQ&Y{rHeiIQ*5z zo!iYv9JS#opPu^g)8glxDaZfQ@uj@!Z!bCHGvfcLoab5mKQZ5n;Qz&p|0ia9@c&}Q z|BD&_Pt5Z0|HSx#_c;TxxlVk8Qu1^Ef-68=lyS}z`?y&Kp zcfVrmtgdJB^s~#h?PjZAkNw5=SzZ4;@7Vq8Jk83Ra(8y7{PBZ&`26^x8%laPb38Bj zytgyINBDnQKYaA?zP^2&-v#gVbLRLoUN^uQ-!fGy~BkAIcaI@5l%@XI=9^6l~eG<~tzti3CUe6jqq>XU4&(odTc%cJroA>dE6z@<3jSZr z`|lt8zi;neAHL_=^WcMn|0mw} z@WX@uC;sVCM+N_Hk6o_~{@>Cg4-5XEn7l^D{}u1Q=hEQ+iT7K!B=~>g-ImP{; z9Sdg$|4%&L^7iom#5EIYg8wJ3ZZ8i0pSX5fY4HEFe?{%1ga0Sav+-gNc=}{NKIQGX zneVr>{J;OaUzOVL75<;N#PZ-D-0KuSe^vHA-SNXIetxIf^FYhntDL9W{e%Cf>w)jj z@&Cl*?e`h~PfYv!W=F1ZZn5zY?E4;P-pBF(G(C*}=WO@aE$5x-*CY3ry)QWPJk(>i zvlEQ}r|XyPyJ*XE{Ql+p_$}U#czRLr|5QJYpH^V?;rV|5%KuY2&m;JMV&2d3|HL)+ zy}^c(3w?d#?E3)xKh+P+8)|}@c&}Q{}bbb;s1%NY6k@W z&zDy}AmsnWjQ=NQe)9ifCjU>Y{J)s-|HSxt_$EVAN)TtekJ~&nDyiT zX?f(~;s14Wm;a~fIiL7{VwR8pr|Dt*KQZG)_Zy#%| zxqpTJtM8XAPy1zM1OM;wVADQWzX81y%TN1%Q->z=+NKOj`haO4G421QeYf=X4(*rp z|Aq}n9*_T8-r(f)xr35E+VFu%e=+UXrTw?`{twAXF25}&xjhpHC6E7)`G)D^o%RLO zoZjB1!AZZaHg&wx^QYIB=JfPw-!IKMDgST8sO0%ibK3VS9G&$4$ivgM%>UE=Uw-b0 z;Qw8CTmO*%H+b}j;Qxtp@<#{%@7b@r{J$~zxxxPvvpwYhi3g6%4gQ~az=+|&{}Xe) z;QxvH_v)QlzDqX`E3C*|)qK2{kDWFr^Vk8$IWOL8&*1-Q{@L^A1^-XHe?xBY|HMnm z2L%65JRv_n^UJYE`|`*;d-&j^obki(|Fr-3aQJ^QR5|4%IcPfUIz{+}2hwDkM=&P-4K zpZ1UI0sl|jR8boIKXFZESN>nj_>K<)d`ZUt732Rg{;!z*$Nv+Lt4aENlTyCl z#FP)%+LFuz%r+(czHtr7JiwM(`X{2_yYjsMVtfADWDZgA`Kl`OGtK{g+qu53B-3lV zZmt+VD)@hzzShQL``6KLY%1z=bMXC|?Rzx*KQZk?_|4-axd42eQ+FtxX{J)s-|HShDVs6{|Pf>YcW=P-X zo#_wxeAIK!Q>^`q{6EbPlm92Cef^-hPdnF{|JS_lQ_lF0y^eV@!SA2;gfrWB&n1sL zH&}bhdDlMXjQ_Xnjz1>2@}Wna@o((?${D}L-oKn_&#?D1XWBdL{mq%}pS#P0&g?(_ zpJmVmKNNrHyNW+}d5e8N{>-@FJG1`vv+s9i{rG?J{P=${+xx3e&;0g&>&*NQU9-`d z_2d7=^W*=CX}`t)iy8kIcV5pse0}h;VZTi<`F}d!l;i)2$xp-o6H|`= zC#L-g|4&SR9{!)0{z3ddG40d#w=;QX_H3SD`sW|0kyX4*yR~dpG`H%vI+9#f<+a zro9~hPfWfd{-3yhc3JTM#PrYN|HX{|C#HWJ|4&T+HvXUXhx38|7c>5!nEk{5yXCZ7 zf?v(`hW{sKfARmsOppI3=KSIRiRJ%^DaZd4(?5;>r}g6(;s3>q|0kyZ1OHE4Z~2?} ze`4-;{J)s-|6<1fiy8k|1>@R9R6R-_sk|4+Y95z8+tu+S9Y~C+7ad{}bb%;Qz&p|0fRhnfZTWeqZqa#9Uwae`2;5|4+>IWcen}{2o~Ti8FrZ zxt;y}{N&sHmj88M=h}%jevbKnI{y`|{eu4|ru~!rKQZ4Y`FPfYtL{-3UQ@&W%bcWdXW=A7XF(f>pqV5znLlmF*z?az$=E6%Iz9sECW zrecT8dk1|Nd^+a;N#m}W+*iJKuAX4eM^pakTtB5W_Q*zo!c!>5C2c|7U(_;0N};(V0BHAO3uuGrpdkduMz={6Ad}F#ey`*KYIU|B2gde*8Z%{@s3O zU*Pk@>%KqNdGg}g;Qwj)6K(wMs>{}N>Utf!z{V@yX|*%?p*CJ>g1_Hqd8g_(rpNyi z*V}lL_R;3^%?npF_Zr%#^3vQ$J9>U&*WQK{ppM^VfA5xt$uUn`m_2f!R9~t z^5y?&ee(ar%KsCSe`o%N&(HG%`F|>h@&Cl+3*-NZssGIXa;Cn*|5G`P|0kxt!vBjI z|1W0zKQX_j_#R7vm4w{0-eqUevFh`Mt5}6KvbpsOh_W!8~W4pYi`xPF}Mu-){8^sy)%U zz{cyt|I_q^me)i6pP2bqU2%p_599x7c`*K8%=mv|@(A(&V#fayGv4CNDZgqO@aR?9 zu}k-9t~Woz{&wd5=k1B>oq7Mk|I_^3kNAHvWb2roGG7t+pEr$?_BF@c&}Q{}Z$Rqh@aH%=Gwwx}G_{!$xeM;4R+Y!I|Uv!LN66#>d0|)BO13 zkH6Z}m(TPYuITNIZ+OAdT@#G|r|p}}`;7U2G2{P<@fY#`#4Hd0PfY#!!AC=#sXrgP zWtcPV3mXp2b;i%Tuxz9=-)|oMk5SIN&n>uPj5F;!_&&NOG* z8=tyyx^w+_dp{U9E34Y)@^%0_Q0#I4Zh&){g!1`zj&bYtbLaT|8MHIU4G!~B{rV!mxpG> z(-zDK{-3yg-n8KVX?fLSYlHtMF0uC;{6F!C`eDKU6EmLVl!K4+?JFNYIQW0spVBEg znTF*j`td1mA8y}Mo$So`y7+%Oe)Z;`&snk3kAI2f%`F~yil47)d!NPs)A{SL`wjmu zX8b=f?X#yhoa*NvzxJ*nr#bWc{^3v7IFGmI2m8J!;^NHIM^8`ii8r0$%=gXsf4Uy0 z+V=cA_bk7Dxxa4S>g)s``-`*vexZFF|4;Q9*DL;?xWl%W{6F2VQ_bi5;MeDQIX>Wm zv(HcP;|KlB86U8*;{s=nH~ycN&v?H0f8s{-0m=Up*R~B0{-3zce9a4%UgGr&WX~8~i_URau{q|0gEj@BPp2^!ef5Z~e|0 zKd||^yPPRM=nr=%__EvYNwD>QIJ5uwf7%}y|1W0iU-9jw-1=Xf<^O4W<^PGR>iW~a zLp3iSh07?)r-#kFthAnYlN-rVK{8UOF;13z|_|EKlI{}Z!*{J)s-|HSp?`{Dn^ zjQ=N=|0h=dpIH8%&X@c@G2`pv|A`way8J(}{6BGNUEkpUiShaH|Fk}QKm0#2+lT)b zGyb2L?IHg!X8b=bpK|=aMd#cU{684~PfY!b|EK90PZ5!xIDjq82?vX zmY4MNCZznTu|t#P>HN2}5101E()?q7+Ry>Xyt?#wvOkvp_hbHFdV5O-{onhS-rs^$ z9^QX(dOY8B-r&HbKbiL52KDV}tzq51Njm>;?7(FHUh9CQADABBH$6Ua+Bf_$PH*3j z`Jd_KrG39Nr!{3(x)7goAfQy? z!~YYH8Z|2Tf8y%=!r=djt8DyX{6BHO86Cm@6PF*bfAIgrOXe>K{-3zUd@J(*#8b>4 z!~YYvo3DodC&q`v|I_~Cx8eVZ@yqc4#N_K8GT?BZA3yEV35O*Z|4+*&-;eyinDPI_ z_-OclV)E$@7~IXApNl6S=;a0FWf}ZGO;5fY{+}4X4F6Be_`Qt(8#Df&xVXmh1I+&u zm)3Rpf6sj1<^MI*RtEo1jPFMNpP2D&@&7bGz9ad6V&(tEjQ{6s{v!UL82=IfPt5g( z|0gajFADyjnEfaJPt5+4|0iaAVDkTB#{Uyfwe83M6HhjOabaFJldpK{oOxbOUL@oH zYX2!`{9iHU``$U*xwN3r#uJ(4%<=g5PTkD-$Kx7idO7z)eE)Ji#9UP{Cc$G0a}qo< zFIj(#OXY)3NYxLFhaE4!xL`E-%bUz83jW`i;(@{c6IV5i3I3nBWKviDpSWyFe(?V; z+wzv+|Ban$ey#a`;@0-U;Qxtvzs3I(^F18?pSW&%Y4HEVlNM!z|0iyqR~P(0am{r5 ze%Sm!G5#C=pO}0-{6B3kjQ=MlPZ0l4EdMWN{J(DQ^8aGS{}YFNKlA@$#{Uz`{}a>S zg8wI`Jpunu%=eG@e`2=(9`pZV#{UzueEdH#%g6r{)BcD57c>5!nEn;~znJm=V#fcA z+1~%0X-~!fQ#s>@;{S>98}R>PUcT3T&a_vy9l6Pw{ww@HO;0)gU(EP_V%l%){n#15 z!rq^qX^*w{>jc~Tw=?tG`+0&l{-m49GsOSX`e6J&F+LyuU(EP_Vth3GznJm=#PoOJ z|B2=QiD|#Kzr8#hZ}b0DPX7x2U(EP_V*C{RKQVa@_+y)*qS_EFix6SF<|e`4mx{}VI+vjczbj9<9E;1cIL`~LsfhKrrqpWj?|ksl8j z|8KzZ4Z#Ow`S^cg#^=QU6OXa=egES5K7YRT2hDo#JZJo$>%KfU!T5hV-drE}e`5N} z@&CkJpZI@b>J$7wG1n*lpSZ%>JMsU-_{;czV)9$@|HShD#MC!g^Z&%ufB1hf7k`G1V(gI~k(!~YY@{}c0lIR0PE_;&uTvNO0-t(>r{pn?vFL2C*)y^%} zKYih5RnClmxuK=PneibXKe;Ty_9l3C#HVD|BD&_PmC{v|0l-J#s3pC zKly)ResA#q#N3bgf8x+zZvLN``SJh6{J!D;i3i&KiT|hbwOz}g;QxvFKK0ScK3>lE zsf_=t>p}jXnD$ZpKQZ4=lm92K88?*iG@VD=c)<97y8iNPyeIPi#AVi>hyVBOUF(DI zS~7NU@c+cL*Y-MpOE2g9@6ty$cOE--VDSIQ!=V3fn)w*y|B1KWy&?F2;-33V2>zdV z_uX5A|0kX^r#|?9V#e>q{}VHwHU6KN{_pvlec()gIsV^AS6&-@K=Od_|HN&U|A+r4 zmj5Sa{Md8yUi9U)Ev?J^aqV-?_#7ZX{-2orv%cU?T`vu`{XgIP$^`#U z*)M(i4%?qk*I(*9ZHX<<{6B3^g)JZdPs=Yg{|^68TxazO`G4YStB>&iw0?XE{J)sZ zm+I90f$xC-C+7U(|B1;z#s3pmo9}1-l{4k|e=3L9ES%k``xD0h6LY=c|B0z@@c+cr z&-j00>J$7wG4&1ppVr6qO8#HWJ z;Qz&p|0kw?#{Y{M|4+>G5dL4x_nnp`5VOeJNSQM)@Rc@Q;z?qa^|<~cgAnQ z|5N!?`+mii@67Wj{-4Tg?0tm%Kk;b${tf?6JjQ%J{68`8zxaRRE>}|0l*5#Q)Ru^8ds&ZKHz!C$5@2BIN&xnIHd8OdjDG zk6qUEnv-;eQ)@&Cjn_PmMzC+7PT{68_{72NXB_0BxsA2a?YXReRt2R1nK{JqWC z+Y|ik{dYL?{CrvS-Ok+Kdv3bdnfj-o>HY+NvGIWfk1Nl z*Sl1u+_KD z)2zODt!Ibx6nnnE|4-AMYo?FL+~4X$LlswDBGp|5vg3N@0B&z1^=(e@(uC-#Kp5}GkdK&*tvdsMezR`-@Y#71;WFd z4)^jF8((I#?T&PAwej2EdhsY{^2_o6wEPLSzt9{*2F`}V_CEByGu_+HPH>jQYh6&E=(-tUzwE_SZ9?-TIf>KJSKD|4_k<4vwFly#;Qz&p|0kCJC&vG?_J1$0F6&4C zfOA!8-;DJiIOF%>|7m_0|1W0zznJm=#Q1>te`4mx{}YpUi2oNe{+}2>2>(y*lQ90D znBzzOpBO*M`fq%G{2}~5Ew9XcHT*v@`Hc8~G2{P<@%^rw`%qTxpKz~<4|lWqe=DjU zNihDO&u`_{zm;J8KW#657yh4E{-3zHsmuQpXDu&|{6BH<%`E>fX8b=f{ulmV%=mvX zC&mxN|I_h+@&CkZANhY`{5bqS9dGsz z|4&T&8vdV{{6_pg%@5=MiSfno|6<1f6XVO-_;Ah*wtto%z_<`F}C@y5e7n z>9gm3onZXGczJ)l_TN4~_3M;NzHz30{oSeGI^!Sa9`&6w{vrOK){jq&|F`W4Hz)G{ z#MC$Vf119qs(0}J#N?mi|A}*KymkCP@tD!O2LDf-Hzw($mE|P;sx+tly0jmc_WjcQ zWBy;-2TRYN&Kt}QO6K7ert&CSD;d2o$GllgK#HhytBU$CTq^7y99(_GXy z=|849omZG%e%ikq)i0T+nBOb8J!u}W>&^+kCC%yOrPr7CH;433u0QSnrFrC#zqId{=E9WEljfo^Nq-1lHEPv;RmFpvS03;m6kV1{-4V8h7Jn;pEy%d z6Z}8%$VJP7|0h0b@4bWnC*EV~)ZqV#=T!|3{-1b$^^oBIiQ9_Gga4=PnOagA{6F#7 zG8>P~{6BG1VM*}+G=HJx3F807jQ=Ml{|^68jQ@rI=WPBP{-2oRjsGXcFU0>7lYfW* zC(hQ@2men@-W>j4%=mvX=Qcdp*snS8vRp4`is{6YLb%@5=M z#mxA>G2{P<@!RnK#Q1Iaf8v6oF~R>6%l{MOAL9STjQ=NYDysHF2@jZV}LX|5hU zGEtts-+zpY3zPHXTgLSf_c#8ZWsC*?Z+OYz;Qxt>8!Ug{^8dt)Z^QV%V*CX1|F-(F z%m3s375`5>*4mTF{}b~)8~&e|?+5Y!#I@7Pg8wHTH@`9Xf8z0TYJ>kLZfLjmLi7K` zv|r%=iOCnl|I_y3PqY`l=;iQV8(&E9;nV))On(FZpXSHUApb9B{68`N3i*FAA+aLVDnDPI_bu&f>|4-a7D=*~#iSc{z z|HSw`_P&vuk?(A9#{aWx*_r-Pd-io^d+l2oXO53$V>{D-g8!%OV|*C=znJm=#Q1age`4Ch zKmYzZXWG{u-YLnK4Y}6K**^f)KXM1;ClVJQmt&i#P|HLeh{68`MzfbLS zh3_A{Z0N6?X|MmH$_#yWzO^$v>b7%GrrcJR;_iWy?wun ze(p?rJpP}ykM-mKi8-G5e`0)1{J-kgHUys%-u%}WI8ybG4&Jqe=+0#>G-lg_&i#PomQ z|HX{|CuaHhe=+0#iK*Z4|HO^9zEy>XIdgsGO+6&R_RivK6B&kn)2a4s4*BD2}ey_^fj=Gyo~ zJ)8^14G#XFu2&fU&)M<`@c(|*^V;CE=1m?R{6BG}jVE>DP1|^RiM9We|M$r+uMIw6 zuJsq-|B1&;%nkmZIN$OPI)33v9yt+BlzjmIxpdoX? zeP23Hn^B&5s^oL$k+btM+h6s+&ZBoL2>#y_Uw8S2+%Ncl;)&*?UUJww&Qta<|Ld=B zIJYmZ%=DP{n)9T^HvZYhmz>GV!~fIr;C~Ez&ez|*XPu3Y_LMVz+`*eY?u;LY|EK+J zURodgKXK!tnhgG*nEXuqznGt2dsnB<4|#YyZ+}OE4;gS#*#!D{fcZqKg z$7glj1ztX3j|#i~&UL1~u>L&f#@&j{XItaz!|y)x!Bx&fDWV}V^+BxKx?BGnk*Ya1kbSB^Hg)6_iSL_HWew@%vZ1>#v>3^Thwt_TYos^!I3b{0IIy+xVJRUZ3P;4KdsD6KvBv<455C zX?-yMpP2kB{J)s-|HS|CBc1E4{~rHO<-8B$|B30}$N%f*{NVqI`F?}^KQTTD{$I?t z{f*i`oFxYF^F1N{ zpQeZL|HM_+-;e(nGyb2L@8$6Sw0(U4g8wJxc?|zgTxQ=h;{S=s&%^)I^9I{T{+}2> z5dUwCK{8DALxPt5p`_;LiFv-p|BD&_Pt5Z<{$I@a ze`4Nm@&97R{}b~*jsK_p<$Zh2-H&-W@59q;pK|7Y>G!*5ovAWA&u;u8!T03- zE5Z1G+F!OG|1W0zKQZ+Q{$I@ae`5Sb{68`EA^x8jU;W+1+d1Q#w+-FFndNVIea8g% zylQ7>{Jdk9_H^cb`{kV8&NJ+M;Q#6Rhp)N1kC#*bZ@p)~1RpSbfHUv&Pro%V!4>NU zJ2OB2pZ16Ih5siepAY{}%y_)`f8v>TJ>ma}r<-4l|0m}9!~YX={o((Kc|XMei+RxK z5@)XOmG752bG_pK>3DE{?fu5N*_LPTKhDfw^=WNZ^$~2}PdW4cYTs8mXYKbK|4;QF z?H$`)(c(<|#6f$Gb>{ft|7m&{|4+>MxA#L|KD=<=WZyon|7`!Z1P_0u-I@2}Eq*o4 zdA#MXez17DGuyvz?Mz>Ovps*<`)^jyr(93=e(cQtSblz1&$rX8eqXrl?pZzm!ab%f z%If)>e6_M?mt+T>c3t?Mr@Xnpeb2MZc}z?1;QxL5=5@gjESWSQ__V?5s)2}D;{cat5R)U9(INMqNpYAXDe`50gdLDbOU$5}y3(j+%VBa@< zS$BSd-yiTZXZlO<|Fpbj^Z)Vx#Q1yof2t2){68_*FaDnxKM?;GmG!#@|IgWcH2gm? z{tNz}7(Wg7FJ}IBHs25bPh4EObMXJvK381aJNSPw{$I@af8uhRAOBBWVLl=L zpO}0N{6F!i!v4Yk6X%ug67v6I#{U!J8{+?oOU(zw{}baM;{SKXGx@fZ+eB z{gm;9@&Cm5JNSQMjxYY7=9m8`mj5TFeF^_BX8b=f{uKV7+CO3ZznJm=V#fc|{J}>v z|4)q1W&K~yl;i(t`(g6`#N-*0|0iy!?H~L%Vg*zYzaV)3d+$e`5SL z{J)s-|HSxl_1{$I@2f9dO&|EK+jt^d=H7yh4(kLJw%G$#M$?C*YhOYpJq z?f%s773bg!ZvCn=$Ft<0-5id$`G4{H@c+b|Km0#&llgP_e`59*|4&@nVAr?#f8z3{ zKJ-63J;{U~r|0ia9@c+d4dH8=~jxYY7nDdMOC+2$i;f;^{c#y|; z^V1(YGyS}i{@0H${NO>KIx~IQ9)EYn_rw3w_00W*{}(g6iF33;j-&GDv<{_my?f<3o^U}Uv z;gDoLU1@5(+#j1iy}b1L)BaxC&nq6D+@G}1nC5KCKTC6Z{pmcxbpBqN)4pGt)4pGt zhYd>ldudMlcq9AvO86=x`XuuO(>#2ar2m)Z^zzdFUfTCd`+(`~OZ$Wa2PS>a!Gn|M zZ+Obj962)S=cIkWG#BNMN*s?ga2j|0f<< zT^syA@w8bpGrzjx==vT(UUx-eX5OSI%k+{-37rRXQg4f8qrN`I*08dZe!p z9`N81&UItVNBZ<|=bBL?g8!%ahm08+{6Fz9^TY7}#2jDzKQVqB{-3z2-15)O|BD&_ zPux&a7W_XkJ{$g@xU{A^_&##LEARnf$+)$^R3R&w&3Y=6g>3KQYV0|BD&_PmI5S|0l*@!2c7|euw`j#!tcj z6Vv{O{}(g8x9$DdxGVEjK#Px~VNU(EP_V&=#H6Vo1# z|0kYhd3gALV%p>I|HQNp5!nEK_}(^vZTGJX;MU%dVJe`4Cx@&97R{}bas zQG|6Z}8Mf5iWb8UIgAf1l+u z`1)b|KW$(2g393k#f<;wZ2sS^J;!ajYR3BD_u&IRKE2hsd|_qq|5RSKpv(Vr-n}&V zf8vq_#lim*H<>?z|0ixVUj_e9jNgL)CvKS6mH#Kk{~-S_X8b=f^W*=CnIHep+4{Ti z|6;cBznodVjSuEb9w+{vjt}=6{$I@ae`5N-@&CkJ@A!XW{3ZN9ai4L6g8wHTTDx=b z|8zcc8+!-;Ph4+49sZw~@h|cJ#P~`0e=+0#iOItx|4-M~F!O!!|HKWJ_qWG~+dF65 zN0^Vboiq7L_UuWYzZRuQP`Oov_Z|+>Qdu`^63x1Md{J+;$ zUe}c;Xx9_|pSXB_dGP(ud^Y4gAH*u%~&KPUTubL+ga%pSMh=gju69dWNS+iyNrr_OJy-QRPYf1BW+-T9jY zKVEc8g3TXtW_;V0LDxC6KKwr|AD;^UPt5wvM{;I-#r&_=CU~F2E_NO}d$jqeKXY#C z7>?iMOntx0i)SVn|4-}dKXY{O|HOmM@5KKT^E`$Br~8TDSNuOQKAVm2nPB`smCOGV zQ~%=si5XuW|1W0zKXIKsU*Z47jQ=O*`2hbfX8b=f+lT)r#s|dz6KBm|#s3pipW^?C zE9Msk|4&?L^)LRPnCbEVVmANFxnh3T_`f=yl?xcJ_Mv;l;LA>aQZ z!T5h#ALB`G)#IdlRsT|dJ@MI6XPzG~dVah!euUM}&iLMzSLIw}*Qe!oZM@*Ybs>+9 z`oYFCb>{camcLQ!V|?Z(K6~RH@ieRN`6uT1T6w*=+4jfgZxA#7<$^nIaPHdvH=H?t zwtbD79=7w_sQqXE?0RwLda&!ynd{H|NN2u>u;b@UUXLB$1l#d<=J{t<;qRPze>r&E zL(cdh_G=HV#7vcYj zo6S$N`@^}_o=5Heab|p9yT1}_$J3eTIs88@PyU~n=P&#}G2gG?|8?`2;Q#6T@qG;b zpP22%|I_tWVf#b=pSaF`FF*U`DbD2g;Qy%{zYqUUOgrDH=4)^}a8NcLDwSVbm^TDpTEeZx1tf0R!h{ev^}kJ$Dn zS)DI@tTP|kEWw|gwuLkG-|X>QCHQxnZIj@^zuz{&r>xjM!S6NgnBd}$owGXryzgGL zV^3$=6TW()SAw%|?vmB@N;&?Y7~gEf_WgW%_>9N;J9GT;|1>?vAOA0A{68_%4|p`k z=cj&Kar*ECHS(V6eB@c*>vJL%=mv|`F}Cv|A|@O6FD;zY|mGT z?ZN-k`v}w9`?E9W*YfqVdVc2j%kuZT+5Ga)c3onE_;n#)e3JRx_2{;QxuMtv<&86OXg^!3Q?1^y4|++TXvp;1uU}``!TmPse|%wXa(qx1S&U zKKwtOzh-N1!v7P?{}XdP+4H?$ukeTWuJP*u-u;Txou}FF{}U_DaHf48|4-LH+lT)r zX8Z8}#FUf&C#F1S?KyruwpsrL{-3T_82?Yq?+yN+IBWeS_&o4|B2=QiRJ%^JEjcF9RB-DyuN@f57>FEeXsYYQ`ROJ|4;KbPPXR_ z^Z&#(<8ng&pO}0#^8du-tKt8N8D9YZPt5qL_S2`Eh_P6ocyP5nk{68HZ z82?XP(9l2lf8x&3krJBzMo)g z|4%UfpO#lx*faQlG2{P_;^p{C)<2VA{6Edl@h1N-X7c~UW#+%(|B1;LO!+h6M+bjAm?{19jSy5(Ob*~TC9a;|^;KW$%W{Xp_dyd3|H z{6F6w^JDSP+AM*dSKKw!aKQVqG z{-2oX@&Cju5C2b$uZaIA=6vJ-iQDb^!v7Puna_*=C+7U&|HX{|7xUw9eBj4}^H=lC zhtA|H;{R!S82?XFh?e39VaSA6MQRK08Fkm3Jy#?Kqn^DE~%8~^;#AG&#x`NH^r+P;bA6Aypw zYoDI^pMLz`3C92P{kQRZ@&Ck(-;4hjGx>jF#{0$piy8krdy?4Ih}Ae?ZdDOZ$QK1CoAQZNH=+na=l1bH4$}JiUQ~ zlj}?8C;k|x{k=4&eZ4fNm!C7xo)01)C(UV}v9M2ae}<-x$FS7#%E`$|EPup^ z@c9p%>|9VZDue&0>DfN~KQYT+zRL;s+oqfbH&h_>6!T(eF?Afz}|0kZgctP<0w7iDNhe`3ZT#{Y{M|IgX{H1hw%jCYIwCnlee z@qfiFC0*nHipd+q{}apq6LbFY|HN!B{-2m~{J)s-|HMp>{}(gll;G!@&Bqe4G8{UbG9}3f8z1uCMNFJ=}qGj z++0+VV3r@>-!%nE|BrmhxIE2uMf68>`-F@)95a3+{$Jr=ZcF%oHU??%|0)tCuY2vefD{ClQ~Pl_p7u#Km0#2?cMl)Vtf(&Ke5LDjT!$>T>BsYFJ{ZH_Hw@e z$Ny6~jQ{6s?Z^0kV%q2N|HR}i;s1&G-VXmyO#3wcU(EP_V*C{RKOGPJ75qOj?bG;w zF<)x_pBTRe|4&>$b4}SH~4=slm92C zJskfpX8b=f{sI19%=mv|)`$NWGyb2L{m1_k(;koiC#F3H|1W0zKQZlF_V(Y#;ug&KG_m{-2okQ2akJejol{Hx~r|FXn^H{}a<5hyNEd{-2os zGW>v`+Outf@&9~!Yk$W7iy8kKb|HXXOao0K1epz|ewF!RY7wetbpM^KAbEducla1Fn)1H6I6IVOaUb)L_ zS2?r&*MD+lg6qG(!kO*E|I_xdKlp!QwvYV3nDPI_EFb?*+%mT` zM~3`AG4&(+%1@73O>3 z|2f<8@&CkCcK_r5b#qt#U(EP_VvZmFpE%^}ng1uIe#8HZ8UIgA|2X-7x_;oMzb)8w zVcE4^f~cHSm)YJ$IqUwPwmyE${bC+#%Hne+Yblv&QrmXC)2r}?=a z@&97B{_ahOpMP!e4;c>}|4+>LUig1v#;+v*Pt5q2*8k(%i_e4qr~SeA!T%F8Kly(# zlm92Czk&R}n92VW*V%Ya_|LOeZTb^G2*L|JoAHe@p`DD93@c+d4EBJq6d>{NjG4)eZ?#|9-)?Z=yP0smK z24{}_#rDqB54*g$tuynlUA)aE%ZLj;Ym;4HRhMn$OdjO(&u`&8-tyoM+i7!W^67S( z@)PG~>))Ec^$(p|9>@Q}6TeCDQ=fh1%;=UiT|f^&OiR2xWW7>{68`M`S^cg&JX^d znEVv{KXGY?<(0gDPN(h%e0A&3bH?vp{>o|2JfGdR+o}YcFXhbdJN}=R$L}frpP2dq z|1W0zznIDY6W7`E0REqtd_DZXnDPI_93ShCcjoy9|4-%AKlpz!)VKJ5 zV$Ki#pP2K9|0l**BmXaE{68`E1O8vk_mpL)V#^jGti3bEbbC|4;KbnBQo> zFV2iFX}`A#w*7bJdd2_K@#A^Gj-QwFerDsfIrBbfKB66FShMhX zXY%Rs|5VQVKKXw!^jY^N82?Z6)Bc11C+7Oa|I_v|KJ={<9*fEgga4=Lx&HD0#I#r7|B3nj4*yRa z-q-*2a#Qsl>w>?>{d?09e@*bwAHV6$^ey|o>&)`;|1>|}r{VvJd4Ig>`A-vk;Iw}v z82?Y(!}NFb`^K5yhm$Y)KEe2ZnqK~&xYhDR@&Cm9zJ2q|mRW5N{KmOkJ2U@7ZQCXo z|4;K%j{g^P`?oteQ~%w1PY-9_e|J5uSAzFAXP2zbAIJCp_CC%mAOBC~85=sa)0R#j>k=|Q{Hp-xz4@C%>TU$#yd0rC36d$ z`F;QK){~rhKEnUg^wh`yiy8k<=a2IL#EZ@6!T%HU{D=Q1mj5T_dW`=UGyb0#U;Bo$ z>wNj#4{Y7n;LQ5t|EWILd;C8!?KSM3)`X8;+djy4fBWJgoe6hWbUQOX!}Wj6J2O73 zJ-_93y=D6jJ*>~m@nh}x)|vHdcz32V+k3?=vz__=`O}qioq3+#w|c%a{a+8ix4?P2 zjcolr!y*|EK9WzLuSHj4zMt&3y}xbLM;) zJLUxE#k)4<`i7tA>ksd`=%oD9UtS%)pW^&#-tm-#@&8oL@rC~v^OP&k@b<#b!~awJ zvA+0!F+W&&wzoI+@&DBRLRuycL?<*on7?(cp7_SpRh{-5@D zpY>1^-XSBYq+NpBTSzGxPt% z++X1T#f<+ao;ANb_u^-RJkxx7{6CfV%r6Z7pSXMO#Nhvl@%PC86VI^wgZyik`}suv zAO4@N7cl;xSpJ`Q+Uz3BTfNH5+h-Q%+WNlZ++_KEhZbM$jNgac5*@vqKL5PmI53?+2Vqt(^Qn_5ZPa{J)qP|5uEE$oRi8 zlm92ikHP;FGybo=|M2DENHe`+rn|4%IcFJ}BdO^@G({}(gk|7v~k!z>@e%VEpU zaAtb^Kh=lv|1>}9zj4P?zCQ5I*FEjb`r-enK8*h-#!tlm6L++Y5B{H6{$I@ae`50X zo_YS)3FH5Hxvj6g-}Loi{qg_QUNHH8G2{OYn|*um|Cm4iU(EP_V$M&-|JCwf#{Z2O z|1W0zKe6)vVt#hl*9X_fe98Qb-#gR3H#h#lx!1-c#{bjwJ*{JNtA@Yn<<$RRleZGa z|5JU+@&B~_^8aGS|5JU+@&Cl~|I{Ax|HSxyd-lKQ?FDan>z|#;_q*$w_Y=nd)AaKH zV#fayGd=!a%=mv|rpNyi%l{LTzlZ-9Gyb0#zwh`z|2<*+zqlO#Pt17Y_f3zzSh`k7hZFw0s0FUwiquV74?KUgs`%^$2Bm6n%|-Z9x<6&e4p zYGPqhUSE>t|J9YI`@5+kEw8P}7h%=VK17c>5!nDJuq|HO!B z+|}9^{6F#RmiFNPiKo>yhWtM z5dSY`{68_i8vdV{;}8E&EdMWN^8dt@jh3(S^xnRI;qyM*%el<<7vuk`etBDc@c*>` zXSFs5|4%%#r78G-V)6m;|HSx!_R#{Uy@JTU&RxWe|A^+z~Y zcXTG_XPxC)#^-BAT|>h7n{j#ee6O04`oJ}1sSiwkWjuX%RXW~pRZTiRIC+BP|Gm8U z&fx!5brl8wPh3B(G>rc%CjSrrk8h;5I_tO|82?W!|4%IcFJ|)p#PomT|B30(eg3hR z6UP5jIsNJQe`5SQ{68`M^Z0);$BnC!OgZ!~gT;ec}I!nI8Wy=AUjh z$mI9!G4f|#PJZ9JlOJ|6<1fiy8kfX8gaH@&BByKOO%sX8b=f-#_C2 z#f<+aroX87H_K_9O#eUrU(EP_V%87;FXm5g z__j0cga4;;+6VtnO#kZq`ImY7!;|*9)S36ue?9aPXQs#hi}x4)pBR4v|IgX_d-4Co zZMOaRe`3ym{68`0KmMPX>kIy$xXJoc@&Cky<_9)!Gsq>oROGf9d%lk?|1q?UUg&eE65MC_dm{a%m=jh zL(b%RZEFxcPGv)YyYEP~o zTyEQg|0gcB^Y7C7Db5^^_5e#FM9u3;v(Dt!GrOvvaJM&zN77TXy1(&eP1dIQB=Q zoab75m~Y{X?{{16@PvQ9a;P)cKm0!(U$FTbUe5k4n!KHJxA`;q{kCz&AKUADTP3_` z;g&wX1O=Nq&>+#fvh=TDt^fA;x-pExsp z+be%{#{WNN*S|P3J^tUbd#?_DB7QjjpBNwMH&R;p>2jc&!9A5v=Cw%?dZM@%4j`^8$tNDMHujY*Zw{ri7ovZD5yXnP# z=eng+bFVFaz`1!Z`#m)OPwj{Qh5skU_rm{+`SYu9*`VW%a`U&GIUelYigOshew*(* zGoJDr=X@_=^SzweKg&+M(z)BdFT(%R^6}5{|HO?umj?e&>%;XK|4+>LcKCndMfScQ z|4+P=-4EdZiMfBl|BD&_Pt5U+{}(g5!7+($lPt5s-|0m{pj{hg-dXN7nCcg*&Pt5k>|B0!O{}(gau=KZz#bV zjQ=NQdu+VQgz^94a{RxT@&CkM_=5L~`F-J^nB&{#*CC#2{w@BWnEi|Y7c>5!nDfWh zuS?AFXzTCH_bIl0&O9IB|Ec}Rk2F8hxz+B+@c&fK{TKe9nENmMKQYhi_y{}bb@;s1$i=S&LzpSW&rA;*uGwv{RjAenx5x*{6F!0%k#qj6VpF{|0m}AMf^W8;|tsVP3DjPr}dHl zC$6{qSMvYF{GQ|gi5Xv){6Fzj%iAOWPdt9^q~QOF3+(qD|4)pMNB&>T_~{J)mRevtToV*E|~znJm=#5MN4<%;QdcCYF9LGb6; z-ii%(JF~y>|5P8w{}VTvA8}#DMz0Sq{lUY|j6dWiq%*%Pc_|dQ@oyq?_ z^XtzzbALW>i(fhOJTvNy=biC;erNul)*n9*|4)n$g8vsY{-2os3H(1X{to`1nEMa> zKQZ}m_|njiH?jodt8{6CfReGC4dnENsO zKQZ~G>$cj?nd|Mvk8Gdtac2#2X8dyeKdldp|0m}9d{XPkgkSw=RKnBm-Z9}dM~`)8 zd+`5symCFo|BD&_PfUIMznJm=#7zJDS(BY-n_o6(%TniAcD=aur)AFcZw)(lsx#v| z96zJdnf|_)Hmi0fzaIZj=O=y{{-2i5_i6ZlV(xG7|5U%*z7NFz6LbHB{}(g2JXQ6SIBze`21;@&Ck}U-*A9QwA7jYIm_42>-U8H_3Wg*^17d7d$!$gpSnZEO$s;Tzl%I3ddCqw|zK&gTzB7K|K@DF^ zc-e>xoM+kjI`3~OcRhFEV7Z+iV|u>s$0z5D{r);L-tQ^@9^{2~fA#n`zv1Wa3>y#W z)FZy>+&6zJzt=u}r#ChmpnQAKXFCJn2`S`p3-dN@tXf9mj5T7I(10!|8V~B|EkKj3;v(DqI8=a z{-1bq**3W`BYv3gZ@we=R29`bfeLy{Xt%g--rLF{zDl5Pt5qk_`1 zBSZe5$}4PqR`UPE_+R*cV#a^P{}ba|;s0s<@U`&&#Pa`Q#{bjwl;i)!O#WZY_I@mx zpXFyblh?ERrL zexSWybnfn)$oofU{6Kp@>D+8SoV~wvrakfhv_75fqjOI!c)^c9e9MzNUv$O?#Q)Rr zN**KrU(EP_Vz!t3KQZm`@*iGtX8sra^3{ax{jaYN<@SEqndRgEX?CF8wun8shs-we`5CEz8?%SJ|6y`%JJpM{}VI)jhk5q^cUwZyz_^HEdNjC^8dt~ z5BPsENa65pX_a+*h1S(N6>W%KK@ob}tX zob~OpoUNbb%7RROUxp_aqX&6Xo9CCEKFft;Q-3b&|7AHl9&pz8%ld-Z z>9amwma{%zmb3YOS#BLQGC3ZyoUNZ7zc)LcaLK5l$^42&3`saUzHoND-)!DrWobG- zZ&k+M$@)I{da=)g&lNLyX)%)z7jtJtb#C7i&)Rs|-4jE;AAT0&|B72G2K+xU%g6r{ z@d3*02{6F!22kjI5Kk>4Cb`AcYc+Y7A z2t6XPd7Q?{3HKY4xR|EZk3Kl1-#CjU>|+Ef?(znJm=#EgfF{}(g) zf8u$y1LOaS=g_|9|A|>2{J)sv^Re4}#+W!?-*Qqei;0}#;)Sv|B1V1R&xK=Zw}MI_`dc%8vdV{{#X3Jn92VWGad~2 ze`0(;{68_{-{Aj=JFGt(|4-ay{pI+7V)FX%|HQrXN`wC==J_B0PfY(j{-1dEf`R{JckDU2F6#q~4=|4RBFL!x4Y|sA*}P+wuQm#{Uzu{`h}ld`A2~G3|x_C#HSy z|HRbC{}c0m9sf_v`d9w_N?$+t^lb*2_XYTWst@D;iK&nOC&m}T{}WRm|4+v|jQnHx7xZbYk_Tz3 zKXJ&9xN?ct=lHvii8+4p|HPb+_zeA$KJ=_|7rc} z7flKNpBUc~|4+>EhyN$W54G{Te15zyvV0F`-tXc6sXo)=|HX{|Cnlc^|4;4Tyr3lb zf8uI;pO611t~DPJ|4-aJuPFF`;;Lz5g8wJ3nLa%Df8wqsg~9(5b9~_ci8(&-|HO>n zivK6Z_r(7bljrsJ+9A&PX83<9$B*lJZd>18e9&bhwi#p_ulCp_TRHdH_`H{VYYS(_ z_q=?}<~~2(FWdf^Q|4-)+ z{^PAbf7iKp58K|pcbwUt;``rlCVy|A`q!No8(+2N)r6m&^s@7O%QO7amCq+^d1(os zeeN>}J&JX;*nDPI_T#xbp#QZ+u|B1Pu!~YZGKim2_^ZR4%lQ90D+Lz~V{68_z z-+P$Yq`!N5c4j@%-`sVkZAj%=Y2`i8cPOnD)p2iy8kzv$@*iKcu6z90 z8-w2mU-7eBoyjM}|5G`P|0iypTbBE{<=%uJyyF39zBk4HQ~k--UxWWArhN-1KAJH8 zpO>4@iT@`iZxH{_+2)7;CvLO*d;C8!{T=v!Vt%ji|HRz?-p__PbN!og?}&uAJ#LgU>xciRakNAHo=X#6(C+2#M z|0ixWzYhOTOnw{wpLm)b@1?ixG{|;7UURH;@Nt ze&EQTer1qte#d_6P-pt*p4(%kGv{x`3oG+?RILquAH3alM>w;8@A~eMzC3v3m%r*v z|Eu*^IP?7^{-4&5{5f`^Zec+D@&h++! z%W`K8vh}av|EYbs-r4=Qw?E?tm$aVa+_$haciWTa`2OQ~y6(1B&iHcpf7-uX|MCCC z9A5>mp6AC)kFC$5{_~xCZF}tZ)S2;m?>hYgXU^w0_Px*<-|w#XFZA<)lOC`j#`}^}bepu`_x7mwo9HXP*Dp^j_-g1KaPrGydN8 zn_TYPWqu(3pU$Tl=I0Mt`E8$H-#{L)Gxd+IyfWd*+g;_{Gjmez*MA)3uD%I;Kj7uP z`3b@Q)AH~EpML!sUw(U+`3*n0)*0Uk|4;i1zmNPsF@6>Ke`0(j{6C$)HRk)^|B1=7 zBmYl~?}Gm)W;|Z<|HS3xUkd&ojvxMCY3cCb|A{A09vb{Vabd-F!T;0y0`dUy|HS0| zk^iUuzA%2T`F~>kKFb$K82?ZGiSqx%b#|c97l`#IF=1;l3-%85u{a3>HfAReA|HLfM-mf|1qv8Ll9Nu@kr+k05c82meppXZ7*_#Eg%N|0l+m#QziH$KwCRjQ=NQdi*~z zJ|O;|jz4@m{68`C!~YYrJp8|y@&CkiHl8s4pP2ES@&Cl~|6*=___topc)Iw1TEEtg z(ZT-{Gd?r^pP2EP@&Cl~|6-o8=Nmr%;Q!5eGhzHc)#rGgU;4I}!+#(7j|5G`P|0kCJC$2I77XMG&)HXc$f8yr$5jp%nG4sR!iy8kkNm%wZ)yB2uj?Pvzf|jwNkaYOA6!T%H2RqYV`znEj+A?yEDmyAh#h^|aNUT0?f+iad+ zmb1R!)Pi*WS)VS;|1HlhTb}jbvh&N1H#=rbx;|sarat6<*mV0>TmyYT`22K+zPAOA0A{68^yZ-4vti9S6% z>7f&x@&D$$dwjx2?>NZh%U#=doR@c5zS^UQAM0GYWMT0CwEp=+4h;UExM8o|L;jz5 zcxP+y|HKPzJX-uet?vxmfB1i5{5$+Vajk7X{-2n+o| z54QWSesh+B-`Ce`<7dtIz4Ppu6~X^gIX)l$pBVqo?*IDvChD;D$M(SXeTXyl?f%i3 z_X&1?nXuh|I`ce_|EKx$yl?lfUcSJdm+k)6dA@xQXZOF()W`per^o*j)Bi#KU(EP_ zV%{Gde#0+)e(=V-pLNFH!2eTy{ELI0f5yw{-?Ha}gz^7WpZVeciJ2e%pP2py{68`M z3;2Ix`cv@##PrAD|B0C%|4+>H_|WKG_j&k# zst;QhwlniPVA*X6Sw8+>%=mv|#v393FJ}BdG0VgM6Vu<0|0gED1^+K*{68^1 z;PqSF=H_8vjqs`)T~Y znDPH&#{UzuJp4Z~*H7~Q#9V*z|D3J=9sf_;Lw`K}pBTRn|1W0zKQaB$_Oc5bt3%!&`HJ{|V)Fg)|6<1fd$e&)@c;OI z!T_V>2-_G-8FDR^~D=VrV9-dC`N^K^S(cH5Ji`Sdevyt2o)+tiusJN}>6 zNB*Cf@q6+A#9Z(3|HS-$;s1&G{jxkWXMCx@ZThY=<5^dq_O>&5e+Pf^2j>O*wg&%C z=ihG2JA(fw-o@Gj|4+PN-^`hXV=?=@&CNO?LYj#nDPI_tUvx=%=mv| z+86&%JkY-5oLOJ|Kb6Dye=+0##cch%>(xGNAO2s=_A~)*t^bX7l0J z>w1b`j{hg-_Xz(_jNga<7qj_S&f)xhVEXz`-x%rAIT<*;A)cM2T-mh|)e`5A8{-5SIz$-e%9AEfkGAo3@&Cj-nonl!=S<$7wQs_GSs%v#jhXyEG4JQ`|HNz${-2opNBloA{(}9!b!&aN|HJ>&_QB-; z#f<+KGyb2L<=giL3FH5%oc;s+znJm=V#fay(_exACuV!_|HLd0|4&T+2>zeAVeY{A zzhd?e{-2ofeewUq^8dv0|HSxy_c;%p-#(xRUbNfY&iD@a zf2t4T|A`Cj_{0Abmsma&{-2oR5&th{{68_z6Zn5IOL82?YlE5AR#zICGWEc+hm(AOt< zea81){69s`J6T>>%iblhs6 ze|e3s561`opUyY=e`0*Ei?43<`tV1~nw{~B_Smu2nej$9KG)_P{Hn`45Bx--|$Wv9$cctgkRgo{3%2`kN|A}YV^S@o6oym8@|I_aUjQ=O*__pWkgz^9Md&BYlN%`Ihzx1bloH@Qe zUAZE!`|%)TL)SbN%c&_N;^--|lSR zAM{tRe|M1k?DrM_Py3Jj`t!S2`Tow^@0I;NIycz;&!7G^$Su~N(ss#temt@KKOS|y zGuQ8H7k|x}{kv1$1|xS&ky={&N}1k&YW*|?R$|k=i8gz-*D!5 zA6xKEXY&2<|8#y$n_Ce4KXK3O@xlKSH_RNLoB7@)UcYhH1j|po)aQr4H+$J-&fW7$ za(iENx!0dJuRQpFn%|r`rF;+I<@_Gw|EV0t{}cDkDG&aixN};_5B75Te>y*5{6BGX zkB#qV{-3xhKQ8!x+Q0Z!_%iA#+6TU=JLeeSL6f9O2P@~iCqfX@#m|4;pY@RU-b$1`||MrUOMmrXZe4skDrA9r~Xpf5C2cx zX+9SIpBNts|4&SP%Xdf^|1U1b|I_jq9~l2n%>Kpyiy8kfX8gaH?fq54_UgaD=n{Y_nx0S69{Jqw<62||F%klqWCjT#H^8aG~_wWAXjBkhkr*fG5Ke7BjG3Ouo ze=+0#iQ8HS{6BGf+kpQkmj5SadH8>WJTm0}iOKiG{}WRm|4+>P@c+b=s@oh@ZkT6@%!-q#FXRz#f<+KGx>kwrut#Q|I_knY`k{z|HRdH z{UrZS%=MA{KQX>^>{Dd@zbwzljKA79A%nHqjyN!C+oXqm!I|XswSrXVBfe2$^2$y+Allaan}DU znV9-|MH5p0Fw2w1rQ26FI$fWv|CjY4C+?Uo@4uC2=l>r(HeH|pXwSMdU#qk>_51Ma z;^Q@&|CcS#=Kqlg7f+uZFBG3DE^jHD68yjXio)RkHI$bG|4&?BRvi34@x+RvkpCwx ztSSlP|B6{Z#{U(w{`h}l^5F3Q&c1F^@CES!8UHut>v~Rh#*cga(370;+wlKXA72vx zPmB+V|0ibq@&ClM7yh5P!p2L*{}T_b>ka;&xPHlg!T%HQeBc4W{}WGNx@++N#0T`% zhVg&JOPh*r-_zOnzba>ZR{TFP<1OR=J^9$g zke^8YBL1JaqO2tNf2uG4Ph3+sHTZvG^5)3@i<$9%#dWn)g8wI;T0SxOe`5K6;wkmz z!T%FC*VX4nPh8>a$NpJ9Z}}kCRpr(lzi+~S{r*1A1$8#Qiur%qzA=?0!T%FiRg?t( zPh3}17W_Xk%g6r{x70TT|IgWcK>RvuK$xeJJa!p%e$L{ z|F>V!-NFBxnr{jIpN(M}{J+kb<-z|Gch9cK+5KBT-#Fp-@jPhvch2qBAB+E|a=u@~ z|BD&_Pt5oH_|JG(E>R{+}4X7XMGo@rVB>o@vK3 z{-2osO8h@D^TYoWy&Re}MldCVvwDPxZ-9!2h$%o#6lR`-1-`X8Z8} zV#fb7$0qoHw8x+xwkXIqEA9Aj+@j31Nk#oKE*IT|s!j?bbTy6dLmQUea zW%cp@eEH`0k^dJn{+}2>0sk*%^8d7bcm zX8gaH$^R2`KZ5@!W;|c~znJm=#5D^C{6BI1;^N@{i8(*<|HS+r;s1$y&3D89)A2IH z^0OHKS4_Si{-2n@&A7Qn_)h`*1a2YZ;c!3+-doB_-}!~Y?d(opO(k<_N}=&XY#MC|7nBD`F+h_^bcpQ zrzdRvu`|9C{-3s=@lNso#N-#^|B1=_!~YY{wf4aO6E9pbkpH*EjcbFCyTp7z^8aEU zanMVH_08W~_`6>xjQ^+lyGi4%_v_ znd^aF9|qa(H}L;_dTUSoKXIOXz;A8g^6nsDK|M34} z#{U!3zl8s%>FHm3bH)Q+&i&e*>-(KKA5Lp}*cty6|4-9%JmUX}xu3)T6O$jlZp1S_ zJ^e$+ef^it^gm78?0IMM0`dQReXTzQ|4+<#!}xzOAMyGhoH>5m_k26yEuQ_8GyOBq z%zZ!MYaaU0nfV{w{;_kD`9b)9+8*+%@c+c*&*A@x@x}1}#N=1w|A~3t#QziXdx!rg z=6)0ZFJ}BdG3PJ-pP1(({68_*w-f%fLtgCz@3VTCGuO}Q2aIs$d&lxgqn!C(75`83 zKaMyihf^&HOpEA*z{sR0z)yMzA{}V5?>ofkJnD4Xj|HNFs@c+a+ z+3|w^7c>5!nEo{UKQaAnSNyEnnd9Tpg1WrUFUHTP{7tTG%Ve`3xz{68_*SNuOQ=NJB; zxc3YHFJ}BdUEk>c#s7;L|4)n`xbyqFBz({9yE)U|_<#ESz`wNnHD~%q?D^c8{*f(? z*vEOk`JNkYTb|eN*BtwO+^2s3yzbw5zQg}}WAk;v2kf%E`NuXKl>f<>*9E_i^QUsv zSDbt7egywde6nvJ*Vid`o$ActHXd$51;|I|M0U;IBYzt1mJoaOCF z{|)}1_QzbCAO4@1_T6otbA12F|I_~Nwe`dQ6L;9}^SO7P>&H{Koe%hbI-WTH@c+c@ zfBZi&{X6)7G2{P<@i+1Rbbi42e`3xr{J)s-|HK^M_DK>nY$r*F3T_2&PH zJB{)G#9ecy1piOmGrc(Yf8x%biQGSU{igh+kpHLs0ptIPmH#Jh?U;~jyy3fEPF~r8 z=X}q($@0kX|8zXmb&d@FpN^;cu2I4N6XUnx|B0uXPlEp^R{ozD|F8a?+w$t4mj5R% znY?B2|HR|UwhI2AxY+Wk_*+c=--wIvawh-J-XG-EAE^94^#|g!*!u@BZ!+J{-cL9; z*IRzyckXp&yiR++;f!yD|EKxO|BKn)pCsk>ekJeAw|qd$UvMVx%<>tW@vkhu!5RPW z?SDP!^Mk+r?n4Rpz5K9qgZX~%|LiBuJNYP7YW<@Luc~y z?ERuM$G5$IbY^@0_sr*<>n%_4m?MAf%=tn7pY|V&|EJ~Ce)xYe+xt^zd_?>|l{0=Y z{-2okBmXaE{68^yb@+ecmX49U|8>US!~at`jQJcjpG1e#!3taL%_3&z(N= zQ|IpHVZr~?^-cbtSpJ{5qhUnw|HSR}!$ba`xV~|C$o~`9+4Y(6f3-at|5r>o{-3z5 zYDDn=Vvc=@tnXJlB^}?ksU#hLx1p#Y@h9pFQ@<@+p7q(XK43N~54>IYWunEGT{ z->qOwntzw|^|Joij$_mMSuPwuD%sxR%y`1t@qDxEpB*nbo1a*b@df{bC#2h-^$oLm zfLX2?o$k-NG3oxw<|StRy{!LNG%oc$v(x_vk4xJx>vQ7E#m8fovw45`VR8NJc%PN! z_I+jU!87z9{+|Bk|Fu&J|4*(inV7rml`}W)eq3Sj@oI_-a^=SiGRN&q( zo#FLafAaq{{gkT8kpCBRasR1aPCg+1pUUyo@c+d4e)xYe$Gd^qoF^4+0 z*H-1;{@x)8lmDmsv`^PZ2Rk#KEct&bXZ%_GznJm=#EgH-_`hP>pZq^Dd5mp;-`|;h zJo5ikPTn2{k~>5=hph>;Qy(dd`bMjm>K_9^J9Er z{68`KBR*ei>M9eiZ%p$-v%X)}7cB2;O{TA&mim9K)_(Ew>N}beF6pWX{@*u;{V4c< zWxWl-|0A<}tFw;lX`Nlk_Zj_s!-Ve#!VxBMY|HL!D$o~`5 zKY;%iGyY%9c7N(D|4-#G{$I@af8uiMPbk{=dFQFtKZ5_K?W6wz|4)pcg8!%K@$c~e z#Q1mke`5NF?fyPt{6Cd5fAastt@gZ+|0kwD4F69||1KKKQZ&i|BD&_ zPuoNP2L7Lz{4V@IG5z8Ae=+0#iJ3qCU(ELW=F6kM#-8t-X+L}ZbDnDbW%hiSF#ey` zm;SGY`}_NOM#cw&w|HWMGyQE%(>Hj1`s3EU|A3eC{`9m>QeHgbelO?y>EbE(C2a2# zobeMMn{!XX*X;RYXZo*?SotI88MZ%qPruul@po+9o$>GNUe;OupSG9&Im^2Ca{AYo zKYx3|*8h<3=AYf_%=Y5{X?_*vCv9`eEzVWuC+&05&Cd8g_|HSnF@4Mw7%m35# zF#ewyp9B9dX8b=f>yQ5@W_kF3;$3!W2>zd#d_Md?G4BiT|HSxv_FKKX_Ce`2;5|4*#(e>J`QznJm=#Iz^=U(EP_V)=h! z`F~>Gui*b_`5OOMjDL2`wdec%7$3Ff*7KaXK0LJHTxYHiyFInanfDv`e_9^zZ}I=c z%>TnH&+_($XRSTc8Q-n$xHFt7fBwqToGHiui|1GT%1K_%c(0HB`-Ft?|5U$ZNonx^ z#AW8o;Qxsk9}53Z%=l3Fe>y&BfBZkO{6E#FzZm~-{uOJ#@c#z#|HNE>ZG58sbsrD- ze*AuX>B`;vThCt?{384`{6Cd9nh%EmCoZ?+3I9*?n`*}!`F~>aMQwbg{{Ai22EUK@ zYnFH8%=wJ}r}74SpJVTD`j_9hCis4R=BMHRiSu*E2meo8v|vK;|HM-k7Y6@NOuioe zpP0Nn{6BH)qRGMki}^b}?Osm*x{Yt;%=<1I|H_&7Q#L+U!f&i@@a>`e%(v>CdB0`8 zfHT+kdk?BknDKwr9!yXEU(DtoIFtW?|EKouHQy8ePt5s-{}(g;Hi)&Iipah|oCz5n~e80UF5p6hYNJ37y{@p~^>G0J(4`F<}Ij_~<+?A>H} z1H-)i@cU|Z+QGSLpQha7-~3X-=F>Pc{_`e7w{^y+yLR!`&iICHmu%^rxBSRo{$le% zHs1#SPwk6;^TD;7I5R#l{-3sgwq2j`|HPbs_VqKb=4F|HNz$ z{+}2h5dTk1{-5PvInQ0*o_py}uQ<=K@s9ETRG)JEznCpAEn)mWmCxF{CHQ|alm91X z{ABX~#N;QE|0nL-d8+wj8+>~?Ub^Sp?~G4oK9)22Xt(v=mGIl^Z+E6W@c%S_+QZ(Z zIM28BA^%V1^UP1g{}Z!3{68_i8vdX27ye(&_^K+cLt^Lg3aVB39|4-ACFNyyr=6Z_%C&p*M{}cD@S`qv|@wBCu zS7ZL4nD)W{iy8kDq3aXJ2%%<;jw&!1)zjLeQsabtz@@wsS+NJvB*W&+a`)Y0cRs26Oc{lifV)EgveVof? z4fua5Z<<{Y{6BGv<;`0Adwu*Y{6Cd9+WU3^b;ho$5 z>CE%3`K8_3|1kca7@r0IPt5Z;{-2ooIPutTtV^Z+{V#fay*IPOMUvB1_ zfqXw>{68`4NB&>T<}!63bNA}t|KSHR{;!z4K>WXvyRHuYAKQ=r7c>5!nDYt$Pt$Y0 z;s2=|-w*#UX8gZFE)V{nrf0lq{6BGx-B17ankT$|ogE+ef0`a&4*yR)%lfzQ|HO6X z58?mCjQ=Ob55)hA8UIhr@rnNzGyb2L;~W1kX8b>AJAU#1#Q01NcmBh<&-h>E|8nlN z;~W3)m@oDZ<455CiRll){}c0lA^u;&JzM2RezE^3f9q{}=PQ z=KsZv{}=O7eMP=JzAst&d9gFkANYS>-x&W-JkPEN_63hRK8UIhr{>1-_8UIgA{~rFIxYV|H z{DSGuB@2slXKp*wxpeWA+#8S0a_0AO?)h_^JM4M(_L=jX@zcov)Aa~nYEj!x&h#JO z^~oYMTh0Dcx%8PgwI%Vc*3ub zKGK=~${D{o%9;It)AdI?vwqtge5^Cy=i~or{#|yzfd41PzsCO)x7zmv_-DjL&z= z=x;l>PA|;8`q3b_&n(UjeeQ~+eEQv2Mm#Y7uiCf4^84`r#FgEng8!%eRo!EGQs)1O z+wzv*WBGsL_MUOU{}WS=|0l+8!vE9pfnP=bpN=PdAoBmj%KsBjw!FMocmIJOzvS;7 zdF73Md{3zw@c+~wjsN$|+}rc#{`-gd4aXkSGkMBZx$f3GoQuo{ym|7S&dUGO^b_j_ z{J)s-|I{By{vi2(>JP*R#Q#(I^vaRJ|BD&_Pdv45WbpsQB-93ja^@qy6#!V#fayZ|HLeh{68_iBmSS5d_Vj@@$`;~ z!T%HYwvG?^e`4l$|8Bp?YyY#nx28XvF#ezF(|-7WV)6>{|HO=cjsGWR`|SN@!uWqG zpV~e!{;!xkMEpN7`F*F~@RF}jbKA(=&6m9FjNgX;r}~Uvi~lDkuMYoD+|fSZ|2bRx z;s3>q{}(gMLH=LN_Q} zbLRZS|I_g%|1W0zzd;_E!~csJ|4&@kG$QzaF_Zr%#`k0VUok$S^$$7EtREQvSLHM6 z2FCvt*I1q)`F}C*`{i7Zvt2)reR+`a|1R8l6EAPC8y);VwP#Cpn*UcfHTC&w%2L0p zVoK`&l@+J{ST?^d%T<~Dz`Ekp&+3^}XuUy$zE;+kYaNyPep#Nd#C>b82?v{-*@#_PTAOgRAKP($oqT! z@{^tM{TTmO<@j-o|0`~)tqb{onjgLt`F~>ktX+;i-s_XshX1GO@vZRx#C?qe{-37r zt+(-a&Hod()l>%mPh3?zDfoZlA{)A#0sl|j*PRdk zpBR6Q{68_{(=z_AnC)Tw-#R5b#{54qd5iJ+SZjW3%vt}ht05gP9G@|+kDnQH zYkTVV<-5~-!Oo6!`l`0_;Qu|a$&Z8o*Vt2=v-_`po>B1qx@^2({6BH`tO5T|%y_=! z|HX{|C+7LTaqn0A&6x^*7rf;WuQ=1+^THXwai-kvKb|Ec~0^ZiCP{L{xZ|M1NZ{ybs)Kdm4BApV~if6%^va%Ot` zKW!h3|0l+;u;(kU-?CFl&Yr)V@f+;S^};Lbo$24g|5G{j@&97R{}bc?;Qz&p|0kyZ8UIgA|0@2UnEo65 zznJZBXY!ZqUey_Y5&uv1@jEQr+8N&p|4-%B)<2E^C$2Hy3;$2d`(pgRn4jN%kn#QS z|J2^q_C6W^PfULz{$I@ae`3~m>4R$$Uh|99&a5x~pXvu+%=|wwFWbueeV^{_yqWWI-g+j|HSx#$9G@u^MfDX=`v^hKKwsjf8p70UgFcU|6ls}VrP5; z^8Yk{%E|u|Q;z>9X8ZB~#Js=2{}YpMNB*C<&5oZ3UcAuPhx6~)Q!eoG>2`hF`l7En zbN=K1X?otT;{S>1Kga)z`5yFM{($lS#9V*z|HOGa z-|_#%Tz^iz{}gBZLi|6Kv;FvgV)FftC_a9W?ffDCPwU^ltG%x>|4+>Ega0QczX$(M z^P~Oo|HShDRG;hD-$x$e<$RyM`kKA^XFq=PKwf~g$5DIj(SOJxHwWLZbK#WW|A~43 zjQ=^n2F#eyI^Be!K`-FADFJycy{68_r3;y5xZw&Z<98dPXyMNfZYlGhhTRwwx zt1S=zPvzv(;s1#luh-t6JCC&Y0p$Owe6-~OlK&^3VtEnxf8tX6y}|zz;~$d$C&o9% z{}Ypsfd406VAo^(KQX>E{-2onZQa-4%=Y2`#oLenC#F9BU(EP_;?`XU{J)s-|HN~4 zF3Xi2Seo!pelXd2q3xgLe<*e)-@$waXZ$4mKg|!u{}Yps_4MoGoqH|c@6h6L5!dIo z+JB7mv^^Vg-@kseGk#Y7wUG&b^2Bg&AL`@(sr~wFeA)T`9Ma!7d2R3krY&o>@r=IY z+`D^|z5m$G89xdCPt(Kre`4~p@c&}Q{}Xe)JaYJE&iK{a?y`w9*W(guJ z+s_w0lra9EwwLj9@&Ck(e~kYp#>c|{6XR>)|A`q7xv2e?gz^8hJ~J)v5&us-WB113 z|A}dT{68_rH~ycq?O*c$V!rKrm-+JK|7m^5gTwz5q@#f<+aX8Gj*iSf(u|8zWY ze&PR#yUg#y{}VSZ8_56D^i7tZi2o;Mdi=kb@&Cl+=aK&xGydNoTOObJe`0(({J)s- z|HSxp_m(d$&VrbPvy09CkFpd++cZi_CK{ zxj)7K6Z1U^{+}4X0RK-s&3qI5Keadg3;2IAkGW@wbMt(A9=&^+GyM(tf0`ftBlv&f zI?K~pe(T|0pX1{L^Zzt|{673YaoMa%_Ir0$!sa(Pm(H9>UXgQ!jrWKDr|HS>A^%Uz z`+V~M#4MluKQTTZ{-3yN#>5={pMLLQ{6BH^%t^uji`lY$=6u2biy8kme$#~O9^1^B^JmnmEfW6B{69_4`s4q_ zjQ=MlzYG6Qj1PzZCuaHhe=+0##f<+a?y>7L{-2oZ_mG!IJM(I5C2b$&xQXNGyb2>Kg#j{#5`Y<|0nJ--|XX-HlLpDefh8L&b_vN58lz~jGuPn z;oS*eSkdE*|8&$_z0NJ>JLCUpdH6{9f8r*4e#QS2)8C8#Czk&w=6oBm`2sKRvHUmu zKV6^X|HX{|r|Yf!KQZ~O_t=qm)aS?VnO)DFIX?0KRGUuXO@ zyZ_7U_e%bsp4T~li|;=$FQ$JL|8Gj=EdzOg_I=3%j~k6P!C1mgH7coaEfTpg8z{TK|@L z6LKH^=9Ikd&)e+zpZq^D*H8REG5Zhy&)Ke@jQ=afhr|C<`@#5sYH#?+;pYtQAL}2% z|I_}b{|Nuj*{+}Xe=+0#>G)!M@&Cm5pZI@b&L8~0nDPI_oS*oAG2{P<+5h-|G2{P< z@mtCN6U+Y-hu<^H|BD&_Pb~jWEdNi8zlr}RZkjbQ_63#0CvKir5d1%JQ}2Y} z|A{Hb{}WSw++|leL{;&2gO#Yvk@lNsoV#fc| z@zK(?WAOiU{J{8sV*DNQ|HNhHli>g9_^q!V8vH+<54Dv;a)l?~$xO^1v7o1D0#`6BbxuIql?6HvW>c{6Ce$ z_HO=)rQ-{?j7)vStpAtw%c?D(E%rUKd3srYZ%ScWKkGL(6{YLnn8`b=otXNGH3jMV zW_`o|Sl>*ZVK(3J|JU~`88tN7{>ovgzgICdUElJd>G;P}hYd-lFB*|@*5Au=cKfp9 z6KDO*Y`$NX8Q(SDpIOfOe_6(_i>I%tN%O<9;|14M+V|y_|F_ws;^6-=Kl1;?_=x2H z#f<+a#_z-b6XQ$a|B2=Q{bhPl;{S=||A{+l>Vp3##-G|a_QZ|OwN<%oXPw}TPlf-d za`}H^d^Y?)@nXxHBmYn9x3Hlh_>=e`4kTiFayj4E|r^ zS%ty>n{VSujNgL) zCvLHP`uj^?>*tw;ytWeSFZo8>?-E`<@3+qMui*cwK8*h-roU(DQ!n?gcO4E#Sa{X_VFG2{P<>0ibF6XVa||B3O>@c&{y{n^Kz z%dEc-|4;h|#{UzOhh@)43ETHm&h$Uw|EWHV|0kyZ1OHD<|H{bye&Wk#{ogwJ;e_v7 z^^h~~Th9J$qqjdia>yX#r>rjQ_j0(Saf5Rhe|P43XU5;%ci98Z^lyD|=>5+0m#sSO zK4*Ni(HGyFF#ey~lYBG$znJm=Vz$4X`99w6J)K#eeH-ZWr+;nC@IhvK@c%SF82?XP zYQ6{lU(EP_V*C^QznJm=VqQ1#7Uz(MSa-8?%g#1_P2akNi+5e?%=Y8|Y5%f)_H>v zEdMWN{68`Mp{Fjt#^=ZT-9=x$+8KYd_?+)JGk)_&mtWg!9s-%($^#2J4D|4-Lv82?W!|4&Rg{+}2h z2LDgoYwd^sCoWzxIrx9#Qp*ct{9iHS9pV3p=URRQ{-2n9GyK1p@&CkJKk)xz#{bj) z;d+AqC&q8X{}VHw5dNQ->l6N;nBxKePmG_4|0gET4gW9ZCA**G?a%v-Pfk9;nd2A# zPxU#UM$J6dne*|1gO7Hmy;od#RKoawnx5ki|4+>OshvMOG~&wO|Eavke$Vj#{&CAK z!T+QEX8w8)XWEPWzwgYyCHR2&+xUOqxbNoR|H0;$^w%!CIrx5j?{DKH^%p<7F68^o zw(YU;lbl(9%U9@UJfOZ62U`BB-CvpiC+7IF_cQ$mZMH7>Ua-BtaV|CA%--)LZ0~=Z z$zQU32zq0NdVW&l%=oA;ZC35vv9vOG{ESLx^1I0YQ~UPrR*9eC<+Cgw zY|fUY&a=%w`TeZP&bwIN7yh57hsQlu=;in;Ki+y$!b|2BIFrA%ef@ZEAAFoOM~`)G zH$QFic4NGL*S;;*zdy>$m)Q8cC$)}rUTEz(>ZIY$A;0VXp$X&v>3C={9|-?X++_Y0 z{-2ojFL-DhXZ)&rHr?78e`}W+TRL}}--rLF{X;$_{$I@ae`3xr{6Do{IKRyQ6LY@e z|B1LlXMD4N{OAK`*4KO$XYvp6|8zc)e~AAlo@eFwf8qt!zBc~lAe;ZU#SyPK z*_qZQ*4>2=UILW{-1c(tjVmuGt=Y$sT`jW|4+>LsQ7Ocg|JwN`wEW>B;ZL{}VG_D*m6C z;}8EYX8b=f{s{h`7(WL8PfY(5{$I@ae=+0##f<+arvC{4FJ}BdG3$r_C#L@k|4+Qo z`fKq2#0#vy=(bnBlvjIk{$7674$hqaC+{-Mne|^WWJJRFf0`f9NBDm+q|0kCJr{f*Q{}V5=_QL-YGhQ(MpP2dM z|HX{|C+2(AnYl)1uD2B%nw+`*?Qn97GuJ=-KTS`65B{H+{4)GMG1KG!#f<+aX8+;; ziMbvw{XyR#+wVo^elrp-oH)xFzX|_O*AMuQSI+fv{P$;eo$uUd*Q*mBUg-7ln_f9{ zku&3i_w_7s=J)B;<9EsHdIrDNyj#Nfe=7gtdhSep{6GCZu)X+yVvbMzKQX@#_ygZ~$E+bhR7^Zbwhr*fYE@&Cjuzhd_jef{a588YrE0f5?0Wjv+%uiopXC3kz1ZLQe=)CbINSHfOgp~t|FpkoKm5O#-#d4e?|=Nf zq65!O82?Yl8@?v~pLm8{ukioGT+i_T#9Z%wI`0BM9@+nGQ!h*y|1YkO{}=Pck6h&S z$>-bjhHp5x%qg|;(ZA`;_{(oE|CV!;-M``gX@2~^JvHGHFXw)v_p?DJ|M{*LFZJ>% z=I>9r_cCXEJM#ZDKbZVKaeIDz@c+aeJrjceCzk&wmj5Siviv^$KkXmxkMaM+HN6A* ze>#6^rw!!)iCNyq+y0Lq53S|{;{WORz<+x2iR+x3+br+R{68Ik_&xZ4VvYYR#`oKy z<3>N;>#BAL{-4gjzKRjS|I_=a&XVne|0kCJC!Scj9sU1#abd-F!T(c#aZ%;=yg$f` zC)N%N{-1bK-SFW5iSZNh|HSx!_@Mb@+cV2?X8b=f{-C`-`+uap2b5h^`M-ZvI-w*XBq3!oz4w}#%$@Xv^a6o|&^sbX z=t`Fk0wMxR6%c75pdu}q(0i5M6zKv=Q7O{?@3SYLclJL1m#p9VvKDLQS$m&z_NjC4 zKF|HUKAw;dX#Ss$2aNw0Gyb2L{6PFaG26rc6SIE&KW&fkQU6y=f9n5=@yYD{qAw5I z`$uP%xA&9IEN|~GooRpY-Dea2^!ewUSzqz}&nG;1Vt?EP@U_WszJ{ds${*PN+8i~pzXlP8G(7c>5!nDOENiOKhS z@be%6Qo7c>4}%=mv|#*hD}?ZfzgV)mc>zqmjC zpBTT7{J)s-|KjDz|BD&_FJ}BdF}@}KpBSGG|1W0zKQYgT%3pu#&nxov&O75XXZ$|= zKlO+4|HLhg14I5_%;f)xS%1sdDewIL*WO;WCjU?U;qU$D8{d9O^N`#v2j+V8JS}e8 zEVuu={mk0DCm93wf_46t+ z^=`)wP4nuqTsJKB+nPtEK3~@FD=SR%4aswh{f}(k;k3duA8z8v|GocNKd^C3I{t6- z1FJ`+=c6Q3Z@745y1uL*ShU$D$^MKPl=^+ye81|!sV`VHC|y3=-Z(tn{-{yu@f$N{ zOtSs#@z3TfHkYS1^|V(Ovd|HVxHpO}0({6Des|1|yyO%1{S6XSc~|HX{|CnjGH|4&?7JSO;m;!P_n zga4=PbuL^O{6F!2d+rtdKk*LRY#aPP@lFe;1piO#o6&9a-Io6+o?KZJ{6F!un$qC^ ziD#I9hyN#@THTlbC+7U%|B3P4sQ)X*55xZx%EWNe^c=9##;T~t!BOE z%df|z`t%X!kY8o~pO$C-0{<^&{68^1 z%)B=qOt|=y2NM2d-G0W0d0_bc-p>5#1=aT@ynpw-&TN0e+K5~&Nd$WKXI4+{uTdE%>3&k=KqQLeKr1{nEXEcKQZ&6_JEdMWN{J)t0z57+p954JoY7mhBiLZ$NCmv`15dNQ* z$M3`ciy8k<9DF_V|HSks|Ic}DpZ_PGGN-TpubA`OIP4Pd53f~qu`}y`uIr+NubzFO zGuy-e)B4~q{`E^gKlqP7UALdRt)46XpZfP~)foIgao*}nPU$(TegEkTCwAt|#92;Qxtv-sAs?nJ+(e!Lfck;2m~5#+m2W&hHJ2{J)s-|6*>g-OrcjdV7A}z6l?F&_2%G->q*f z?R~g*dGPth+422T!FK&@zaPi{yXMU0eR+V!vtM1*Yc)56@5k}``4wCBnu8O3KN$Z{ z%<;kh+v>_|ga60-1Ith7J!JB=!S~~R0sfzu_W}5SVy;j8zw=+~^Z)Sa@c+d4Tljxs z@}ltn#MD>C{}WT65&uuzWA$k9|HS!itAqb1?lwOQ|4)psWA&??=a?U8`4-Nz?E1I- z3up4>EFZ&p!dCWq@#RKmd?EZl?Jtb~CuaNjf8s9l`SAb5+}{IFs7x6DPwn_i_#()Vf;Vc5Ay%S^8cJI z|8K89yzBj^Y~N(Q*W1opE^W#^_q*4fXYSAv{6F1)bCR3^K+cJKJovwKlqXOe`4y_;{S;o&40xI6LUQ9 z|6<1f6LWpqznvKm{-4HA9^cuGze)I^<-d03`nSL5&fFj4uKblV?FSc~moWaH*3b3_ zUV5f)A2z?q8Gp>`V>)wx;Qwj-+#mRVV(t&~Z~S_J@&9yv!T5hMo8RL+$$U`rf1L3% z%@1;BdGm)7w&$%gG;kxzY_mXO#N~EKk-yMU*!Ke z+x28VlCN*FjTiq<>+iJBgZO{qnhE%JJ37~PhkEqR)KjwK3hySN`^8Rf73FH6ic+!slCmwC@@A3b{MRSUR|0l-x!~YYL--Q1sChrda zFJ|)p#N_Ma|B1(1ULO9RnD4{*e=+0##f<+a=KC`KpP2Xm_(xvKZ5_KpSZ$&3iAKN zmD5KC|4&>yZDjEO#N;>P|B2hCj|u)?%=mxe)@gn9f5qej;s1%be&=s_k#p6=KL1b8 zr!w;ass9@@{+~XNRE;kP{$I@0|NZ;l`+UFZ34Q*bnEv>GG2{P<>5u;>CclXKzv8h| z3WNVA#_z-b6O*rq|0gET5dSY`{68`KkN+p8KmMN>KNA0Mlhdyb{vVA0C+7SQ|@j*-SdLFjgd;dp~nf(0So;)bwY3Cf`%=`uZpT^JcEAjutJu}DTist+{ug~M-EKk_x zU!2F<^AP_}?VaX#)6arzbh%(=Ociy&Vp55T!UwAt{;E@Z@O_=;Y^~Vn+|1W0p|HLeh|EKfQV)=mhe`5K6 zx_|imO#Yvk{6G9ZT`%Lz-@*SA<1gX=#f<-_>r?)pxVUD++!>Et-rsKiU+(%Vobmtc z_iE0~6$66*r}=#4|A{v(+9>4zi3b*M9Q;4=(29Y)AIOVG)C>v!pXM9O>NW}fpSZk! z)8PM!sSk|*C#F6y{-0R>pIG^S&TIU?nDPI_4@~}F%=mv|#)tnGGyY%9x4iRsvVQzOZI66H{J)s-|HNFs_i=s0VEjKZ^^d9l8#DEP#q$4R#{Y}?_D?_b?a?3qPvh%o9~A2U#*F_b z=6=Qh6O*Th|0gEj5C2b0JzxAkah>^o_OfHzKWnTs8E6`+nJc zzHB|>ELV<5eZMT1j?UDF9+T!dR*y>Ct1|v%b7fi&x}_>T{#pMo>-XVH#n*F|v-y8n z&ia2a`F|@OC=U65_+jM#iShmL|6<1fiy8lK`}g|%Klf=)XSBx)(|0gC75C2cx)?A<4=Bgk1 z`dI&^Pw(%{`rpm^wWm!8{-3yLw;h82C*EVH9fJR-?d`I3N$~%~+s>O4 z{6BHG<-zqHxQ~x-K~r<^|I|Lq&M*0YV)6^||HR#m&B6Z@<45BEiSzZf!T;0v$oIql z6E~R8hW{tV$HV`N8UHV4{68^1->Pvttp0UbQSkl9@5BF#8UIgQ)?#@t_iX1}Zu^h_ z=j&^23I3n@*SEC>|4&@k-dF!uO#UJMpP2E_e|nKK^>nHKt9JQ+Vtl_7mMmQT*3N}J z`3;`y!S{Ro#hFd0$-lvkWv#BEY;eN08t|0~Xo$ZT!EO@&Cl+1K|I~ zjQ_`X7W_Ya1pGg>%l{KkxAo)y#f<+a=KJ+wlV0c_pYg+so_A(`e$+nCIWs?s|EJ~I z9{yj<_v znvnk|#&5&_6U+aL**;4q?f8FcpJKiY{-5)L#^C>nCz{WO|0iaC75`7i2gd&sJQ`piP=8>pLn{>m*W5F{NOj?|B3ON3br`knfj79)|}@&)%+m*KlP^_|1W0z zKQYG#|4%&2&OiR2SpJ{JNB$W8pBUe7ht{*4yUiDEoOY%&^`r6sbbhEGjsGX+{Nw-q zE`Lj3y>mOCyS#9kx084Ghj&kPCJzt)PyKnnj{hen9{~SP%=6?s4JY~XF#eymzootZ z#s3pexA(>Pe`218Z`S?9_ov-_@LR?o*UxMGKOGPGe`4y#;{S=u%_qkH6Z3q>{}XqZ z4~hRL=6=Kf6U+Y-PqXI*{-4G>)t)DBzj=W7=l(cj{U17Wf8hVc%j5sWjQ=O*d4T`- z)h5>m|BvH4c#kE$KRjZ2@cYQWX}Embgb&?gQSYEFmIvRD`ZD-`V*2C%iKpA&NBqAN zPP{Jof7Hjt|EnmuF8F`s>*4>2ssFiR%8cHJ?z}eS{o(WA|B3NO@c+d4J@|hy5!7$5PzQ4I<2 zvSXby+yC;?8fW(B{MV|S@yD7=DxJwQdu;b|XY#`K`E6;!YyGV_;Y+KE62|}2`0$nR z|HSR)n_ars$lmU{YlH8HPlW#`#vj7}i}}OGq0WrQ@>6u%_bFNpuA@l!t)|4)pchyN$WXU6{%300_|6<1f z6XWmU|HW+ni!*tD({Fs)nfkp)H@x7yrTKt2uXrY5^J$#%$L4lC=HumjpLpv-&YbU6 zo%cJB+q%~LmAjoMEv&M7+jk_qOYcf&{{H;3=T>L_{ylleP0rjO>rMP!!aa9i?@S(` zy~|11d?si4e|jFl_y*TFQ-p=y~|Id%Vwd4Oe zukrt4w)`v~AHJErZ*;~-!~fIu67nAl4qBz_5k9l@2hRAQUsmtoJb9^IFHJi-bH40- zvNPw?@@bs8zU+DH%=Yd5`6}JN_<#03K4E*ld4HZy_PlcD`DD)@XP$rdJaNX?wtP@$ z{66!2oyS{#D*m7LAKw=LFJ}BdG570^=KqNs?0vfVYtGc89Cq`Q&eT`4>(iOPUv|AY z^Y_cHALo`?1;PK*`kQ8q!f*0+{2cs0wU>5VeJb<+#Q1yWb2-=LM+W~-?Pc9tkXO1= z=eN|}H}2K+m)pfGZ}m)_S>DdCb8Sz^_q$E&tI6|w;apCP4}|}h@{V0%{2=_lnDPI_ za$ngJS z#{Uz`|BKni@7t$7u3aAq+x6qj_j~+5Ef3@WiTV8o{-2o7m-v5Te!qhM7c>5!nD68G ze`5OM|B3m0i2o<%_b2#&I-W58pP1h>;{S=6|G@tfH=2)v|L45M{}apq6U+Y-lfP%z zvoFu}ga4=YO7lO-{}VS)Eeif$%=mv|d{OHE#*F_bZn5iy{6BHC<@ee9`)*zT++XDX ziOKV${;#-ULZAN^Gyb2RU$mPG)veDP_2Wn6@c*1G?}z+9F+KwRpLmS<0{DO8Lh}jm z|HP~x|4)n`LH*yD@&Cls>&E{Rv;4Yck8~fq_cg)agP*$KacB1Tl7UYpyzfcRI^#p) z|7m&p zgWrSy7c>5!n0))6y*Vb~LoY3I=J#Xxf7<_0Pr&>?G2buOYpO{2?|-j!W`5(TtE-*y zmGJ+xy!^kIkAJ1X+wuSQ`DIhW_B3d|LcJG4r$df8tp- zzk&ZJo^A6L7tK7td5+Cz;Qy(8s|5|g{}V5;-!tR?iRJ%^@mcZz#9W{Ff7(Cl4dDNY zIUo3cV*I$_w;t`shx5DbfydA8(#Nw_o`aXZ%Y1Kb=25 zFP!x8@qWHx{6Ad}vu%C~|4%&AKCj^ai5WlsU(EP_Vm?3M|A|9>r1^j12~$df|0f=A zejfgxn9l>`|A}kN_apyLOuioepSaon{^9?L$txrOFJ|)p#Q012e`5R+{6Fz9%h$sH z)A1T@`F!|)YUlGU{$I@af9j9lhyN$W@5BESH+K)qy*U3@3FH6ieDZsmOZL7nVf;Vc zKTTH8m-@frhRz|m^LD+&8D9$jPuCZ0-!GkOnuq09o^hFTan&Zl|I_tbS7knd`F}Cv z|A{LqHw^xt=4(sK`s)9R*Dc&2_T z_csV|B3P8@c+d4f%t!7`s4qJ$%n`P)B0ijKXG^0u;BlR@mKNx z#9Xh`|BV^{PwSWe7c>4}%=mv|&KLflSpJ`w-?!oaiRJ&rjQ5jQ=NQ`D=H1&$+IBbNfC2`_B2cK_UN7{kvNShWtM5!82=9cPu$$FY4HEV_;)3Hf9CD@chvt?yZpbH z$^R4ce8K;V8UIhr^0zmBmDlr+?UxsP?c7wqN$%VM-#9bg8P(t9nhO zivK6Z|GW0He$M)TE#+z6UvpXNdwrW*47p6X3mb3etJ>J=T#Vj`zWPHGE{o&E6kD2uizs=vw<}21` z^8d1Ve%ZXgtlydS8#^k?6CWqbS>G?qS>LC%`hVwrW%IxO|LTM8aM-b{C+u3t4S8*$wvn_sl(=XVx{F55I@=oW{1?;CFU+?rCn#E#0i2$zLS@PvgTE z#s3qNzli@Q#^1#Miy8mV*{-L9Hra9Ywx9R;e$?;9{}Xe4?za8X)fYAw1)mNdZ~1B4 zIX7Bf-Y2&%ac;JHzOR3@#FwZ2q|Fz5JN)G2ZJqJ!$p6#!IN$hxV)=hD?Ki$T_bmz=Rfwi-uz(UEa>|+Wy%)6UP73 z{xH9a|0ia?68}$(UxfcB#(%;86Ei;iKQZ-N@c+cjN8$g)jQ=NQ{+0T_V*DQacf>Uz z|4;3mHh+fyC&oX-|BD&_PmI4q{$I@af6nFuU0ZUaGxasP+i!5jf5ZP%fARzI|HSx3 z|K4wT!Y3Vjoip>z_@WUb%=mvX*4=t zd3*=_Kk-EKTk!wH2w0xK^HUBSW{68_zqd}vN_wmaA)BeEte`4O>lK&^>{RH`c zV%|^V|B3OB@&ClE5C2b09x48xnClz=Pb~jW%=J6*t^>Ut#{W}0_b>jRn0nOse`3xb z{-2ohhyN#LJotZgANToxj2Hj!we7DD{vZ2?{}(gGpX2}C zvd8k^|M5J<|9kO!%Y*+%e%j!*X7zq~>2<;P8^6f%ip~EM1b!RhySPJJH?Kl)i>*X>gsEQ&j(xm zGiQ#U)kky2$HV_qfBZ%KznHiG?ZAW&eQ%S5&#vFtnf2lSX*@9gpLo3ae)xa7K6=dO z!~YX={o((`jQ=O*d4~Td?y~*I{}VI*qki%As+eyY_JuP(*?Sj!>MZ|H*Z({_-xW0< ztrE|->%n{#XMC=6>)uWH(G_nwlh?OaeDO^$`S$7mbjR}%w^%*0XT1Lu z^8wA5a>gIS|I_&J{qX<9T>tog;=K8O_LzdN_u_d)aLoZBo92mepUv)$@n;{S>HK8gP)=KCi8pSX2; zN$~%~^%FzBnYUMWZ=Snp*pGdCupR$??ix;>V#4M}I?Mml{=oQuG2{PEQpVyK*eu)1k=KDMT zpP29e=9hNIjQ^+g@%uOYKQX?8?Pb@c+d1Q_6z> zCuVu-|BBh3onPOdu~Yi$|Ej%Xa-rpYp6&hR|EV3u|I_u34~YLKZnS#8_4}%=mv|{6qXdafSK1 z_<#SNdTsFkVEjKZ_c#7u%=mxeiV4Gm|0k}VJTmxyV($MZ%>NVPQ{w-{jQ=Ml9~A$u zpY8X(=KsZv|0m}8i2o<%d5ixi#=ojR@5_XbS|^uRJO1BpcYepY)AG({9Pzz~`}{v0 zFYbrUKVHY%$w&M0y7ipNN5lWq`sM${jQ=ahv&a_q|0m{nG~Bgy!uWrBzHxoy|B1=J z#s3pCKKws%kL|yGK5)hlfAqthoLOJfid~%9-@QNFEwAS<*SGz>=w};W{`S4|{(aug zXW^0Gcc#7q{-5RtrrCVN-*WqVJM$Hf-t|N0$@YEghU1qx&$0Q-bEY2TJlB4&dgywG zIJ5kA4;|`EJ&FA3hdXoqjyPTNt7dlgjZ^XussPVx3}=2zc$^Qq3{>)!T@(-OY!z|)>3&T zKV47wOAk)E)UU4w^K0<`bp4T!hyN$8uHH2Gf4X0&$BX|LGyb2rreed~gq7FlHGf-P zyiV?et5!H~RIowr!e89rOdjCO<8E}O{xA7|n(r;Kygz$?;H>;V%?B#~PfXq)E{&M_ zzWiHU-L!e||HSx!_jIW3PC&q8W|BIRYznJm=V#fay*LDmH{-2oqH1hw% z^8Ymd3*-OA?f8FU`F~>he=*zpEALOc72_*X|5wcN_l=#d*8pE@#|Lp{u5`~$^X;y2`2w9=CzObJmF<~|HqlUz`rc|BH>w+zjSV~ z=N0~+*4J#$;}7P4<dUp2rrcUGChj!52#4KmGmpvZY z^<|G=w%%}4!T-)f%xaoUt&t$6?8*|q8 zqdsrkp7npS{$H8-b8-JHSDG&uw^J{b{J*8kN`vo5ei{Cs7(WjGPmG_1|0l+m!v7QF zLy`aY(Ag!y|HJRX|BD&_FJ}BdG26rc6XQqW|A|>Y{$I?uO+R?`CXW<{{5aazI^-Z{ ze7#whALvYb!>0%O@{AAvFCIVne=+0#iP>NLKW!hz{}Z!4^8aE!Z=)ah_8aP(a<6vo z>s(z`o2%OE`_4seZMkK?*vEO?ym`5mckS)G$D&2K%Qx7^*T3gB+vNV2c~gV` zr|s9aRtNu2JioCi_c75XiiQCLa!~YXgzZ(BfO#UPOpSZTFEY$xM z*HxDX|4-+u!k%~de`4y9BPO#b7)zS_#y$MM1c)B0fizdK8dg8x@%`Gfd>F&}Z>Jm;2{ zmfV~7&2=U}F}@$UK4Zq0jX8V2XL)Q@>H~LHr_Y!6hSU%2Y)*YZe&0gvO%!&$~IlN$s*wALQPDKkLl;@&DAH`GC95dd8Xe5BB-lw_k4a zYwzyzv~z{M@52An_*fqQFJ}BdG4CJn|HR~1eRtU7zCC_lyH)jL3169i)Vb2;S3aBn zh;xS=5<)H2ZCev;03T&-n5G#N(|#1pc3x^N0T@uD1C#{6BHqg1X@UiOD0x z{}VHQ{J)s-|HRB6D=jQpLmYd`^Engljn#3Cni4$|4&SQ zAO4@7KXvB6;QxuqufqRRfBYBxKkYw^|0l)|#Qzh^{}Xfl;{S=M=lbkEKXs=53;y3R zC*K-;=V|8G9&yHL-p=`*d+DjpTp##<>d*7%Uw5DE?L6P^f951-o~OTh`$T7+mp}OY zgoMX$m@@vK#!G%E`F}Cv|HX{|7c>5!nC;>J#f<+a=K8_^6LbCG|A~42;Qxv7d8z*^ z=6c2d6LWpy|A{$X_$)9{*2FUcrJ77WTe7_4?rV!5`EuaBjEvCBOf4Ztv-@_xXOE z^ZWciG5JmSfAz;K5B?uMkiCEDEqbrd-y`46-p?d#?{A#B|196Z8Gi`>Ps?-v;s1%b zU-19L_$&B-G2{QmjQ3I9)wpM?J>p1Y{e{}a#Ns?Yxu<0Ik!#f<+a#^3q( z)au?nEiZBZLA&>vpT;NuPt5Z8e`0(+{J)s- z|HSmi|BLy$0|z*>eXIZG%=+$~vA!Qq`G30J{6Fz@yFLmF{^dO1@(>qa_M!6vJHPmUx2-tzwVd`&A}bDq4U1%Jr7 zYx`DvU-*(U`EmGv8V@{R<F#533A|A{&N_e>z_<{-1b;oj?3P@l@MC{68`G%aEhDS*7O*_lLcob{=n^-|TtoJZ^Sj z$p2G+-Y?_-iSzcp9sf_v`)~X|aku@R$oykx-glZ$oG|{M#+Nt$3;$0{JvaP6ap$z* z!T%F?Oc`pv-4`px)F;FL6Sta=g#RbTN5cQp@x@oN>(krIri`|F?Ke4-mxceQ{^WsC z|5sdY^?Jzv6ElC0|EKN2_NV#fay zQ?C^NPve34&)Iw>{J)fU>=GAEq#p5aol7QLy)?`JQ#-y8{-3yR>X_jFIh!Ad{}(g) ze`5K6x?f=YKQaCW{-1cPeO|!-6O$K(|0kX_t18t074!Lx`oCg+e}Vt!+qcgn_36Lb9V|HSx%4Q>DE-oWy>sfUXn_|?@PIm`c3fBAo6{674@nDPI_%&+19#f<+a zo^02DL;Kp!lPu2?|4;4w-WLBa=C6ltkk@!w|C>*4nD8f?Zj}GJ`r6?4;fF1KaN~sW z|I|+29R6R-_ccK_r5X}o-Y#Q%#K|4)oRhyNEd{-2mU zv7^2$_Wgr*`(vpyzjv*8vfTT__Wi+``5*g!;f(+H(sye6*`B9&uB=P=%0nBRSswpS z*E9arvcETbJL6w`RjV`kYxsZaKi=wzUV7q%%I|QNK9K_m98- zA6FjZjDL#%r{lx%#{Y}CVVmRp_~PGP*7_4?>H{}C@Do4Z9G~JVk9X$y;s5D+X8FrE zJJIhCmf!s2ey0B^kDui2e7^Ydx|5x$f4%>yr#N>`?eqV%em)=I|A}ku?=SwJn7?oM zf8s*(qwxR4_$&B-V)DBVeXpPK>%RZsS>BHSxBYK_=8Rv2|EKF4#{UzuJpP}!se5Gb z|HRGReffVeH*{bX}-6xVsP;P#G@Pf>i=qfu)y-T zsD&w(|0l+0#03)L|FJHu54QIo&g64hK0?Cw{v=`iKdp~^K>R;3ei8m(%=mx(JS6yk zVtgn3KQVc2)c=hc|4)pMhW{sKdGi0n^8dv6U-*Aw`s4q_jQ^^@qv-6H~7j z|4;MrF#ey;H;n%$=J|mCCmv_@hw=ZkJ{bQ`j9-ZV7c>5!n0!V2znJm=G#<_${-2oh zLH%F#hw=Z!^vC~;8UHV4{6BH0`Ih*9;<1(=i2o;M{rG>{U)GQRCzk&gGyb2JCyx;S zPh4rfC;p$9_2d7=jQqR-De5o z|EYgv)26}y6IV44%$;-C7v7)sP2BxU=Z=Pf!T-~E@dxq$#I^SP!~YYLPxz(zf8siO zUgH0W$wMXoPfT8F>`(NR4NEv*n&ttP7p1;j*8j`;b+zA;*O&F%YRXf;ufD1z8PBA$ z)W;ZKocbCKW$E(S@npA`_0RsVob~A%GQMGbVLIO0f^@v)nR>Zp1!I!^&-#8@&gKs` zWc*GqPNHKWu0%lduUdcU<5sjpL0p87n^ z9~l3yaavjM|7xo1g8vsY{-3igkN+1l{+}2>5dZI( zJxYWB2jl;V$q&T;6Vs0WC#K#k{-3z3rYiVzeeKWE!T!T%F4*=|Ab|HKm} zjt%~wc&;6P^8ds$s!ButpSarmRQx}&{6BG1MRD-|V#fayb3F0?#2jz(|HShDv_I7q zCBgp_kEtmR^?$|1^<_Eg|BCVdsQ)XL|0f>T&=l(b#(eOs#ooWCq0j$QJBJ^o+J_)r+!FjhzMtd&iTQqx|EK=U58?mCjQ^+c(2oBXGyY%9_ zKXH%EN0I+09&i2a-_FzLHw6Dr?NhBjFaDpH`7QiEG3zJ)PfWfS{$I@ae`5ST{6BHK z)lb9!6SIHh|HX{|CuaWEeqZS4A3o>t<<1;`{6F=F@&97R|BLy$E3Ziy|4;4sd-#81 z{GZ+a{99-8-3 zfARA8e=+0#iSb47|6<1f6O*Th{}(gLX5f=K8|_Q#*bf{-3zbo=1hhJH?s2KKwtmci8(M{68`8kMaM+?N*Nk|4+>PI{shG z_{J)s-|HSx7_X=y_YeM`nEMC+Pt5u) z-=f#vDF^=!f64MMobkiR|5Jb1@-w`hd@{?|aBeZb$nrOw@saTVUi!}R;Qzt+f8t4t zns~qGOg&V~|8SnYmHobEyAtP_&@?~Iev5RkIy;n!OfiMzthHp6aLY{fzJ40_-zcNe17r7+RpO-%rWcBqqP0S|BHF%uX5g>=k-IkeYHyG zcar&O-;DoHKU@A`>;0cNlMng*+5dE&xouPM|Fr&Di<|M8R*CWd?!D@7&hr1%PTm~; zU(DAo`?Ifq`jTdQU-)9eLymsVnS8$)Yd`Ib?{~~;PdMZI-8Asggx@{yL1*eSj~RWR zbEh2-{6CF{>k0oaX8b>~{68`GkNH^M&h>%+r*^hy|8`dWUp-H_AMpRg+)wy_;x;=T z_;yiV6EB=b}oW&i%|I_+rZPOO~KQZ-{@&Cj#mbRMDcD#?D zc6;CG%=yCq)BaMg_xrOC^y3RZvv^-;^83c`v3tVLeZ2iDUH{ZqpYXkHoU85ckG-FE z=I__wk}aKU&0jdOWuh~FhrN$?#_zD_n=}4}J+GYGx3oMT^Z#@|;4k6-iSd`LK6t`b z@7tODG0X3CZkSkTc`9o;QxDAUua#O~o%wFhEPg*>{68JP>Iq|l|EJ?mz83zU+6SAj zga0QUWcgh9f9lWsJ^Vj$ z-`D)L+qHhiYvW1S*6%F;PyOZpiODa+{}c1R*Ou=Rx@4@{-3rt$=hyN$${;}il%<}ku{q3WJ{}(gR0z1FX9aBdI|4;4h=J(+^?BL1Ja(e{V@KQYVW|B3Nm@&Ck( z2mdc-{68^%ApV~iKM?;d2OHd58YusXV#DZr*`sQ@&Cm9{lfoiTJO5x|FJy& zU(EP_G2{QmjQsPx}Ys|B2~8$Wd>?D9s&pn_f9M-k&eYq$|I_itr+Q;SK2j>U>Pt5tn z{}VI6i~kq1eSUG~`r75gNeScs>3P8QLH=LN3049^u1*X+utK+uIEMj9Fp*Dm4`Vqe^Kza!xP5;^YPgH^cK$@;o~Kb6aP>9$Nhl+ z7xTtbyxBNdb?*|&%Pw?xV{lov${Q);! zaiZT(TpuOJp5)wNpU?6CyuUqf@&Cl+>%O+!2GCp2$#@DMJm7d?)jPF-6Dm`DNqtorx4^PKe zJ2cH7EZidH?0AM3r{}LAQ@<16D&D^=<5$J)HI=0a535dn%Pd!yr2S$1zx76z2mfzW zc}ej9#G@-pb0=MP%<8+|C=d04tE&3y|Ee8d4F69|z99ZzTW4AD|6u$-aeaM#@c+c* zpW*+Bw=_TQ&vzWU`iKKcgWosJe7lN&9O8`6g#V{@82?X9J|g~K%=mv|{IzqRSmxYZ zSrYs|ZJ*`w|HRZ+#s3p?KJfp<_><)SiRJ&rO#NSH%d4aQuNa@~z7zI!#t+2*(|F6w z2PXedymnh%ZtV~EavnW*T5is$ex9{pPVW2}dwM%e{a)g>YSPfWdP^8aGS{}ba&zV?TmeEXcA>eqI3CU24YzuF&;7x{l;@)OtHXM1Pr zFXR8Iy{o=4_nJL~%VKQZ-qssAgc z{xSaFU00Qad_oxi@1y&QL;fE=BK}{@_1^2y82%&*}8^|x0B|4+>OEBrq( z+sFSC7u)<6{@?mPyfyfL%-7-niJ6bU|5JY$|1W0zKaH1m{6BHK&8Ol2iJ3px@Xt^B z^6>T_J<-pWud%}XKdqnnI{ZH|^LzMzG2{P<@%QlmV#fc|_E{hPU(EP_V#bgE7c>4} z%=mv|ju-x)n7l*$KXIkKpTz$YlUIlT7c>5!7{3PpFJ}C|nDPI__&4}}G2{QmjQ{6s z{tW(K%=mv|{4x8tGkJ9OS=o8^{Knw_ssD^Qeg2;qe+~aHX8b=fz6<`J7#{}zPuy)j z2mW8o_Wj?_C*!mF00~?D0O#3ueDVKu{%6_z9R8me{|Nt2>xc3G#Q0tKe=+0#iRq93 zC!S=!6aHU6*9QMDX8b=feiZ&+%=mv|{3iUrnDPH&#{Y{M|4%IcPt5tl{}VHQ{68_{ z$Nv-K!{Gmk@n!J;#P~M&e=%Qq*f0I~;zxXT+WF4-Br`5K&zbg%es^xd_5!7+)Cw zPfUOOKe7BjF}{(#KkB`9()GdD!}qfHO9|Wir-Ut^!dd>G*2nda|EKlA_c2TtU)1tp61MypXZe3RpIi^-8~OFa{x@v% z-GuS~)SvT#|0gED75`6+uZjN`Gyb0#|L)SKK5)jrGoQ&B-)qBH-${7<9&b9&w!FWC z-~VgE&wc#LDqT-3Kj6nNIO| z{+;CrnQPaFy>Im61AjCAN6ys$zTnPfemL23&X?gzs;s1%rU&sFw<1^v^#ccVb&iuVR^~3__ za`Q*5KDaYJ4*s96AN(`?KQZqQ@&ClUzrgr}I;9c?tM` zI{w3q@&CkISbw{Iyg%!J@c+d4a`=B@)&CW@S)L#MpP2EG|0m}9!vE9$a{c1}#f<+KGyb0# z9})jg&jZGX|0m}DFgKxF&nw1@{}(gvV+TVX?mcM+Tzb1_T zr|sbf*ZZH1n6t{}YpUh5r|G#ii@}^7x2nY`dW|d0F^> z+MfKsnDPI_JfHCY#Es^o;s1$w9^n6p^Y(ng{}a!gSsDC4@$~6s!T%Gp{LfDx>HXm^ zCXaUJ`Lpv^1kEp zTCc{L?{DYdQR_^;?>C3lJI}V?L+{bp=sd&x?DJ1(_VY2^@`R7}ekw>Y=k=WWg% zGYfJve&3PshA(vHbv=;}{L#Y{-2&_ZI&O2|0iymZocjgCp+_e z-LUHv=TiH7fd8lUwR8*${-4GN36i zKXGYGU;dx^!?;3X>H+g_F@7NapBVp#{6DP^e~A1)F?s6b|HVxHpIH8%SpJ`wcKpAX z@&ClEAOBC>V7@5+pP2KF{}(g|4)oxivK6Z|HA(hGd}!3G1m|NU(DqHi7VSj zg!;eYs*aJt{}Z!){68_J z@c&}Q|BKn`)A{%qPks3t3176`8-9P$K6Cn;&g}mcx4h~1BmAc;-g0LA3m$sM*T?u* z-~2ac@*Qh`^KQZyoc*3N{qg@a-rBYyHvj*3Z|C}deaSx(o;UpiXY%{-|8)Gx@5BES z@J@?2LYp6(lxGev_`fgdDu5?VAA6HhG`e0dqF1x*KeqKXS zNizPd|Ch}l%=(AfJi~0BU3NU#<*CP+9KXzXviW{>BhuqrKQi_0>V^$T)>k`pvxKwl zjU&?Kv-Nee$N$?ndw#N<_5ZT|Ue+J19I<&a{)#Qq{VN}y?%#;gG#|0Re5&~PX7m2C zd4bt_pII)cFG|)|Sd*T=vWnCXtf;d0r-vQ8`n=mJg5QVlw``++9%DWi{-4_M|1NA# zdG}u)?d|w*_f8Q|HX{|C&uR@|4&R_9sZw~cI1 zV(QJ}|7m=c)qVb-c+)ETeVqA!;)1cQ!T%Fao73n2iDxcYko)VQdwBo3b7tnMezUuC zOLIf+pg-;A+*H-)|7kq!^`*i86O+$4cgZf^A3p!2ot?=$#Q)RwIp6qyV*Iv0<#t$o z_>W41KZoBoqJDel_LhcF|5xqs^3%5KZ@2tB^8d6x^7Qck#Q1>J|JCyNf=^D~)_J_u zU#9-A`uEiJ`F~>aB+361lQ)U~C+2>{|I_-(?>u42!h|0`d4V(i?f2o%_=55Mo@MGu z$L&om^$E|cOZ~qEt*QSvY5cgPKgajt_P2Xa+-ha;{aRYeg8wIOZMFKimj8Fn2Yvou zOTHlZe`5K6;`-?Y!T%FCo4(^^CVu{}%tx z$7|pB@&Cl+Bi-`QpL~4G2jKr{yfFS>%=mv|<}2|3#PrAi6Vs0WC#L=|{+}2hZ^rHq zJF|Zm9rjSdADs4}Gx>oNFL@y0bAETfGsolYd+&2*zOv(md!0Exr@nuWGxa`S`Q~nC z@(S_){P-B-|B1;DdwT4h-XAWTeTOskA`aVWwKKlhLkIRclixS$q*cyrZ~tGdbY^{b zF2CKm!~7dNR?f=*(|BO~KQZ;IESuVS@@(^=F1y*8{4V@I^>4BD%a4T0e~cC&pjI{}bagy*%<7U!L~* zhO3?P3mbCBPP)pO`mp5xX?eJ8pDVo`AMLOsf8&gQhX1Gj^8aGS|BD&_FJ}BdF@75P ze=+0#iSa@3|6<1fiy8kfX8b=fKH$RLf92!H=feNf@x?#E{}Z!4{J)s-|HSmi{}baI z;s3=<{-2oRhyN#L`yGQ*CjU>*Q~7@}{}b2R^9BD;%=|h2U(EP_&h~qD{68^1ApW12_2d7E zSwH@tnCBP%pLm@4cKCnJc7E{xbUkps@c*3cddL40b3F0?#Q3QAe`4|}@&Cm5h4_Cl zM1=J;E_Mem&}uMhcr zu;pJk<0qcp)Z~m0W%aY1@t>@|mNUNF*B90FzOl{q!S~~Nfd40Ey!d}HTfRramjB_5 zk7xNH3FH51`3ieJ;s1&8h4BBxj2Hh;%<;qjiy8k}8vGV_Pe8?li{}boUS0eu} zX8b=f`H1*`G2{PjQ4O@$-H*KWopipE%>wU2x~e&iGwVZ25sRKAOFM zcgEMV_w&y9eD?m{8NbZl?>o=frjhsm&aB_^fmUgMVapG4#wRnsAYt*sjC`qPuV9UijT@y;_AHQV)cj31vZw{EiQ=Wyq~>t&fUejomyt~c&S z{6BG4EBrrkoqb=#{}c0h1phB){J)sV|BD&_ zPt5mu{6De$Kj$_6pIH8%nDOKPiJPa43jUv%<468q%=mv|jyL{a%=mv|^5*dWVz%Sy z%=yFr)Ab4C|A{%@_>vK0KL2rk@c+adZ~Q;8 z&2t9-@BBNKhde$Q|IgX}p8WHWwGv)Zzm7A{r#s(XH(~t0czOIkF?pN#f6nGZk^dJn z{-2oqPW-=^@&Cm5P56Ie)&K2h^QA2RPuyibJ^6oP#)JPCGyb2mjSv4%Oujw-pP1(x z{$I>D-&c}fx!v;oifKFdFusDL%A9-5hsOU?fAZ<@|6<1f6H`wF|4)n$i2o-h?+^b^ zOrG1Le`|8CHJ`iXvKD82tqYd4IpaTlXK;rz`Dplmx}L~O#Q%#K|4+>P@2d63J2U@l zpI@9gKBpW#DPjCSUEdS!eAxHPgz^8>jt_|c7c>4}%=mv|d^r3+XY=v!|HSQ+#svRQ z%>9D@C+72&k+Ww@e$A`?zhXbL;fc{QkokKmDxwo$`AA!T5hM z5!xOwWx z9R8np?5v{T|B1=_#s3qx+V^ezKk)?1BYg9#ANzQi@5BGo{&D@j@y1bpyr$XpWS_^K zsjstb-LcMG|GV9JtY1$o|Ln!bIdlEv|LOW1Z}%(ypP0PBneQH-*Yl6-KY#xT&diVC z|9SiDn&AJ58z&V7|4%$NKO*>l;Z+s|;umpkYDGo9Pl_7Vf;Ta{vQ5c%#(Kgxig=q+a{dj%;#zH|8#!%yo~=R zrXBw;X8gaH@&CkSwm;J!{iSoceV(WOudWaLz8>@cV#faylV67a7xN$2yCkpAEBG#Z zz0=S5EngJ>I|4%%se7#)#Z&&2S!;9C-U3B&h&Ks1k8~i`b{|>Zz#8+bf11x^fAIgD*W~}HfBl;Jzhe9y+@YBHx0rk}{6DRayfFMfF~=AG zPh8)zc@F=tpNEG0znIDY69>P`{68^%7XF`@_2d7E<^PFU-tsAYys+h0IOA{O|EWLu zcldu|{5t%l^=1 z?PEKJ2mepZ_VE8=#{Y{M|1W0zKQYG(|1W0zznJm=Vt(h<7o9mCiynI^;k$2tIbo~s zmax@-bH-n`_rnPve!#2F!4Eb6Psan^YSwGsP9EOG<6iUo1^#fq*PXe3@&9x`HMeh` zJLHi!@_HZ4^@jf!GyY%9-<!`?|R3)pD_NP zjwj>8{}Xe6;s1&8ZSnuapIH8%m^?rHKQVqE`F}Cv|A~3tk^dJn z{-0R+f8vUYjcoR%KQFGXEcLUp{$Dmfuc0jU_x>yIt}w0tT9NVns*0Ka>EC{K`KIB!K4X@@&Hu~#fK|n*&skfR`hVH_zuEf0_-gU>gx?l(RZYtHV{v<3 zb=ppSR{XyooK@ME?`O;7|A}krDs!jLJ$Cic2UYbPv(L*t^dI=fF$tf0SU)$^R^~=- z)X(@|MZHI?{=>Z$AzzSuH2lBI|JvsV;>Y3tiSg&C|0^ah4gc@m&C7!ih#!alCvIq} z4f%iK?z)PV#bI6C&sTN|4%$&TzAO-6K^$lUhx0K ztqW!c|4-aJZ)WiS#B(Nfh5SE_x4X&e=hg1&>z`@c$Ny9R*-cHs{}YdGYs!tkV#n1D zv&w?s2cPn%9h_U+n}YwR_LjEB;Qxs`S{sA^CuVv4KXGeoYwnXYWN(p(y-R8q z5k&1xYlb3-k*YnD5Cl0HsETT}RQV~jca$zw)c^CkkN4-?_w&F0Ki5Ck<#Jxv{p|gH z?$`7FOnEWk=lA}jv;04wzxjWCZ+^j-Z>oLYckn~cCyf86<(K~#GyY%9_~{68^%B>tax zn!W$1>eIthW>`Jn!u8&c--iFE;Ta$QPfR=hU(EP_V*D8VKk-CcU;IBYKA`>WjIU(R z`U%_bTR;979{*3rBmN%#U(EP_V)DcA|6<1f6Ei*hznJa!yU(AzKKs7Ud4{b&{-2g# z{-0R>Uk_WoT+9E98UIg=UxWXr`BSeG|4&Tb*@au(<-?bouY&)l@$s4P|HShD#Iwu? z#Q)RuW`67csU6=1|1W0zKMju`MgCvR_4}%=mvX%Vixm$ZBjXXpyhPv+K3> zFFNO2KB4tLI^*wI|D-d1BL1J2kL#E9Z+bgy`6tc{Kck|*50C#h@7TW1)N4I$)eg?o zN51--?VQP%!~fI%X}5ed{68`Idia0hG3MXl|A|>1{68`K8~;xn^8U>K)A7Ld6#q}m z_|t!|X~Ot_YUg^6|0gCN5&ut2JN};-KM?;4}%+J05 z`f9BYKA+Y9b7p+}Kefa7e`5K6G2{P6O*slw(Qs5&h|OF^+{*8FaDpFkK+^n zFJ|*6oO!;m{)E*!|KZZr4>)uEJ7B_cXZ9EQf4Y9KeewUqzrp>{^CEby4smM#^MoICT#s%&TPNSt1fY#Xxr<~Eid%>;qQIf zdA_&9Rv)Z~IsUge!?)i!^I7NRpXl6f*Mnyo7C4Ww>qY(aBb+%um+Uvsx!lfw{6Fn4 z@?G)&#N@l;|B1;n!v7POP8b~gKWFnh@c+d4H28nopVYs^{}bcG;Qxu~|Hc0kS6V(5 z{+}5C4*yS_H+Deq|HShD#Q1!6emy2G=;+S>)A2)nOY;B3jF11P;{(S36Ei;kpO|`? z_8(Lag*C#F9V|4)pshyNEd{+}3s3I9*b_Q3xWx0_Fc|0f<}zK!{7kBae?@c&}Q z{}ba6*zk{t@p1SkX8zXRDwh8z=J^T#PfT8;4e!kJ6aJst@jLPV#Eg&sC+;49e`oTK zZ2KgP|EJ-}^T+=a7g+v1{-3zgo>%by#C(s3|0iy<--q~rG28Mx^ZbVYr*@e9KQVb% zU(EP_V$KKrKQYG({-2orgZ~%vkeL(Obv&{^@&97R z{}UHj9wh!>%=mv|{4)H%m@S{l89&T?i-ht2v^@A<_HNnx!T*aH|4-KsmJk0= z%<|#?iJ2e%pP1#t{}VGl{-2oZ8~&e|>kiy#X#f<;w*W30XA^%T|e}Vs} z;qf!b|BD&_Pb~jWOnxB#pR?sJ;s1#XEZ+(LPfWfb{-5TbXX}gqCuaKie=+0#>G_cB zE&iXF{L)jG{I^}tvutnj|HSMs{68_<8~-n6{68_n_`Gfd>V)9Y(|HS0E;s3>q|EJ}}U&H?slTV2Mr{Q`3i2o;^JiR;rPt5N@{J)s- z|HS-c|S#$ROqpRRu} z{-2oqQvAP|@&Cl+nHG#XB;j7KAL`s@*Dw4(4c}_{ZTNp;o~It^f0Q%V!==w3?ach~ z|8)KCwC_*w|HSM+{68_r2l;|0!tA{7s`w#p-9Z&Q>;Qxv7Rp(Wo?Z@9(dw$ttn{yJz|I_i! z`+EF8G3OKhpBO)w{6BHYn1R9n6XS=F|0gCd3ja@xzw_BYQhw+67kWGS*nhhBqJ;7P zv_7=s|B1=t#{U!J`)#>!QNkz9z0A4s+xoxSzRl(X;{S=cf8zhejQ^+oMLYhVxN7W> z;Qu+>^Em#WnCEr;KQX@-@c+bo&-3VA*E&;gwc>&$&eT`M|I_g_rgd2G|HRFWgK{t4 zbAz{6H4X{>pPpyRY6sZ&AWJ*M)X&BL)BCaV%58%Gr}t<0e)xZbpIj00|K$IPtIM~| zJu&{Cj#&dA>3Hdv^E;^ryrAM<=h2o2i2tYlEAs#F|HK1EZ4vxGz3&}S*6sg^hn8D? zQ1k!v{%=TG|KR_L$t$$}32%q3|H8Shdb?2nSHsuWY#;Lf#MB4I{}U_!&)Iw)-j(Wo zDgGq>pIH81%=mv|>N`{aH)i}lG5#6(e`5K6V*E1vKQZSE`F~=@$N$sv!uWq;#<%)b z&WvyMubk!oX?o=A;s1#l9{(?9{68_%$N!7@o%=q|!VwNBOPt5Y-|A`qN|1aiec6+Hq#~;I6eYJ$G z{#wG%4}B$J{69^P;{*Rs%<+T&Cmv?`cKCnd;f(`x_QMhKjQq{}(g6_;<_%vbsKdmq0yfLYG2Pj>vQub1WG0cn0?mb1&3<*e_Q<)Wh0zoWiu z>;q-<|FS+{w*GIHsn?oJuQHt<`D}4Jz8?PHgo8_i|A*g%|0ia6{J&#olm-6}9}533 zX7c|ud_`4h?$XCkbH;bW|NGgsCBgs0m&57XMDg1PF~>5@_%*5F$v@UX?kIP=KsZv z|0iy!stf*~xUsrE_a@ zI8!fp*=9XlQ&yGxqUK<4A3tVn@c%Tu$@}gd{6F#3{r3(2pLo9=#{~aR`(t*e)w?tQ zPwjKer^EjfSAN)V<4;cSX+}79>{6BGfb4&35#4Ys=!T*aH|IgWcK>R;( zYg4!XCmvr{6Z}6h#{>C)V)7*M|Fpa?{-0R>U(EP_VvcA0znJm=G=1_A@&97R|I_eH zKR*9BzwrOwsObv+ALkGLpIH8%nDxW|yL&@d@c+ivR0aP}+|*c}d*=1`y&cB?)A$wb zBZL1ZE+3Pho4D6I-p=nk{6C)gLp@-7Ux)uEuADk7_8F|6~6Z3uRg}-~P%bcy? z`|mLjLAB_Je=KTWx-&0E-4gMeXG4TJy^8dv2AK?Fq`Mr++7c>5! znBmF))BNyR@c*=Y^grPL#f<+a#(yCHPmJG&|0m}C0sddi+3y^tb-FV59`%346RrRLh23uR;qmdv|I_&L z|6+b-(aqk@@WXEYWx_{4bdxjlTesmC3HNzzsWblD!Jplj@WbEh;a2mp@c%UbHuL@P z|HSxO_zv$@qqs) zX8+`0cbV@G^5yQocaby0PhNLv!Y@C6i8J|*N4$G+!e9UUBIn6Ay+yrJ#{bj)$8W{| z6OWl$68t|g*DL%#G5LS^e`0(;{68^yGWdVuP+!XYKQZ;C9$Im>bG^O4o&Mxm&J8wy z{67uP^&9_B%>7`q|D5j3`CByNH0MU!{xc_@;w=A9<8wTd|0l+0!T%F8JpP{;p9cRg zX8b=f=NtZ?82=3aPt5fL|4-av^@s5P#H>I5pP0PFtv5Z`nf`bDzkA2tAACR<|4+>R zIc4G8uJ4au5qv-Sf6jKj!vC`juaNi0^=sw!J9e4V6MR3eulRrBCYwI~pY_Rh=l$9A z@&Cl+L*W03*&q0SG2{P*LQZ^QP>y8XX7=C7Im=WP1}|4+>Rvi`HKZ+>#0`+U~Fmaye-IETCf^ZzvbSi3*s z|B3PY@c+d4Q}};k`F}Cv|A`ANuMPiCTx@x6_FJ}BdG4)@UPukWQ9}xdf+kZ#9zTy9gske^*C+2*^{}Xe5 z;s3>4-L$zg!%shDGv`j*KJ(UXlCt@KI)3mos}_H?TGI>bm;Z$`{-gDeJL5m%|7m>c z*W&+)@zv_5f8@jC10M3idkHVu?`>y%zUR#U)BIulKQZ}z_N6~6v#&jlOr_jcH( z?acA?$|mWp7{!qS_ZC+=RCyQ}m@=NWrh{{I6@65gTnYG?eu zDNkSFJi+E~{aen=-}=iEw)$H=Z2n&Vzn$kyexK!o^sxD^)hC|5TE{#7-&L3W#F>1> zukSb};e*y6?uo3Ir6YpT-TYjW7{t^D4?q@LmpBUc+ z|1W0zKQaCD_D%y+h?zeB#B4unZxu5=8^2AA z&xZdOvkmV|z7PJN+F|@ZF@6pHpSU_K&;HIFANYT2XMD@Y9HZ?`exUhY&gJH(*!FkE z_p|+zu=$(L&C`q7zs@aIZ}ZUFzc};!cWJ@KgjWvy(wX-G8_)e-yOsw&^YmWM)E~hA z)ACnN;dmJ2%=)+fIM0WNfBT~%XMD~B_peO&pL;Yo^Zw)foyR!Szm5N=<-y;>{}ba| z;s3>q{}(g~BhyN$0J|F&{vn>z)pP1#v z{}bcO;{S>9zxthcxzA7jpXM+BPt5U+|0m{r!~YYrz48CV9DjEFI5WQa;R)ma>H5L> zVt+d`JpP~B@n!J;#Q2-|e`5Sc{J)s-|HQ06{$I@ae`4kT#e8R<=e)h#w(s#5KJQ%m zZT(*jUtxYA{$I@ae`4~NsQ()?{-2ori~koh{-2oR1OHFge~yo@@A#};_bZOar-%L1 z8NU$!Pwgzv^!U!+Z|&|HN!R{J)s-|HSyF__ z$ID$?_Uahf=f2?YHQ4oThc!QN#%DfpVQ*)?H-4jHJ7@CG@c%SEejfgx7(WO9PmJG( z|0kyXo%I8qX`gx0U}yZl`)h_eGyNeS40Fcs!~fIzG=A&CKm0#2zt8ah#Q1sme=+0##f<+K^I^}lI8QbI z@ONjoCEPfs-Fdt{@8JLGcw>I}f8tJiU%agMgoGFWdZIJ$k9Ym&&J7uU4QnfI?tKsr;B@??_AN+&#repjIUz#F}$7pDf~Z8A3q2GPfR`; z{-0R>pBTUInF}xWcDU=%OA=l_=~8F>zgtEwN*Mo7=M(jRH&$Qn%>4-e&yP>LpW^?; zY~NcYJoM|7$^X;-CI1lrPu$RIdEn;%iOKiF{}bb5;s1%*KKOrP^3g00-Wflz&y?$( z@t^SjbiCmoegEPco$+n#`NSE2<=NYQ(V^#`f{Na`{olT+ZR={}cDg-#m9s?-d>De;QiaJNMLo zdN|+eRa*Z-hu#N|vgNb>2WOTC|4;7+<^PGv$Fh6_Z^xIR{;%3gs{022Pb~jWOuiWI zmHPAQ?0DvHF}@M`e`2;b{+}3s?5r=>`265c-(TyDe}@03;n{!W|B2cER$t18hi|>% z31^1K|I_lq_Hem(B#gd3|iB#i&3<>C0-ZtLH8JN05u`#fd* zKTW^F{8Ritab=VJem4J4%<|&@#f<+aX8Pp+iOIL4{;yd6pP1?4|A|>Y{6De$KXFTQ zpWy$+jQ^+OP5xiZ_wZA$m|IdfF<-`Be{AtJkiy8k< zOx_>5C2cY%l}h5jQ#DT?|#|C^8Ymd z!iw!f{a-QHKl1-##{U!JYg7L>=GeC=DoTC7f`aW6AER`5+Fmkjhon85UzhdovOZZh zFD`#@nkV>O^<}gESmm&E`KpGezTfDKFISMs&&&FUSx@$P%>O%dWO?xa@R#uaV#fc| z@MU$?!T%GN*VhF9Z~vo9ga1c98~)#RKPw6TA3oq!KmW;^-5)Cs`F`Zv;s1&8-4?As ze$5Sk?e_Z^{-sZkb7p$@e`=rAP?cNr%`t0cZB^8{>sx>9oKahzE2`>Y{5t$U4G&Lx zX})u5O?B>)Eqb`Dwmbh%%ftN0{}YohNB&>T_w^EM`OE(kw>C5e|4%%osX6$6;_;2m!T%F? z)-{CuKe6)v#Ep%OA^%Uz{K)?kx7+cE|0ia9;{R!R+5h-|V)7Ts|BD&_&)JU03u<=j zIeu;Z@&7danbwZ~C!TKkjQD>VpZv)9eB}6vnLNWRZ-3uMU4tH36MR4N5%K@TtPlBr z;<{$b8!LRj>yo@R!6$_A|HShD#Pa{dyx+tB;~5|SufX0f*!LG*x8-#OABz47dp>jK zdt7^dbH?|;{~LDx>fryuTO9Ff*V??*!T00+KmMP%-riT?|B2~8!2fGF|FPiz!T5h- z`F}Cv|B3NK@c+aNkN+peufzY-{P64W|Fpc+6TttA8UIg=FNpsaGyY%9_{}(gU(EP_V%|65|A{;7 z{S^M6nDOt+f6y7f5dTl@EIHOsV8})xo&|BD&_FJ}C|nDPI_JDM+o{}(gwp^X?Av-R1X8e{PUgeArVc*9(<1ga>Y5r4ff8KlD&%GTV?964CJL7BO z|7m!RKm0%K4;cSXjNgX;C&o|3{}bag;s3>q|0m{n!vBjI|4%IcPt5s#^b0@r<>UOc z_nppMU;BJ{o-;lg{-4IDzZm~dOgs61G4DI|Y#*QN;eC6bl`#IFhUfZ({}(g5!nB~L& z6O-SH|0k}r`ZV}|V(K&D|B3NO@c)+PKhRwd_}lzHG5tsQe~;wfAN)VQ&nN#+%>Kjw z+xO8G!T*Et|DMlZ5&S>y5BPsE|1ahj zXLWQ9-gSBK{kWdv|HX{|CuaNM|B1=Fo%cm!*XmEYeLt?xg2ZWx@XwkDF7RJ7~@Gx?QQpL>7A=C^IX%$fWD zf3LsWnY_rF(mN8K_uwtgY)||@EkBI^C#F6y{-2obiT~$p!{h&n+wJ(n|8utOiT@Wf z{-2obZFwHPJotasKj_TyjQ^+OsnyO8{6BHX+cf`ATw&LL{68`NF8-f*gw^ZA{}Xfl zUfgRp=jv(s!T;0pwM;TU%=|xb<9PE$%>NUUFNXgomj5Sio;)o0f8rMNqwxR4!M`y7 zFJ}BdafSIBR`1)n()y$E|8%`BvpgRBznJm=V#fc|{e$80|D5gn0Q^7QfB0U2{6BHN z-B0lU#D(^}i~lDcYWENG)0_v|_~x%U)BleDr~4g@|0m}6D*m6i+qWx982>MB$N!5N z|4+>H@c+c!^ZUyq;u`bo_$Oxj;{T<*e_PD>e`0(Z{68^16#k$1TYu4+{#^V&wZpc2 z&g8LJJ-#v8p7>Dse`5S0{68^15dNQ-db9X{;tHz|fdA)g>xcg*=J>(?6SMyKe`4D4 z|HK@h_@Vy4Z`bt##{bjxMgE^y{+}2h4*yR)+I$WCKQY7O|B355hnQdVv@`2Z z{-4@m{68`IVEBJAlm92K9WyNWf8x4!>VLlK?QI=-!T(cxbK9_x|0kCJ7c>4}%=mx0 zUNb!YpYAU({+}2>6#q|5JN}=Z2aC+t!2c7I2ZsL_Gyb2ruk8=~KXE@h-|+v$_}=(` z;^Ilea}#E7)$!sd-M$~^KmMPX^B@0D%=HuhPb~jWJYh;v@c+c)CKUw#Pt5fg|4&Rl zApW12cKkmv?f8FU>d)f;iSe)S|HSx%XDuC(@CUo+JLB)q-gZ>N_WEyuZZ%6H^}*|4%$|NBchcA05u)&Hw)1J!75uKKh6sjd$kv{vU=-be?GMhfh0e za)*xBN#-veG-j$Z^;_}(bUt*LkBR>$Cf|_yzcG{lCuaNM|A|}e`S`}|=XU6PqW#?8 z?2@p3ui=b;i2tYYVf;Ta{wMxl%=mxKQ@Zp2bbV_u#{Uy@ypjJWo@mcE_qN!3l8mMc>KS+Hg@}f_3uMa|0gEj3ja^<1My?X{}bcK;Qxv71M&aF z_&MbNiOCnEwy2o;pZI_3|D%2|E}R&DiND42|6<1f)AVS^{}bb1?fc?7XZ+X=kFR&; z{J{Uy@G$;g%+^2U+anDB@{`UyA6x%c!q)%g%<*IWV+rH`Y5MqdHxGR#Vf;U}k8c?k z{6F#7rXe}}KQYtC{}ba6;{SPt$)#%54QeCXV%yHClj{*OJ|11|I_ri z9+Cei?riGz|6<1f)A7adc9fAQh* z-`>6bb!Udh|I_r~kG6c%$7lFK|LEbiy6*fx%@4-^6U+aL8UN4O{5kx;nDPH&#{Y{M z|4+>Mf&ZuFh2N?8*xT{*b{M?T8NYVy7N0odE8_oYderO1{}VI*h7F%4jQ%{6F!en!dsR z6OXk#Rs26O*JtYgYIzII4{ApKZ=G;K z;rA0R8e;x;RIj&i@U{t;_fLJVtPhy2XPX^<_<*#YZPuU5=H+EM>&sOSOY7lgxn_9k zvwatr4I7cHZ|TtC2@e^P`ip}Hr_;}_|Nk!!9gzB%S>G<}(`Eg=tnZiQY<=G>XQ!9- z`34M1ebD{`)8#E3m>wUa`={--#i_qnU6`M2->mOfTAJqdW$XK9{XX);;^Q~Vzl>;Q#Hqt~liTk#~pxC&q`{-Rk+i`*OGMhwp{|CmvH< z75qOjei#0qk8h0sCuVu^|6=}A{n5_&TX_c^l`#IFmY3zh{}bcq;s1$QzSk}PPt5Y+ z|B3O@@c+ch|I_looOrGQT1AgSZiRCL^c*#8H(Q|gmJ^$E2&NKGg zC-{Gw|D-*33;v(@*r}6(|0h0VOiS?p#Q1O2|JD4d7fk-27@u#S=l1da13&rA-aXt< z8~i^F&-Nn!Pt5it|4*#?zhZ{R|BD&_Pt5kg|I_lqci+9o8Xb=uAD_RpyEFBf$8H|6 ztq=a6hG+iI@4Kt>nCjH$Ypt~USJC~1{K)@}>nqdoVf?@I?pPcAKh975znJm=#8veL z!T)R9c5U$gsv8P}|0kCJCoXLr5$gZ)4G+E_@B8up#Ju0f|Lfa(P4NGCe`n8UUFK{B zzmNBK_Wb5tW51{E`L64eA9MxZ561tC8UIg=4~YLK=6hWHznd4V4*nnS%kcli_=ME| z6<65%F8n`n>&(*N|B1;T!2c7=|I_^N?ePD!KD_V3|BD&_Pt5x@{J)s-|HS0);s1%r z=fnSt8UIgQH?272|B3NG@c&}Q{}a=Hi2oNe{-3jLAN;?V@&ClU|G@tfQy*mCqn`Bb zkIzwc))UUG?u2BhIk%YKaKy;v&g28OH!e$f+v)c?^M32ieeX>e|4+-q`1pS@ zH~;G{=kR{a^8eJ%`!VwW#MIlM{;!zn;s5FU=KUW2pUw{$|4)n$i2o;+|EKBUm*D@! zjQ=ObN5TIShyN$W@BH&muW-ii#Q#$}{t^CP%=mv=evZcr3NLe( z|EK+fFNpsqramkFpP2kJ{J)s-|HNZ=stW#}xN}xz4*yTg`~6|-e&+M%{W1QZmXGTP z{-2oZ2mYU!ygK|pO%HxJ|JxOd@#{bj!ypPBK6Svv*Ws{@Nbmsan_pCD#o?dpk zv;05JzroHw^8du-BjW#wIiB$U#MEcT{}apq6D$8OX8b=f=Li0uxYf=d{6BG%-Cywk z#PyaRf&V8SHqGj>74Oq^^kFN*_s1iwKcmmVdpWZ`tADvi!sP#5zUj)~1JZwi|M%lf z9ti#)+Y|p!On(sm-=b^p5B?w5cl^Iex%-3vho6c6C&u5z|2zDe6~X`G{(%1%GyY%9 z_uW&A%e`F;3*Vtm1Up6>0;_1@~YIaA--`geVPGwu3h{lCuSLHzmZEfdE7 z^ZhZqkp5+#Uj5GY{YTfP&TL=npH3M6Pvgt~6LY>=|F^eOpVj)uox6Rm&z!06THW}G zGyd5@>pyfRf9|ST?{}XdR#Qzg> z|N45=@0{6xHOroHZnOS1{67s({~7+DnC~0#|HQSneewUq4RcF^|0m{n!T*aH|4+>J z#s3qNuZaIAmj4$s{-2obvv~YX2|x4O8=Ud+zTRs|!Zq(Lb`IO`*ejgbe%8O`%<*ac zWeHpVTMvKh|7m&f0rCID^8aGS{}Xfkd~N=pxYV{U{-3zUz8}K>6Iae08T>yn^#bw# z#MBe~delzNH1eSeqiwb#HAAl1^-V>{yO=8V(R0O{}(g^8dtjmZygQ zC&u5v{}Y#6{to`1uGjoN!T*aH|4+>C6Z2J^YiEqYe{rs#*`5E_bN?BU+wJD{kLiBH z^sU}>!uWq0o;*1GznJm=#MA@C|I_^r#{U!Jf8hU#@juA_6Vs0W7c>4}%=mv|{6YM` zl>hRGxZHd;{`GM1`C3!nzfDZu8vb9*_LFhBbVb7We_B4q$Nv-KOXB~D z%i6pBKXJL$tH%Em(_fAM7c>5!m^>2vKXFl0zu^CgM>KWk|HX{|r~N7aPmKS!@!WHK zdhkP={?wU#H~c>h-!f)+@c+d4XVm`{vwzplxXPLRYk8Z_Y@a#Pu1^^MPs>YvN<< z@&Cm5bohT__Rm#M-{bp(;~W1^`ya;t)Aa==|1W0p|HSx@_2{-2of@&ClNR*x0`PfYz`{68`N5B{H6`F~>kMEpN7`EK}sJ>2d8iJAUO2aoQ! z_n>7R*FAASC*zMDR_Ki1c-!+u&a`iPL5VZ%_fh#!Keq30$2iZh_pMKy+u=Oj zzTd|G)A7Lc@c+cj5C5-+^Me1U`Ep_PmzxsZZ{n@VwLabY}ggwe0Q8`fYaX zzCJ&G-+oZBzcat5pL_oRXP$2!{N;hpZT9= z!}fgYOnu(Ln;+@JQ=d1t_9*A6I~V01-29jhU5}>BDYSg_1;{U~r|L1Ie4gQ}PUkLwCO#U7IpSY=QNbvu}_A82> z?NSX7lg%b3KM;3JTwXUI$KPW7D*V5g@&9_bU-188#{Y{M|4)qXh5skUKg0ji^2`5= z8UIhr`Gfx_W_bKRG41$&nm)%9{$I@af8sX#9>@CUe0=iytbUg><6Hk;!q)$nu=Nin zZ2gDM_`UdlT0R*6FJ}BdaYM7^$C>{pmj9>ah4KHy_W|g!~9EM`z&GnKMh}Lz90Udu17HWf6m|fe=+0#iK!<}{-2n7-3e_B8C1M&Z2#{UzC?Qi~H%+&wY{K_rg5dTkH zQrqqSiP@j{e`1Em{}YophyN$8E-MfIpSaJ|slor#{3{MTF!+DsBlg-ici)sB`uKZJ zoss+e_ye4G8b3Dpf0|xrZFTM+OZWBdKd!ni_0IjPFVQpVkk?|I_iw{>T3llMi{$ zF1xSkHK;t~S;F!8$NrDGq$WMzn10;;UCjLP|NegUy5RrS)fNZ;Ph4A56!QPXb#(=y z{;#;9p(wZCXYcv=^8eody4w$g=l|vHu8Xc(8~i_h-{Jp>c^_xrUvyb!Tk!ql|B2=Q ziA$%A3jUutUcvu^@&Cm1x8VQ9jQ=Ob@5BGwe!s5Z|H1fwVtfSrznJm=#MJL4|4&Sw zKmMN>|KUgTUvS13Xsda_=a0{}&7|j@d4KYkJ^tX#@c4gPU#5ruC+7VQ{-2olJNSQM zmLLBwX6pZn=|98&iy8mV*`_z4*9Ko6=GSk;(+R&<`)g;GZ`I_dobh)q-0N4)ywAh` z)Ar|m7yh5PZI*oxZ2q5^?eqK{>z&y?`{b?j?TNqeN&VV{PoK6XVVjnZkN;=Sdd@5_ z{-5T@_QwAcvwZk}G2{P<@t5%b#H=6wpBVq+p2ZJ2pLnd*D}MX!yM6oder(|vcR5eD`EAv^ zhp8`m?Z`X5o%dtqO?NosXLQZD-5EdQ%n7&q@x}W&>i_C^gYo~gJo5j<^8YkE`FQw$ zV*G%M_rJ-<#~0cE*k2@!|EJ+;-)zZ^N&6q~y}=nj@AmcACw$V2*E!=y;Qwj)@FVd5 z#MD2;{}VS`UJw4C82<(TPfUIv{-3zQ{0Q>@#Fe(Z_e`4l`|0k}p@AL8h#DzBek9zm;XuICw|EV3{8~-n6{68`8zw!UXE#?p4 z|B0!Oi~lEXwD-aIe`5T|zs@<;89(!ipPcNB|JQQkiO%>`uRVE!Gw07)A0O{b9%5mi zj&yXu}FI~SP$x9f?^>q~0R_ z-|N#K4F2B`%TL1p6W3V(5B{GRp9KH!oVQZ{Z}=PC{vZ88_ zcXS?Q*E{^bhhOXV0pSl9Pjjxa{ulheeNMPP_<)r*ef&Q$_b>dvnDPI_?0@{fnDPH| z+ua}hKicvC#MFnz|GWA26~X_*f5iWb8UIg=zli@QuCn71|4+>I9se(8{J(3qSrPm{ z&Oh@1VkZAjO#OKLKXJSD$Kd~oOU%Eb{;#;yd}I7SF~=kRpBR7F`VYH0Ze1RHJ?3xy ziwWcZY53p+*9`S`&Ts3#bmsbl|EKA3yyO3gxqjmRX?igJpP1`A{-2oZr}e-3_}qW3 zf7Y4)GV8x}rho3K2eG}Im`dk@{k8{{2QD5_~a$x|7rgCllXsP zhR6RCx0~N*{nx9-_dg)VV{IwGf+2~BYTKqp9FZgTt ze=+0##f<+amj5T7zFS@J|HM-*ZxR1bjK7BeC+;wR8UIg=|A_w=Gyb2L`!)Vw%=mv| z{674@n92VW?_~QQ|1W0zKQZ@vs}1Md2YX{68`NpY=ET@>1XWja4T& zmsq>KFK`}h_wPIZb(pjKKTWUd+x)*C?#}-cSJ?F%|4$rzHS_;;{cAEG@0XVUC&mvX z|4-aBz1#m2bN|Huiy8k<%>4=fFJ}Bdagkk5@c+ccc0I!X)AgF`C;nf|_HJ`Mj*Tw?i8_5!7+(kfPb~jWEdNj2hkP{rKQZ-0@&Cl5tX>=We`5S2+x}y;Kk(OV|0Hbt z&lx|-_OCNOlI1@pjQ^+U;g{k6IotNZ|BD&_PmIrn|0ia9;{S{}VGm{67s(Jw5zCG4=Lr|2j`FA9Ti7mpG5L@yY+w@I$Qso%}!XQ1b=I z{}bak;{R#>Y%lyjwX?tR|HSxb_>Dw2^|I_}!AG6wn?Ydszi{bx?X~+K) zQ$HO4Pt5Uw|0m}7!2c7|PX3>m`Q!hI86N*nTwvP||4+>N;s1#_e)0dr9Dn$KV$MJO zKQY@2|4+>Jr2em%?T!DZ>o1J|Czk&gGyb3MA571lZ`$=d1mpk3jQ=O*c*g$|vwrx0 zG2{Q~d5w1bznJa$&6({-{-4H&@&7bD*Bksl@ksM+@c+bI@9_V`_@VfJV*C{RKXI*H z<^=K6{MC$6!2^!R^b-e=M7SOo8gS_hySN` z`G4Z}>BDkwzdGC7JMDV}{6DqJ{}apq6Z1X<|4+>CFZ@3-`P=w^V&0Eh{CJN!R!o4wDl?@4@o+LvANBWLD+)vQCD`8|sNr}@M9e`0=rO+V$w30F5B z<;?fK{XacA;b$5a`10`kV)>`XCcOBry&?Z%O@MG4(C+|HSw+_|Z zz8-Vc&l9%aTh0xZmy7?WNHO}Pa{`-p_=KlEO zKV9qX+@J9ObboAY84~y+$|ff_jde~t8c%-nfyEaKRsXIkKq65c|`u-$x~N$ z`+t`Am%I1o4!vI^{}2B!=C|hG>ReH|U2fN%Z*#_H!T(c#Q`M-gL;jz5hrG>$|EKqr z0}FdmKd3{TSK2H1e`4|k$^R3NE*%j3KfNy;RnkA?|B2=QiP;|H|HX{|r|DH!_Y3}? zSpJ`euQ1;a|4%IcPfYz_Trx2}7JrMI>idQKKXFanpy2<-jQ=Ob-@^YBw>0(-{-2oh z3;$2c3tRmvXP%Go|I`lS|HVxG-=6993;v&&;qm{(oUizQVth3GKTR+AiRS-_<^PFk z$Nv-4j{g@k{+}3M82?Y)*xEPvf8vhjej)!aX8b=f(_g>nj|t=dY57?{{6BF;W4|2! zpT?K}7c>5!7=MoZKQZfv|0ibp_CXQ6CrouZQ~t|4)pMivJfg{+}4%4*xIa+#lcd^Edc-Yu|Imzr+92@G$;g%=mvX z{$I@ae=+0##f<+aCf}6&znJm=bbX;6|4%&H@(-_m`ftvhzxaP@r`|69pP2f; z|BD&_FJ|ihin(5q|0f=1*HipIt>5sf?SucPcKLrX z7N!1Q<*3yE8#Fxi|AywLd2U(1t|CA6=_Y0J^TrKI{koO`X+7K4 zfvHcI^~bVYH7KpWTQelh>&yClS>LZFFJ0dHQR(vGs@f_F@0w|7rT{ zFY^Cl#{U!JL*oC5S$_OKG5LVx|B1J*uFnno=s@R+xx42M9@N8!9&k|b|1|s$_uMD= zf8s-Dj0ygqcy41+@c*>^$5zz_|4-a$d4%NuiP;|be`50U@c+bYZ~VWQ4_Up3bCpf+ zxsP{uuB&axH4p7!e8QzOcJp@f91r}(Zoax6gy+lO6Oe!MQ^`88J;_|LOYR2a^By%y;Qv_-*Y0}0_Ps9oe`4NO zk^d(yvftbGeAi`}Z^8eA@&Cm1ui*cQ@dNSy#PrYL|Cuuu{6G3<@c*36f586}(;tNY zC#HS|{$I@ae`4|_@c+cMvx|cNr}^`~3;$2d`!M`JF+LyupVk+~{}YpUf&VAQhrs`H zHh%&CFJ}BdG4&qt|6-p1`G#cv_3fIwB-q3fB7Z92E0p|&pSGo4ld!2c|IQO}G62|}2 z_Qe0f{}YpMhW{tV_rU)X$Eejb#Afq{go@OaVFpEs5`E9X8U}zda*Ox=dwRs<;?U)y?158_L=EF#ey$ryc)Kj1PwYC+2$k(U>!Q{6>4febO&ZbLRXQ@$@Oq zoF9*WdXh8y^N@ijIU{$2+tBb1yyCnf8A_c#Jdaf8A?G_pn{xH=A^% z@88;Kg}I`mj_6@qAN)V94|zkDm)!OI;)gpP|L38d#Z!g^|8M8=hl2lCHr?_`4&JLv z%=W?m6LWvW|6BOPgP#Al^Izw7-Cg`(c%P~Kzu&K2>3M+of0p4B{6Fq*_x=(qeX^bhi2vvOt^X(Heu)1kChrRWPmIrq|F>XcxBtib;s3=<{ok0W z{~I&@pE*jw59D~k|BD&_Pt5Uy|0gDY5dZJl54!z7&Nuu&G5ss}e`3y0{6BH%|1tkh zj1O-0y}CX-b4Bp^V5|S-%=lIxEMfdV4bS}-|4+>MiT|hRbN*ZZq_@NPe;S_SAOBCx z@sIx}=K6{Mr|EJ1wEk0X=lXB`tInNvyyO3AeCo&I|A}j6j}HEynEXWizkY*P1plwq z>eJ%?iMhU$|EJ-}x5NJvlP_oe%g*HYS^smw_C3`*S zOdg?a3upX%{6B4<@wUD3|HSxm_5!nEXJ?^YGl^iB@&Clsi^KmDbH643PuyR(ftre`5K6;xV@W@c+bZE&YT4CuV=*|B3Ov@c+c@5BxtJU*rqo z|EZmPIQ%~``EdAuV)=jCzPw+;{}YcIH$3=%x?bd&Phfwyi}3^S|HRB6|4+>EkN+1l z{+}2>5C1P_{68_%$Nv+v|MCCCY#;nTG1~|KPt5kg{}VGk{J)s-|HKTB|0l-p!~fIu z7sme+b9|HkCuaHZ|8)O=@&9zcg7N=i#{UyDJ^a6z@&CjuAO4^2cQF26%=mxKRu3Eh zPvhg$;Qy(8q}7MS{}Z!+@&Cl^AN)TtelGr>nBy7$FJ}BdG2_>N-M2%}o7B5ra({nk zzHi3=)9~a4;{Q3DpNIb^Ccm%s;$c31<fi&Mc|Y-1-hs}HkN>Cj;du-HFJ}C|m?v}`>hoiG`#zXV$OTKydS zKOHYqtbWe2El+di_wkI<)BX6R{sjJ?&i6*E_m2N3#_wBKc$PDHxBuAW?1b_EG{5TB ze!>3}SGDxD->2t#yZk@xUl{*SEdNhjZTEBhzaH-P|HM2$;Qxuqx5NL78UIg=|Azl3 zZfzf7dHk0+^<|GBr5mwegZdKf=& zkJ(rH@bHX^tDMK${kUW6#m=2}|Fhq3&fK3zKXG-!_e@qB~-C&njw?SUoE_+jM# z>3#|0|B3Ng@c+a`l{@f!(xK-M`F}B=e*R4zdY-}eTRQvZ4!uvKzAyft-nYT{f8z3r zZG-Fc_k-a7>HVMb|HRa%Jm7yG=8uRxo|4)qnx9*-tovHtO^tF#UD4t1 z3I3n6`DplmG2{QmO#WZYRzJ&`~ z89#5gD}I+S{-4H|{}(g)f8v&A+kck-CvI-qA>{vwSw8%~nDPI#{b}<(?lq zlOMR*q>VjXGaz?N^(P6xKIE^?oPRrR`Dw!Ve_B4ySNuP5wdHf-|A{%j@&97R{}apq ziy8k92l4;Js{gC~1(W}$cCK&a|B3Ot@&CkJ zzsdg-mzHf~Z(r7)uK&u4wobTc)D{U3%1i6J4jI`uY0vs_H3fM|d)B9`&gAQ5{j=}# z3A624KdoV8>g!eJjZBs&%k9I`;X8(>{$J(D)Gy5XjoJ0ju21EV)Thh(b6Fp;K0lpb z*00Ov`(=HtyYv6V zQ_OG0{}Z>Bmj?e&+-iB5_R!T%HE*Wv%gjQ=O*_}uE`U7cG> zE&t2>KW*>klA_@M>3FRuPS4NsqSWUtDoW4q!ou|YE-y{&*Me>-xUaweO4Ty6gEG ze|pqgT`#n(3w|H(XUCuQX2SOT)nzqZgU?quF+XR|XU+u^^7wwkS^l37KWTXI|HLJe z3xod`Gyb2m`GNR<=8y&d4_^@fPmC{!|0gc9_eJ=BV)B9T|HSwg_=UMm_ggkE=ML*%G_zQHehB`b<`3ili5qvW4E|rt zi&y;8+o^wx|EKdg@GHOYcJiin{B)@^?XP{WhpESU%%B^+9Y1B$${Tvvd&5@m^kMuzG1~+GPfUK?$}g?n z@3+@0{J+WDrHuclcKjdwznH(;@v?+3IdGA){6B3^d?NfmaiP6$#s3ozwetu6FXpjr z7ddnN*kPv&ow;7Tec%NNKe+H`&J6$43x1mL-Zz}@Tx-|giWTQMlZSx+r}@M9e`0)b z{6BG}L20%Y5ZpM)A0YqT;JaP@?_tB!H+FC$(g*% zidjE#CQozr2@9Rs-uQo-UXxva@&CkJ&+-4nHRfNuKICX0AO8&hPx}`?5C2bGF(W@W zeeq$=WtQ)U|M$Iin@3w(weLR^{6BmU^8e0W`e5+?=)b}LD{6i)@&ClEAO7FC^Qjjvl7{6P7CVtf_+znGUl*5ORv?{9ML&fNd;|K8p3K*$Hg-@yNix$~f= zgz^6_IPihs1G4?`|HQ2S!8J8qoBZnjkoO1U|A{$%@c&}Q{}Xe4#s7<${J)s-|8Cj$ z{^0*HJpP|p{$I@af8xnIRRsS}Jl^VQS^kK(laGb}r*`sdkH{O`HSM3>z8&-1?C^mJ zzB869&Ojxt48&9E;2ug{69^f>oNYHmWRAJ z{68^yZJ$ruGT}u(-`pAh3ja^jgYo}j9{Xr6;bmL?ceUE_&ECBFKMD6K{oEP9Y|^8D zPk7@AvR=7&6Fz*KH&<)@@XxMY`kFKOa?jMg(!)0Y-%otW z#~-_Ed2X{8UvOsoZS}_QSL=9!+vfk)89xyJPwg=NU(EP_G2{QmjQeA1`% z1ZS=f_r4H1>;HAGvUQ((2tMjQ^+W9qssk zV&(sd=^w}c6Hl@GJN}=T{$>0>@dSI`#s3rYeFFZUxW)Wo{68_{Pd{Zd=TQGV|BJ`e z&i&JT6=$AbH#_!KXTC?k|I_uKd_Vj@F+QL5-8r*;MlQV7d6?Zlte%+jQ2V~%R}Wp_ zjK5dA{KSOu|8#$&9sf^E{a*Y(vHU-AndL>{|B0!OjQ=MdY59Bjf8t)27lZ$&`|S_R zhvAj6a0`C&pjF{}bc;;s3>q|0kwD7ynO8eOLTHab4p;rtiFi^*`YMX?got zJ_7lF;(~@9@GHmYeoy~4{+~GC`m@Z{N*Mo7?ZYg80RK-s+~$w}Cnlc&|4&?G?f8Gr zmZyXN7c>5!nEomJKXFxae_P&x&eX@n|5H1R|0gD25C2b$e~16)Y{TRKiSeg)yLo)V z_pR>&$|4)pch5sj({}(gN;Qxu4KmK3L_znDPI_EHD0_c%=D}_{J)s-|8)PLo%+Ax%BKF7zxD4PZWzq> z5$(D^QI8V;&)LSu|BD&_Pxm*@C;UG#%ZL9b=J>SlJDl-b@c-1#`r-e@jQ|Li<(Z?$~H`yt>Y4&bnQZC_BZ~Y_BX@#-SQ-F zC%^BM)h8$X*0HBL^F9dwPv>LhxM9Kn6O%uO|0ixR-yQ!?%=HQXFJ}BdEf3c-^8ds| z=C|PgiFy7gUVUD|_5UsVBKUu5?=YVa|4%IcPs2CZ_Q(Gdj~zQa z_Mc7c=>PG2{P<@%ftj-Qhg4V9VhD zslO+0)aD`oPfR_^U8X+JA+9Lt&i@nRx8VP&{|^5U|4&Rk;{J;scCIepHi!SG@#X); zyx$&=`tb7qyxq1p{$I@ae`0(iYO}_S{}(eZn0Qoe-yDC7dH%=$6Sv#%1N=X6o8_0i z`b`hx6XO4=UH+e#JURTonDPI__-FWkV*D@sKQYfk_x=a-CXD~5>2v+S{}c1PNB*CfcKkmv?ekB4(V6+-|LJ&v zdvEb_!YBPbW&FQ*diZ}ax8Gyb2}m+K?`U(EP_V%8u3FJ}BdG5#F+e=+0# z#Z3KQvGV`K93S|9dLK`|ApW12;qm`sKFad{#LOT6PmI5Z|0kCJCvK?SA^3k{@&fVy zV#fayQ@kNiI|ejfgx z7~c>7FJ|ihit+QP|0~AN!~YXETmCBkpSa1c&-j00uHU=7_mwlgHvXU5xxV55#eB%i z|LstJEZ6&fPkiG%((+VepMvXg%%kmk9CLo2<-bP0;K=+mKX7y=@2+TMnx|Jia&$6& zmWxNFzFT(utbdpF?Xvz~)~74ZPyN55y!>Q&viXD)hNR2$T|Qjazsu(FW&OA8@@9R* z=7DKGV8wvcxBM>7<_k_7n);2|{Kc%Fn62+yHaOiLS-&sK#RF3RFv~^#)AcLQ_zIvF+KAC#Fb_C`|kTaTx|Z* z&0|jY_Ogn?+!ouNx@PHJ72WlH&4(lZFXqi!PFnN+%iVrod8Or59DJg4Sw(TE|EqR< zy4Tj8;O+QT)c>_UxZnd0C@l*9pLk$daj5@0acEia{fdi=gZ~#Z{+}3s3;$2!GkyF& zaX~>r@c&}Q|I_&RnfQNVwm12I8Xm^~6O#u={-3zEsx0__G2{P<$>$^gPt5St{}tma z;{S>9De?cr1?6SI{}YcYwR))L|A|>X{J)s-|HN#6^8ds|BS!`QPduWiB=~>ganri% z|BC1Avrq1#WA^jyGkMOO;QwiR&13-g2jC$25c z3;tis_Ne!Gij?vcwDbn-q8|4+>OOMAZRx@Gmc;QN)>`&s-yXZ!t#|0l*5#QziX{>+~5 z5+?so?R@V|{$I@af8wHv_CCn`Kg*O0{vVA0=WKa`_5!7=PjJ_0J`Y|EJ~0cd+k!obe~@`QI7ez;#{UzueE5Gc zj0?noH_PxEK_@c&}Q{}Z$Q@&9yu!T5h--fxos7c>5!nD?0_Pu=89{ozN= z|5H0Y9sXa;_RJ^Vj0{TKLu zG2{P<@x$@|V#fay(;tujC#F9h|4+>I8~;zt^&S6D%=HcbPuq{6v%dI$ zjr%>4_6fwkJIp{6E_9|HSx<_y zhW~eJ=gQ#!Roe0S><6`7^*22bd_Sg-|0gEz0{>4O_P6rKubA_f{68`C!~YW(+Wi#&Ph4bqrucuS zK6ih}+vE7h|BD&_Ps4Nl!2gRG|4+lSeE5Ij|HImSK-pE7d)z+)S0EukNJ4rtlj*%r zCNr5c=>$Rv5PFr4ND)DlD;)$2QUyU!5CN5T=_Di*Ak=^qQ2_--K|zFobP)7?zW?`7S!Ue;o*eAnKm%$YO$oU`}mJe&K6|MNB2IC2f%hWw-S|IUp2q*F@qV>0tefe3tJm>n{@ZRx6}<6hFMZ|H6}mh=Z1nmc zXL|mn?+>;4yJMT)@y7dId(WHR+t~SmpV{&COmFbYtKRs&p5y=Gjqk(%#oNdK#m4`s z7c6NgeDdHk-t%`fuWA0ze;+mvu=C)jGJW8Ozw~Cl?#16)?Trt7WWqzW1fuPALjYl@o8`Tw;k`! z^y($ES7>{NkGJ!od$T<=-|Wrn^S>@{^qy^h&j;L5<<0yS{GYa$%xl5_spbFFz4m;< z|Ec-@2L4aoZ}0yPF#o6Sweub0|6=3+)Vx06|FnHC`SAO^>&(03|FoRO|EcBw)Kl&A z75-1n>nZ+E-DrN|nYZ`y=KTr&Pp@}0{!h*PCFcLBTg+$R|J2O0!vCoo&G+H|)Wc?u z!Rsy4>+J~hf&8b&58?mRoIe!*=WWMt@qe-Le`@>^{!fjkvHL$$w~z0#pU<1)J9huP zr`Y@m{GZmJZ1W>*e&S5Me#`&G#{YTS`PT4%YCIqQPc8o!8~>+n>>8E)pPJ)6_&;@( zT|fRWHvTU*{x3HEPhHbhn*XQ9*G>Csb-$huQ>TwFEIqI()A&EFj}OHEskuD(O{^9?$9IuD}Q*(Y-{GVF$|MYk=-xB|)mjBc5 zi_7Ex)U1#Hi;e$N;~VgQvGIT2YyF>^#}EIfX8tDrPhD;2@5TSAnSaOpzu5RcHT%=> ze`-7j{!d*$b9C~5vGIS}K63mP{}&tor{?*D|BH?P)9VAv@qcQbkN7`z^IHF>*F*U~ z@3sCfHvUhqZ+J-jpE`L+^M7h?AOEN3`GWsbvp)VWHvUh|&yW9$jsJ_y{695*2LGq7 zx9>YM|4;9?8v07}|J2pi_WszH*Y=n5{@I)D`_sRj=*{`n@qfBJ&oBI+-rwS9@PFzS z+rNqbQ!`%+|EKPsQ}Tc6KHI-)pBIX|uD+$X<{SGAbk8a;{N?=GOh3M$eyGj+-SKgQ zHy#K7r|aYP4|t@-yVX7)9l3d%ug~k-uB+RKUrv8~ z$qc{z40}C)X`8;#m4(%x>(BJ9w->#6e{$^aX8HBedz~}Ko6m>y=grIXBNMjp-!IEs zf3?sX&xilh^OgIL|BH?PQ*(LzpSozDm+^n<8C%==aLoUyd$+OA^S@m(bbI!B?2Bjb zoav|L?dr|vx1LXS^Jae^{!iD(=Q;deZ2X^k3;Vo@|5I~*WBWddH;+I5Ps@4y@qcRk zCH_x;5A46$;FUxC_sRUl>E{3Rd?{{K@_%Z)-v+&h`*QlNHAiIH&V%AT$M#p=v+L2` zc)p*FIL3RXeILb+-+A+S`})OS^ZUd5SNxxzZ+KMvpL)8@7r_6i+viplCM-J9udm)- z-#%A3*}JQ6b9;Ubb%)LG!~f~>cnSQUn)e_0KRsSF{x3HEPmLGC|Eb&U{G|9lJ^r0N zcKzo6)SSN)|EFgAhX0Gr{6BAd{lNdl#{a2#J!k%3Z2X^^^ZVle)LjD;_G#Q&*z|G@k|y`H4^6XyTa+&||3si*f&O7s8JoWGd)e`?-O;s4Yv zZDR|=PrNkKHV@t#&$j*fmlgH;N8|tW{sFIt|BH?PQ;)A7mHeOHkI+}t|D>p{ts7oA z@BXWb+MkB^JHPGfqV~7R|7rgm^QG{A>WJ_&;@J&4$VU>3G}JY3n8br=DE1 zLGpiUo&Q(e(6DLYrgGaiw)XfP-e#|j@APhK+O#n2pF`czvRU$fTA%q|%>Rpx|I_hB zd=T^hv>Y#p|MNBvi2qZ||9RW*5C0b%|EK2f4;!ZD?~Q%8+JDQuG&{dkrtyDTAAi+y z>ixbPueH|^4|wx==R3PUnCYbp9?JA9?GI-f|EKH6%h~z0e0lP79}G3uZ^!3+Ioks} ze&>xZ!~f~$>9zUm_&+t5XZ~Mo{GXcJ!~dx{Kd+sC%$w!-zj%M~e`@}o@PD!Ke`;=j z@)zxVz-ymB+<)f(#s1pd=Q54|({g@3{GS>>hyPP^efYoF_`ji_r{w=)7XPWJ{p`G0Es9{x{_@5BG8@p|~b*!VwnZQCZv|Ha1tshitJCjS>3|L47S{$K24 z%>Q}Y-#h+Kjo-und9U?Zygnmrn4mx9i9MX*u@~{}&tocg6KhX}%xJ@qe+I|L5IUoBW@;p|&#lKYUC}%FO1)5e_!6!P+d6X^!>c? zqJO*f3*LA`&i||X+gIO|{GYnN(T?XGyRR>=*=DQc|MdGAIB>t@|I|C|yi4+b>Xweq z-kb zOXvSpGfxozXEWxK|Esk9W%xfeegyxgu3hW@)c6YgU+hh9{Pm!jwdCVizTc{+GmZb# z`s_dYuQgBka?W45^SVQg@4)|Q{Z8{A1J69+jjwp}?~iACzrs+n{|Eo4pO^C&;Q!S4 zgR#X&{qpjEx;^{~^Z(QXwm${`r=JgRi2sYd?Zpoa9=P7U$&a<#{-ClO?$0#-PwS`i z7n=WzjsH{Q2khUOw)a}z_%r;U)~E4*vGISg@qe-Le`@9#;s4a^U&H^!#{YS5SC#x< zZ2X@Z-+=#%jsJ_y{J+@vKlPU81Mz?A1?DmFe`@X@{x3HEFE;)!_63jM;J*(pe}J9u zSHCYB|EK2uG?(D|I{2G#{a4DZ}>ko z-VOh!#=E_`%awlpTW#B9`^&HJ=6oODJ@v=lUE4Pm{&4Y+GTm~+<=*w?74Uz$zjd7N z(EOje*XHBl|I~Ou{GXcdSL6TGe7_q1r^f$%an8k=#{X$KJ`w*Hd!JJ;^v3_)eDMXD zUgw7Mz44Dr?mI8j_&+^f@_%X`-?HP*@#Xye-SVC9dGr1AxmTR+&GYj&w|&=}=O_M8 z+m~K@yzzhP8FqdZ{GXcb6aG()55)heIlmA7Pd(fA*W&-wGv-f9{x3HEPp$cX>K6O{ zKK@V5{5SkxZ2X^^?c3!)KgoYS`o3SC;LY-X@UZl3+5 z*4+l@K5|!@=ZD9ec+@W5yx#n&Yp20i_PHy0KOPVKUu-)*J^0=COWu$3`Qrc7{Ji)- zb$b0W|99H1cV_&bx^b(r!j@+)^!4$8e|dO;Hy#rIr}eo${GXcnR7aWrQ!~#2|EK17 z4*sv^&659{VXyapo!93**B&4I-=k;Tkv!mR^BMR*HS;;}e_x(t-;q9NzX6_a_`ics zygm6pen0p>HSY)Te`@9nF#k`@@e2H(dZrzZ!T+g?_Ii!~Q*(R<|EK2o4E}GUF}ElG z$KMzJPtEq7`G0Es9{x|w^ArE4uGnT8$0rAGzV5c<{qW!TKQ*uK_`ldT|HPZ^haDfy zH2zQPcP?&B{!h*JxPH$~27flUL8i;e$Nvpuon$=-Or13%oxo9z?+Puma9Ka2m< z_N-^##N_|fMSDHK|EYPs!~ey`|EYO@_UPkNGTrvdSZ}ru%>UE&l*a$5*?!^w)O>!y z|9RW-bo`&XXRC@d|4+^91^!Rlcf2I?|6=3+)V$u{|GaH`$oxMw^WX7*YPR?IKQ-s) z#s8_h29oDmuGbsd=EHe2KgGP6cfI)^{GVPQ`Mit&Q*%CC{9m^JxJ=FGXZ}-jdHkPV zpZR_r{!h((G`s#jtxwzSXBz*f^*Mhg{!i=UZ}5L={15(5U1Rh0@PD!Ke|kKa-|!oo z{}&tor^fH$|6=3+)Ev)X{-2uT9r!;rzK{8TYWyJnPmLeM|EVY0`uIO}rOgAu|EZZL zg8x%<{mlPUbN%=~{rVM&*XGsW|I{<=e99+(XR$Y45dWvg zm&X68dA{KPV&nhR{J!viYWx)bPtCkM{GXcrBltfx^LOxnYUc0Y|J3-U=55dE*Yk(x z`v;Gm?~Tv8XVFF8Jb%wxeTjGb%&~=|-@MGPkH-J$`th*cdtT*_2fo0bKbdC!pB_J! zFFo)E|9#ZX9-rp_>Gwn9|J3q-vGIRu{2u;Kjo-unsaekazu5S{*!VxS{GS@%_v4XI z_iKAbf9cHMdQa~km;9gB$D`o?)I7e-|5Nk$;{W{m*80EL_`lfrzu5RcZQt=F_`lek z|5vXkoPV16e`=ne%>VPY=O6R`)Xcxa|LOIs%(fr+zu3(GQ&;p%O#Ux6{!fj+#s8_x zZ2u$vPtEad{GXbi2mhzWQ{w;B%*Vq2srh@s|LOe)&HTUE_`lfrKXse^zVLr)&IgMB zQ+M0*9sj5Ie?8`H@PBINapC{eT?1vw|EU+6?_>U-dO>k&@_$?Z^w#A6rrSI%{9kPR zpBnFn|5G!6>&G`XdGr12GxuxBH2zQPr}{c;sKF z`*OS%{!f>u@qe-Lf3fj@YChlL|Mc_Y@$i3YmgE0oH+?kUdzO7(#{cQ}t@(d?zOsK7 z{};x~Fe!I{&X4ABX>ojsH{g`hx$9 zjsH`3*mC@zx_j2d<(=DEU7%^X~9}vGITE`sxjn|I_PVUDXEZ{J(lV zWquR>Pwy|7--Q2DZ&J5e@_%~2LgW9`Q|pEm+77;|sP{)@^~00@)Bd@}+TrQ^zt=vw zG@YM=`-}fm57d^<|Eun=-l%ZYlIx0(E?i#xa{m_x@F$mSd`nULGpnjMC_MD>P}kY{ zDBt_*t-id)u7BFow|O)F5C5m*bu|7@jn~2dsquTiKkY8Re0%fA!iGmJ%{1r#)%x;( zvGISg@qcR0AI$teHGd!YKQ(_J_`lfrzu4F=Js$FZ>KW#1KX=h8U(Vk%{!h#Kd&B?5 z#{b2}|EYO@f&Ys=X6hrE#{X$K{_ZIAe`;KZgHPvmF1Y=KkUT)Z9M)FE;)! zHvTU*{!h*4gAwze_U7|mU)!&}+1`9{@^8Gkef;0h<86M^{9kPRpBkTu|5Nk#ivLsd z`^5jnw)ri7d(3aNZ^ZxU{^LEF{}&to7aRYl=JxS_YVIHYPy5$t{9kPRUu^uJ zn&&6}FE;)!HvTU*{!cCc7kk8WuNJjGpZl|X)!#CW|I_;Q=I`)->blm^$^WUl?C%Nx zr|xVWlji@aHUBR*{?FU4kNJP%H>x^*(Fu(sD{rT%QF)tka=eUu%^GA=)uAe{uZ~lCuoPRW4U%vC+ zFW=1Pihh5u9I zp*a7q8Xw2`f7Sf__&>bh{+m8K&{SWY{GYnMCVhWs<&SN?ApUP+RYmfDN3Up1^Zv$H zl>DEX`I`8@6@M%FKl~#8PhDR%wQ%m|5M`uIsb2L{GYB5pN9WaciDVH{GXcnkN7`zV_jA9e` z>HNRyrk48T|J0oCnE8L|S#8;Qm~%VZGk-5VHlHy5{p6eTGsorm?(fJh&wIhvmaNBZ zY0i4xistgdzhC_O;Fi}uP&{n;F#}btcKqMY|9fQr1NNP>V+K0ACnf)P&5!O+9+3Ih z_&+t@@8$fzTA%Ot;{UXq{b~3=zEgw$yYf{-rnHkNjrcW8R#<;=CWM_Uq&PUN7J9h&Pw-TJ^AZpY1Qg|LOj*KkkH6 z9vr-IP09Pw_&+trFY$kByvW=4t@6f)ta|poOxtz)^|L?B-dlO&74Uz${qF5c{!iU$ z^V9Hu>Tc%Ong3IFnPzpivNp^|5J1Q_`lfrKQ+fs@qcRk2mVjLk6GqB@qcQ59{iu0 z#|QtX=JCh>#m4`sdHnEyy1hBJKM(&G8~>-CX?}A1H?Gd~RqG5j*Z1z&pZaos-UUrp zd9(lU;yFL@X8$4nPuI`ShyPR0w&TnAKQ+D%|EK2sy7)hJ>vk2%|EW87tV#Y)&3r%n zUu^uJn(r&)|6=3+)ckz-zu5RcHOIs8e`@?4{!h((MEqZD{GXb6g80AK_&;qQxPIpU z#m4`s`93-RFE;*9&GQBSr{?j-|7rWm^AG-~_lN(BedENl{QB7b%xXQ;o9z$& zPwTgvS2$p|GkkfgZExQ{{B&=&$7h~;nm60i2^XL0jmNs~x>LNF@7I6N$=+naE6w}k@%!Q9+YY|peb-vwH?45{$Zfp2{!!~~?d#KazB_OEKV2V<|5MBV4PC$a zdGmj2j_=_AV&nhR91p<%*^C#T|A+rm_biy4{NKR-cP9VWZ5{^yr{?*D|2yELlK*SA z<0tq(JEv*#e>}eUKQ+G({GXcT_&+s|KmJcG{}&tor)K^z{!iU$e{c9do2i!Ze`OU4gQdbQ;9@bsy%|8##_&ClWg z)Z9M)FE;*9jd#QUsppwz!~dzdzxY2j^91pKYUUH#zrDAx`HlELEyqvd|6*VNi(mNt z$N&9)*0tX9e_DSF^M}JezQQlRz&t7bPtSiYkN=B}|5Gzh68{$)|EHG!)9uOssrmh! zd%+og`?D9S?w<{!iW3F+Taf*!Vv+o&f)+`%7PU^xm1}vkp2i)A+x*KK@T# zXU|XkpBm4E|5LXNOiun!&GCKwpPKnR2R`wgem!4k{GXcnfA~K&`&XF%r_0mK|5Gzx z2>%z`j<5UA!`~nNPmf3I9Of@x)33ije9{|l{5;e6KP~6^&iQ}UwX;g+|5eNXskwjn zKXt{xwB-NP(~4>P;>+<1_&+VD@qcQr5C5l@|5Nk$PmKqh{^@hxcnF(+ z>dob!eD%dlFE;*9&E@fbvGIS}-pc>Q#{cQ{g8hB?KQ+g<@qa^Ye_wYO zih8}`_$&TTjSt5Esd;|m|I{4cW&U4m{GU3V58V8py4=2xjQ>+}|7^Z=QLneO&7bz> z=fnSLecIl?`f?thKOaB3sP|j+>XyyD+5Y4Ibp7~C{GS@{ciOfSeSP|{bteyX-{|E3 zbp5T?_&+tjZ~ULS-Oew}{6BSXe`)@ont7d^|5uIA%#x3IiE28FE;*9&EFsM|J3Xc#s7KR=i9pWZg2KS;{UXq&qw$_HJ^9ze`=QF|I~cG z!vCq6cl^UcXJz{I$#cBd$GkcGpSs7sFVTL{H++4LA29z< z*T?%Y{GS@{g8x&?|EbwN;s12~H2yF4o_C#|Y5Tm8Y5boa@6z_}OmDVF_&;q=Y5boW zFVFnH*v$VM>dDFf#m4`s<^R-pWc;6+*LVD%8h_0EKQ-GA{GWQdZU69pYA%oeQ@8e( z=KrZ1`o|>yr)Hil{!h*0jsH`(bc|wtyEpTk@PB%JqM84v#%JLFV&nhR_&nzS>Gf|) z?S{$!>GhfUdH6rQ|Df@I>T%}%UbyFqOymFbex|BwWb%J{KU7`4S@M6{A1D7e?v`cA z|IzqAb#wiQ!msc9S@BPc?=Jr6&4UM6j{lq4w8H(L9Umxa|6fJr=b0biJ>ERyt4nSz zYJcJsyS|-g-R6yl*?#5iMeT3p{J$q%cgIkhzq#S!JH7FM_&;CYmgE1__`vQxmwC(o z>G&Uw|5I~*VEmuD)!x73|J0oS6#u8j^Wp#0JU=)Wt8SmaSNvaWtXFLQ9UK3r=KT`> zPtEyu@qe-Le`?-O;Q!S8ed7Pr+#md(n){3Y8|u-?|Ha1t4Ry)?#m4`s*m`J~)3Z{?FUa=Zyc0jsNqu`FHp~ zHJ^v@f4V(>-}t}S_&+s14*wUs{Cj`!=QrN^oUi}UoB4g89`NE&cW;{fpZ-4Dx;9Dv zPtEn?|J1yH#s8@}KQ8_+HvUh|?c@K{tu{{&|EK2p&-}mG_&@zUb9wxqn#+Ij#@D?0 zd^-M;zkBofl=**tefIZ=|5Nk#%lyCCoc~wN-zWZ0jlaYHskuD!|J0mc_q%J}9=iS3 zk%ivp-tp%0_&=>rcPa!+5R7Tz^9qMc-wz@^Lp?=&%ZMry$17FV^`(Q2i#COGP6A2^;5FmE8ls~ z_a8kj=fTEgy;$D6)lSH+pZ9V3&ilOboZri@pYQzo`JS3PUvJs??0mia_5EKv@ALAV z_ka2RtjDW)a`yMvG%5S|SC7jsuiQNMd>Cc(D}(o|-zTtDCW^O4f{zfCr8%gp~%H`i4p|F^2THTggM81w(s zt<5#b|EULBo0I=j_chx2jcoqkh#gvz@593}|4%Ld7n}3{s&)R~T~26D{*TA!*|&~a z8Jqck!@t**JRs*Q#{Vr@+L-45;pOmuYCIkOPwUh8KQ;5(@PD!Ke`>Ce^Z%-u&xiku zeT(@&-9MJ&|6=3+)Ob72|EtFTasFR5^XEAKuNqH@|I_WUKJ)+7Tp#{V&F$m=)U1#H zi;e$Nb9>DHQ{&h0f9k%Lw&efR#rDqR|J2>x-O2x{ySloP|5MMKzcBef^^%=-P5w{4 z?Uq}m`G4x^?H$SgsRz2+lmAoW?U?_k#^W*nPu<3Kc9neK1v$aMbv+xW!S&VFO?q^^gG>z{J$Ky7Db@_+At z|H0({X#C#~8y-yluX%dO|84f&2a^A5GT(>)Q}caZ{GZmR@qfPD-Y??+zWw_B$^TW` z`%(O#n*HPWzu5Rc-gD#sCU%TY{!cx*Yx9D=e;d5^&#ThBKE7{%%THd&^!z)Y_ipMO zU-<2#zxT!`9`fSvy!n1I{!iD}Fk^D^e`-Ge-~_|2lZk9%|c?($uKndvo$ zKbGlPr#yVE6vy8|J3*t{GYnp zycGUVy=YNg@_*`u3#-%lf7R^Y!vDp_|EXKdH{t)(&E|dZf8J~TUu^uJ8t;bxi;e$N z_&;xZ zeDQy=@qcPOCiDMdGyhMG-@^Z?@m=^oHTz%jf3fj@YVI%oFE;*9&CiGbQ}cM?|J3*! z{GYnh=J(&ZDf3fj@vGIRu?l1mN&GCHvpBi6;|I_xGd7>Y^ z@NHk-zGZdc+i!o%o5yeR`q{?+>H0YSj{j4)+WzmS=Y7+g`FQw0EoZ(R{!cCcrF&2z*5so8&u|5JC`@g4l1n*Fo*zu5S{ z*v$V^bAFYI-H!0zC&v@h$_&{%@Dx-kIkA(dJ_^eehpkL?xyPtD&a^Z#Pw|6=3+#_e}U@_($4|5LMl!T-g^|DAiE z?GrBSJ0SlT8~^9)FRo7hPu;P7P4a(g`M=osKV2W55C0c?_qT_8;|1}5T2ABt)Gg-k zu6+9QnO-{Ozr2}G_tc^5dgJx}cH8H?ng8~=LLt-b7k#oq*U$RVK^0+V%Ey{Iu2lU)la^yt)4E{`s2sfX(Z}|LOXzw<1`BrxQXIHKCX8z!c zyYKeK$GyJ&UEZAk*p8KXFS4I^>l1JG=JEQ*=o`J;c4;l(|8)PE$A|w@bAN|FbCvg8 zJKr(>Pxp7u4t4hYzT6wHcv#t`-rV0G-g=QYzu%7^INz_2uHW+G$pPKgv_&+u8zwv+C zo-*GM|EFdiEB-Gw{!fj6#Q*8~T5Ns`{!h*4C;Xqb=QRFL&G{Dbe`@?5{x3HEPhDsJ z0{^GRqu~G4_$mCKdYqjP4*#bf+cS#!aNb=0!8?a}b9wV?ckA^DKZ5_$>mhy+|EK2q z@qg+m_WpqX)XZYM*EEe`<~|;s0Xe|I~Os z{9kPRUu^uJeqQ-Mwfvu&<45>EHOEKh3_Ru6N8|sroZ}t%KQ+fgnE$7qYUd}z|Ha1t z>HgvK#(aG<@A9?t|Fk~GL-2pG@qcQ(AO0^k{!cCc7aRYl#w#-aFE;1@)%|1t2mUWM z{!i<(9RH_gULpQZ>(lr@b&Va*!~dx#nb*Vr#b*AWn*Aa8KQ;SH@PB$g$nj46pPKWh z;{Vk6HT<70-)Zk(@qcRGuj2pI%pb%5>E~hp#m@iwNx%NSX#Ag={T28>HSdSaW z_&+rskokY!c7N5|5LMn2>++%@7=an-aNjX|5wZ9 z|Fr#+|BH?PQ?ow)PtEn=|I{;Wz9jxn-DmS9@qcR8$N$B~|7rWma_0Z3`TgVn^m-xx z7aRYlX8VEv)9Ve5|5I~375^6-{}&to7aRYl=K7fbr*1JnjsNqu{ek#Dy&kfE5dWu6 z&*yVTdh_$*|FoRn7yeK0KWO})n)#dd{g_PK`)6*n%Z;iQe z3xE8W2fuRER{s0v`xG^+7iHSsUk$are|f)qJ8!912fl;|I_VpfAN2M zzHxc{Uu^uJn(w#a|I~e3l+ORFo;}~rFJt~MHvUh|{tM>+shMBR{696m5C0c?-^Qx z%=|w!=hyxESHI`C$K{)LILDj$e)jz+?}7fZ!uK~k&wFOCdHBB!HLqWv+;hG!FU?oI zz?=CH%>UEvPwLn-`9C$j1OKP4tXe<$KlL1S@M5+KSJaG)bfAov9%-9{6D>)k^j^CA^AV;kCXrV_62um=Krbr z`OiP)=f#KDUr}83-XQ~Y@#X7^T{jOFN33($0O#{9JNti%+CM+3di}yS$KC9`skI$n zC~E)U=8Yx)r~QpwepSQmMRjF!$^U8pZbSXJz_pj>^&kHi8~+y@ z{}&r8re@v=|Bj9SQ*UM8f5QK%7j}*-;Q!R}e`@(ZHRtQa|Ha1tsX3m?{696HkMMtL zem>^^she$nGX77^|I~OqJO1m>FMOOGAI>!XPtRxh zKXr%QU;LjMkIDQ$HS-sl|EHG!Q}cM@|I~O${GYm~)qJn{KQ+&H{9kPRU+lftyyAbK z%)i9{>F>3>ZCvty>W=0y$^WVOe2M>4PiZNg|5w+K&%^(ztC}`W{!fj!!~ey`|Ha1t z#m4`snZJks)9usvKX1D|{GYFHjsH`#J;VQLeH#C#uBjPS*#4Cde0xTpWd2XvyYgD| z#&3RD?3;04v3}1Z2iQLU^x2Pw+UBipWd2X<dBRxB>$(LIBi76 zUsP0Ny%yX1=%v~#vi_@WTGof&9iz$NO1bJ2vYF^WHDt|5qQGpFh|;E<2xa#@Ot9zq}{> zzjprq<(u=-#^+nUr%lT)=lrvAea>$hySmzr-v^JFU!M1W|6lX}{_`9F0}M`!YX>KUC~$^X56 zR#Wnz3%W}FPd%?A>;LA?$oA~%oteL{nbUhRJ3KH)F#bKx>1fMzS7&`;mlM_u zzFzro@_y}YHHGV+czy7y(;rIS42^M4{GXcr z@%TS=m+eope|tACoSgihmbWb`Oa4#Id@%fMN^XhQ+IA{^9XGIpPJ*V z_&+tr7x8~;zHf~GQ#1b%|EK2sqs;$P&$0be%>PsK_~8H4oF5JUr^Zv@|J0nH0{^Gx z=V$((x^=6mY5t#@{b%?;HU0+wr=Dr&*Tw&-`?je{{!h*PJ^Y_~zRg?0|LO7E*5=3I z|I}NVXJY=Jn(N2^#m4`sySK9AtLFdIecP3%`G2~-?aUkE|I~|YJ{g0pW|EW2DHvUh|_sQ{pYW64M|6=3+)Es}u|Ha1t zskuJXp z;{UWg!(ZY5V&nhR_$&OMn%@WhPtEyN@PBINf8zhN{pRt+|7kgo5B@JU{!h*N_&+uK z|M7pZ@qcPOAO26x@jU!rZ07&PX8xbLX>Mimf9j4c>y!Ue;}`LN>Q?*v$NzcT&x8L{ z*V^$9{GXcR`}n`u_`lfrKQ+hy@qcRe2jl-@bw=%r*~V{!h)k1^l0y^ZVle z%7-n__&+tjpZ?c&^X2?L@qf=9dUx`G{J!yj>fWvElmGklUnT$7wMA9(e-#%lOa71F z5A*+i|4zyOwVBt%|EcBww7&eGTK-S#%m2m3|Ha1tsoB2Z|J2M+!2hYae*9nITT7Gw zqw#-gj%VQis-`SW{tu7B{695bkokXG-FjE@f6SY}|Ebwt;Q!PO_WQv9eQwlU$^TW) zos|5ay3Vd2|EKP?^IhZr)V$u}|J3|G@P9QwyEFMe`q_gj2N(6;HPu*8Xws7 z(F5LiKK!4SVq;yrJtIy-)UkvH=R@qfBL8vm!BzC(TTe`@AYf9tHX zd^!Gp>6A0PJ8XMu#|ORHKHBldOxym4OymFb_rd!3zu5RcHOIg4f9kfi{!iUv@5k|f zYSw@2ng!m>$7BAVwkK>q&)H{&H}iyTzUc~We`woYdGmhpqUtJdzF)xnKW+co?fVe; zKQ;4PfAH^3y*c09zs3&p#_!<&w7sSAe`-7d{!iD});~V^KQ*71@PFE#<0bHaYP<&i zFE;)!HvUhI=fMA|IX;R1i;e$_jsJ^{|5MBVspbFl`o#Ui|LOHm{!h(v{GS?6#DB5z ze`>yeW?oc8SIzze{GXch1K|H+Dp>H64T zfd7mAv!lm*bN#(vD)Z*{?eX#E^84-6oN4@@-<~b!{J&~^A^uN|AH@H~#{cR5upIxV zW`7I*PwO-P5dWv<{^9?$KKBp*r>x$Eo|5JC{`AhMCYUT^!|Mc_lejop*zaKmh{!h*OU;Lk%{So*- zwfvu2{?B`@|BKE1zu5S{*!Vv+K7#pwYUUr}|I}r6zC-+9Z2X_Pp?~w_|J3y}$E5jx z+Ws*wj`@FT&L@liQ@8X?PW~@8{!fi3!T+i8Cip)!pFi+_vFAVgR=>9Y_?b~#zME(HvUh|{eS3=VMV>(as4(w zdZ=yxCjQTtTjT#?+xyc@m&Y8jUU4QseAe+C;z9$1L6PFeEz)dpUuT> zAG*Ex{6~8aG@Bp4@Wxhey!|)6(C*Fm4-OpN>D@nXQu2SgzM{?V#s8`Cf%w1J_&;^W z0^9#~{!G6<=H>rxe$ku#d-y-CPvie$`~tRwtfG{>Mwiqe8T_f`gp$K|I}=M z@qg+T`+LLxsqsDdKXrR&Y5t#@*HiqTn)fI8Kegun#m4`sdHuuxsrh@v|Ebwt&!2a? zH`{akpMHOAU-5rxyd3BM)%J~_5C0b%|EKLM%RgxNc4ql?>whQHd%rZ)_`S_me%F_G z+q~2VFFiZc_&?nq_XqzM8~>-~{KEJ@HLoxDzu5Rcb-SH^)#j~xbN@|M*H@e{%K6!ml>Gs;Kuj^!aU97qvf*>wD>_ zYl@#7vpo4fn)!d~UQ-c!7L%P$S!Rq%h> zU%zR^M#=wa|KR2}uh8ZX6xH&7+W(0EYae?@QH}q*Vx2p^n;It+HeNH-ctHH0)@M2X zPt80){GabHHs6H*Q!_v9p0X9*%==rj(V#c}Z_-CYJ>9%6{!f?Z^9cSgHvUh|=L`H_ zZ2X^^%VW#b93SQ1YF@ALe`@Xz{!h*2ng17?`G2wTe`>BD|EK2i_`lfrzu5S{*!Vv+ zpU?1ru?L=c!XJNp<@NVH>5Z?%|M~j%_~8Fy@qcQ39sVyi{!h*46a1f= z?>piD)GWvUsT*uwApTFy_r36c>L&Yqga6a>i|q&gFE;)!HuL|~^&KOV|5G>H=fT&1 z@S^`c(3hU}CvQGaEj;4S-rV00c74g4`*-!+m%SV9^Wu``zj)*C)*1iTOy9ijE8cin z{Ga|F`Fp|tshe6hPW~@8^Z(R%JI?>BpND4tpPIjK{9kP5|EbxY;QwOd|I}O_|EK2s z<@mqY_&?nrmgE0ozq;z(OkaHCd)|0#{GZlme%`cC-}mhoo^IDk9~6HvZB_Dp^h5vk zq4%_D8z=v#<>loglK=Cz^S9&wv_0hf?f5_SI9nh87aRW{kR zU7o*uzVqu>m1S?QVe-_>?d3cF^XAXbTR(nM=JI(T*fb&Q@fycx=O5-hV7~L0&(B}X z`@ekWukZib`JX4>6&2a@^G=IN6A8$+Z|2V%Y^Z#Pw|J1CH|5I~)oc~un%{(3c@AwZ& z9#avtBQGG{GWQ`meTyc*!Vv+`}gsG z>M5<8B>$)8{Tu#I&HjA+pPKh`_&+u8Pw{{MJ???h{69N>f&Wvpe*phy<}LX@_K)NL zVl)3w>vQ}F|EK2o67&DO%@5-L)SUkq|EFeuJN_>={x3HEPmSlq|EW2Cg#S}>eiG*Y zso7tN|5Ml4_lxj<`gz#Df&Wu;ei!_ochAV=|I{tLqmutqv;WqYQV&nf}+fe--{u&G8E6|EW2if&Yt*|5LNS6aN>R`G4xRdE=7*Q*%By{GT5GS$2Q% zf9lzsPs#kB8sCWjQ}=B#CC&d+GoJzf7n}3{>h=cgcs2e{&Hg<6pPK!n_&+u0=fMA| znWu&Si;e$NGd~Oe7aRWZ2X@ZKZgHPH_xj| z{!h*ECj6h8-!J}8-DBqy#s8_h=ZsJOPmRaI|Eb%}kN$Vth5mSRe1GdLF7W2~{*=AW z_vZHAJo>y$VW>vQ}A|EDgu{T=u}by>$I$^WSDD2jlW?2 z-%WqGJI()N-UIXhcKXWQ$^UVD^@WqS^XC41?Y?cid44eePwUgn|5G#Hk@^fU;3dhr}2Mr{b~LGSh4DgJJRt{F2DUVZ+LgvJj9c}{F-<74z-0F zhri;@`Q@L#`X%oLHs5vltQWoUd_BK=KGXO=-9Fw9|EI>s;s4Y%=ItI{{)Bg(dBqQw zJm!tRt9s*MZyt}G&UnC^d3dK!zR#QGx86SJjlX+oo4dXH%qx!k>z&>#$N%Z^q>tSE zW?$aDLv!+fy1!l9n@=?Vr^erX@`r1@@pt$?T_4X6{GWP;%`e9PshJmv|5MMj-w*yz zy{*kN#Q&)|pYnnY&hgvpu;0(ISA562)x7@IJ!g3{e;WU%%TKcRQ}{nM?+@^QYTj?) z|J2FntvMpoc6`;F?JNFIf6p}jPtE&3=KsaU|Eak>{GXcd=WPGW0dKaC_&;r5`2GU^ zPum~n0ptH-VPAv035iA3m{M+iT9Bc-8&)dgC+jf7;&D_&+uC_3(dc&bN#IQ?ow) zPhDllOYnbcmgE0o`;n)wO%KQ;dEtksvy z)cXhaC*1JBwcgC%!T)J}=KtgW)U1#HQ{&KOT|Ebykf&WvFv-2V0|I~aR691>>{0I0y^@R3OcE01q-t4cy z|LOK={GZmR@qg+X+kb-p)B4;W{GXcp%ltnzw}<~zbARxEYL3U_|J2OG!2jv@DgUR| z{6974&mDH`_x=9SzghDGZ~W;Mhg_EFZ-4X0{rdZ0-X8u>U1i$`{GYnU{0jb0T{W-d z|GaH|=Krag=g0g%HSh14{}&tor{?bm|EI38^RMFn)c7gylI3vK@y z{!h*I;s0Xe|J3|_&0AGo)cYa2;kXKK9zXn_mecq@HIE!> zKQ+&P{GZ<6()d3$`@`^mYR=D%|5MMNJ+-jyLtWmpW=$zfKYqG5?@!8_W_a`dWWyJG zz42-IKV4tX{3*%*squlUJ{<7n>@U0iy4j)2()>UDJnRo){-2u9WB5Nc-_OGTsrkOw z##e5YY5bplKkWa)|Ebyk^`q{^-uS+6{(bvQA92NwncjJ)oxJ%zT5;Ge-uS=jmAhto z<70OB=JO!_PtQO4k1y=y%jeqX$%oG0$9uNz53$dY-t7Oo_>=uIjsMfnga5nej|ckC z-)8#*PrTq@?+NB158mQX?@9Lk>h1pdMQ<*T|I_11V+1_lQFRJ*SH`}w-|H}5K&z5C5meui*dG zbq&Lk|5GZjWUmi|5M}XzVytc zMZMn9_&;?^!^X+~>Ghd;eE2^#UJw7L_g53l6Ego#J+g8{@_%aX5B^Wh`uIP+f0}4M z5C5nAZ}`Nc|8-6A*bi2u^ZRoDP96AJ@u~d=i#H#A$N>KD%1wV!>^O2|ai3*}rk*tK z`r=!Ey{9)V&nhR)#hdKe`@CI;s4Z=n@j#LHvUhI*Tes*E9y5+{!h){ zC+Gi-jsH`RuOF5CpMDdZZ`7Lj@e=Xzx;m!8z z59_||jW@>s>Hg68KQ-Gw{9o(`YTxtiQMviNcQ<=K)A&DazgUj{8@JK@$^X&#KlRip z8zujzo;+z-@_*_nlS}jebbU1bFZSCPe&W~1<@Y`DQ}5A}H!M7H@V~srOc`c-U+y_c z|JO|3DATo5a`OSpZ2n_dzarNSIsex#LuV^>}r;d3+61v)-<; zEIUtcU}{%=^at{mIY&%b)MJI`{i5E6e_V^POM6rmQ^kd|)14eEv2z=KP;|ytth6 z!{YzWyRakqKl~Q{PtE*0{NF2AwkQ9GcfXy2~pD#Q< z(~b9j-J9$G>Kk9nbnTk2u54f3Ryu!hYeV776SKW+;jzA)^Vj14p89vm|KYpvf9ipb zuH^r|@pj1*&TMT@{!iWC+?f2I)}LuUk@#k1zk7oYgr(bv^GyhM` z`&Z`wRlHyFf4pC0{@)%;9!~y`_iN1mQ}g}||EHd6^NsO;7vAzv@_)QP!vCqq+vhvZ z|EuQvP@Ml)y=nQd!ji53?ANz$ayno{Szp+1m*b9Sv z2M1rs`zQN;h|BH?Pi;e$NbA9+fHJ@+rf3fj@ zYVHsIFE;*9KM%|Ce`=l|wyv+w{k8W}zMQu2N_g}60{^GWr_Vp;|8#rYU;Lk%`-}fm zPqseb2P-p;|I>2(CH^lq{!h*RQ2bwP{9kPRUu^teZ2X^^<8$~wHQ$HE|EU{n{|^4o z+xCy+|6=3+)O=qa|EK2r+W0>;`&;pUvGIRu_P;a#FE;*9k2m{o@PBHK&*1;m>_5W) z#b*AWnx7B<7aRYl+vE5l{x3HEPtE1=f3fj@YUYvP|6=3+V&nf}6#h?L zGcZ2+KRwQ+1cfdA9u-C)lb{GXcNC-eWbK7U{MKXqB_#>xMwIX=w%KXt7g z?`8g8>Qq&K&Z|I__zpHrIur{;JD{%^gQ;s0Xe|J3+3{9k|lisb+BoA^I9k2n5rzrp3n|M7T_yK{SQ&M$@kJ9CHS z$pdmc75}H^_z?atHvUh|E@&G ze`?MDi;e$NGw%=oXND~KKlIIy*d9h z{!i<-**x5a*0+@AyAG|CpzY|I_X9 z_l5sc&#?2^;{VhfAO7`|r+atUe4BL+J;j^t^8xF8Bh&Y_AM4HQzkUACv>jjdW_w}B zYyJMQJ+|Y&-W>17|LO0Y#{a3gfA~K&KM(#-&G~t6d#A^{+vffK zcr(A)wm;q-=CkpCzP+->|EZa`y6Tioy_x@4d&P#{d>`Qe^MBfY@_6C@)bf97=DXnk z)XY=C|7m+oPugtY2fn=4yu_am{BsOeEk_ClmAmU zn?J<=sd>MK|MRx@-}t}S_`lfrKfQkO{v7|OZnXC=_&>c~()_39^8)@)U0Q#iJ~ckj z=IwdoKk$EA&gY{8pBO$09{w*j{!hOjd>sBSHvUh|{tNtHZ2X^^<5&2<*!aKL_&?n~>*N38a{Ql~{W17I ztxx0s)Epnf|EYPr@qe+Oe(Lmo{eD<}+2XUj`FxK5({g+S^Z(R%qA_1T->?{x3H3|I~cG#Q&-BhWI}< z@AvV4vF+d9{C(m7w4D2k|5Nk%8vhrY`G0EWd9GjmSiiPMcr5&%n(Yt%PtEs(@PBHq zAO9B{{}&to7aRW<8~>+f`-1;d^Y?$;!Ef|yd(HL||EI>g;Q!Rjd&2*zSs(uw8~>;7 zo?-JT&Hw53gvS4=@oe}%HQz7A{|$9%{$FhTpPJ_%{!g!G>G^2>PtEn?|6=3+)M@)? z{x3HEPtE1=e|mpF|6=3+)Sc#$@PD!Kf9e7I z`@#Rk#{a3i1|}x|r|z-OL-;>$JAW_!Pd(kd8uS0uyx+n9shQV@|5J1R-|z1|H`6DK zobTPZU}Exr{`1@S6Yzg({2~4?_6JM0_Ll$C?~BI&squXHKQ$f@|EFd?ApS2l{!h*4 zPyC;n`S$ofHJ=ahe|o;s_&+V@`(*e(b-#Vy#{a4Lyovu)^L=0ZpPI)L|EHgy#{a4L z{EPon^Zj1@pPKdYf3fj@>Urk1@qg;Mwtou$r)GZ>{!jO((L5afPtD&0{!h){3;s{d z`xEB>squdJKQ;59@PBINk>dZPrj&oobM{!h){3;r)Q z{!iUuKi`#4f72W9H|EAOGi~$7y;&dsr{6!f_s|{R_U8WL|FoR#4gN1S{!h*J6aS}X z{s8_@U1`TN@PBH2P}}Y2dUO2cz;n;@=6sI$KW(o$e=qa@)c6hN|EcjE_&+t?0{^Gi z6XrGH|J3q-`aB^2r^ch;|MYrCPOz(AN-$|mrWg!{GXcn zgD>23g)gV^e_GDGDEyz^UrnsE^KqVYb@9dNgK6I1gqro!{6F=ShT(;)Uc9z=&2xjv z1Gd);Pv`&L^X8T5{J%8w{~p};-ZcM@d4)$la=kb667hf9AB^9@|EZ^#FU0?8|DpV! zTK-S_Bk@qo|BH?Pi_QE$bz|emH2+VHuVVh6_7~#;@qe+q&Rp)7XZcT$UXf}1UtIsB zEm!(-&ab+r^PWuaS$3~C$E#Kkzt5ZJYtIKm&F2TsMXLMDa%P*w#!AKJzUcmNdHi2& z{GXcl>-ax4@4xYXYW5%F|I~Og{GXb~^WD+E^xNn0*{|@pH@E-f-?NSX)BWY~Xa1j> z>tp_(uAk$l_`lfrKQ+I9{9o*+_xO!pUqj=@g*jXNHq-b&t&fMZ`6|A=!aN)PPxpuC zAO26x^AG>0W;y;Z_G#-rpLzbaugUg{&%TgZe$J{tWV-*xKYHV9@qc>$)A&C%9vA-? z8~+y@{}&to7n}Ki>Z$hki2qY_{#g8#Ik+k?D%v)?^z0r|W0?cH?z#4s9>Y%RT@7x4hY24?p=InV#{*w=;dnl6Sn> zeqU64*PHDl{!iN@t`GmG#^2%p)RQJ|nEc%|=&)=K(TlvnPKes98 z_41xBKcDZj{9k@~-UGHzD$D#lZ4PYeCO|f-qYpJ|64J|=FNx4FaPu8=j(lz zkIQ?z)^S;1_*wG-n>WvT#{am!30aSs_lNoO{pRQY<-K3NKkMhq`@{ON+4Dg+)o0Jw zTU(X&dwK7f@BDnm+KQ~_%%AU<^X10hAM^NP%l{p6XlL?&3(ODV|J3vAOaAY&V>^=n z!!zOk)STay`G0DzZ`ttwUis=}?aAwLd+W|P-n-tekNJOEj#tG0>GF6({GU2`MDu@I zpXHaVek@Nqm+dE71|I{sQCI6?E|5GQ=_{2UdZ~LI+`S|%K6o#7T z^Qo{GZn6`LKh{|5GzR5C5m;_l^HkH*C2@@_*{$p1UXir#@iEos<9j;HJjp z|CrZ^|5N8Z9=>CYUcfM{@?2suTCDYrg3uee~Vv!B+dWh{UiSG;n|NQ|Ht`xxHPPQ)_{TE+8p>cSjrRHVtsdd8&_s)39dt%k+3$K0SCBHx8D%UUcfA7!U6RI~X zyn5!}=eHkS^asB_KCiX@`~~mU>d}Q$H++6@&W|5X zK9Tw5Pfz;2cYR%&KRw8McKqO^#<6@q#d~VYgaZC=?{gnY{;;;WbpGFG-zfP%dea+! zJ*aMOnq1g#)zjWhjgtx=oc^?5p3f)vKdsOEar~c}@3YwZb6=n15BC1uo6j%y{yx+8 z{@G#F{E&QLlrZ_R3|5vxi@e%x=n*Gc8zu5Rc zHTMVqr)E9^{!cw+U_v_oubS_p;{Rgf|6=3+)O^1c{}&tor{?JIZ4_&>G$-;u)xlmBb9 z#~c5rX8-#)%>Rx4(Te2%n(gnC`G0q}tw`Pv--`c>jsH{g_lEyd^Y@AWQ#0QM|JQ!b z^5p-R&w~F`bNl!|HS+-Qe`>r4{x3HE@7Za~OY{HCm*D?m)1D`1$dFvGISg z@qcRkA^xv&D?6vjIr|OZ2buq;=6J~Jk*(hRKJb5+UAruKKzt?sPc8o!oB4lgE|344 z)3+@7KkhH*|9$20rD^^j_Xq!{W}cTFKOEe*acS~?O?JL_=KsZJ{-3(qycPa0HvUiD zymiU{skuJ-yBi}`xxFFfjv=iBbM zhck`;)8$#t`G58MV!j^!Ps{O*_&+t?(~jMFcW+yf{GXQ7_&+ti4F9M5N8|t0%=5(m zX?+_17aRYlX8tAqPtE%Hzu5RcHOFVWC!FuMH{Fg$?tk0&yqPa^{j&p^WB#9-+r$5-*FD{S&i;e%&>m|pJ`A^OFckq8| zd}QA(`}FDcn)j#X?Y!}SeYgD4d-Lgbyw?1m)*sWosjXk*E&r$Mr}2NW@qe+I|EK2j z73cp|Gyfg`r`zLrJM;gvoa6D#|5NjM6aT06`8N5L&AO0^k z{!h*OG5nvJ_iOk+wdViD=KQ~E?hohxRkQ!(y$^ZUpD#m4`so7*=^{!iV~F(Uat zHP1)Gfi|oj(u%r{?j%|EcBwhPvecV&nhRoR1Ix zr`Ipe56JvKHIFa;FE;*9&HZQoUu=8-TGZ<+-!H}gsgs8>|EK2q@qcQ5fB3(l9-HR> z#m4`|X8vDn{9kPRpWYAfc;Wxl+&=zK&F$m=)Oa5JpBn#z|5NjM?04U9DC+$djsH_m z?JxO1b-8&x{GXcFAN-%XwYN0?@Bg9g&7&;I%6jc1_E>Y}Jm<;rOqu88JP$R`-Cb35 zHBHMTDk4e?jTaD{QMojOqR5N_f(l#^=L=0&H`2)14T3@=*nl#-1O*hY-}T;a{~~## z_WPW*YOh?y{Ug`PXGNSCckI{^`-$H+R(_fMKV$h!^8buAUHN~;nlAs(Sogcm(X|b0 zKQDy*x9|JJdd_$eB4*uX$^^{}z ze|G%j7k>7-8y&y@T{k&?`%}*4yd1{Yc*W?$b5{P{FFts4&WFSP{MZX_$yq+%`2)8) zUitPTbJqTUr~IhAyolxhS@~HH&)4$*VwV4BtnV-6|Hb^)+7IW;*L3-Rw!dQef5zH= z`G3Yo!gTq6#+qOLpRu-2{-3e@L-~Kk8ec&EpRv9-{M64qE$7j-4z-_iR{j6xFFieH zjrS@4&-O?8bn^dn&kgk`$R1N&scd;^8aF1{$I?upMKqjwWs8>ytexKoV9;1zVCN8?0uT{ zPx*iL{!M<4#{WIneNW~Cj*jfl{J#h9x+nAhHp^lDUwqTX3tn<>=KrmY?JPXy=C^G8 zGL$7_?#)CJ%XKOs*@A`lC{$BZAZ#n%Z8^-dRl>cY% zkHw+?BIn_9d*=Vy`$)0;KjYDAr}{_o`Ng6CBxmJsJo4@Dbo0OORd?kqA5H$BEl>Sp z^8aGq|Co!8<^S1q`Ec_8VwV3Gv;03}EnohhvD)|Y|BUrMSN>nj^8bwGv&n6<_uum8 z^nc9q|BTiCmj4&C{J)sx|HUl-&shGQ{6Aa2SpJ`}{5bi4G0Xom?hWIw$^SD}|E&B! zTfX{d<^RPj|Ib)?aq|C+HNX5nTb}$h`F}Bo{?nY*Un~F5riGJ<#mj7ogKTZB$%<}(Ymj4&C{6Ax@ zPyS!b^8buG26txupRs&5`F}CX|BG4vpRxQl`G0miD*bk_`Cm_Pw(#7QK-N0 zn>p|8yr%G)r++Kw{bBjL9{25>wZ3Pa{I{HkyRI#Kb>`o5?rhug|7?52%KtOg{PO>d zwLJNM#+okw&$d^r{J)qr{;%<1`&9*v|7$G&Pvid@)Bme>`nv9 zC&AOb-jAcdN2X6lpNsR8Q~q7K$B&mg-sShFtH*OspP!%p-*ErseLDJZWai_o^!WU} zr7oX`NMDc3Ac#Gp<)gvhjb7mr5hq_`k*r!H-n_pYcR>Bpd(tYri#< z`Fm6KQa1jtvH5@h_qEfR|2JPNXa1k@L_Opayy>a;*!=SE0vqjJ1FA|6-Q^XY1E^ zvv2zQAG+uC`=+w|J^6zB_FUqrkeBz<8;{SYYyUrg`w!-A+}Pat$&YWII(xow z_V}$iKlau~7M}7$7w)OA)HmP#!N1--cj|QE!I$2gv+@q(@-2Tf=GE%tWw}wGcGG8P z<{jTK<@t1d)=lSlz&d~O|GxYyAI|*0ndwsI|NYKCd??HR6U+ZIHvjJtn;**jze;_u zaQ>TLyJ)QT@3~+7>cyY?*atHoQ0?E*mwzQ^wdcR{rZ49_Qt2ps;I1#_tmlDO-~Yv& zi{oK@*Ux_85{KuBm;Lw`^7ZNY;>W)h#tZ)L_V<=U`{ik0xOne3w|u|u@oO^w&sgot z)!+Dse7f3;|MA~Gm+znazu8AUl&??z-+S)*%*BPq2Q!~>q7rjSuDPQ~$`D&wnsyJwM6+v+Wnl{|kSa|2IAnzIPA)pRvxb{6Cw2 zU&x=9|7X+1^8bwWd?NoZX8C{id-dLI;rTRY9iNb2pR=Cd!uM@C>v)Fe-<-Am;rqCpC+E79pP#ed zr@yE6XF2Qri~K*^UcHZ%|7WcCG4lV6^}a>^pRxL1T6y&yoLUtoP&c|BS0keOdlr%<}(?N0<9D|Ic`A zr9bokjCFkE{~7D}$p16e`+NC+#>!8S|7Wc2m;V>D{J)sx{~7Ce$^SD}f2sVxnC1T& z%ZHQyXRPsyklmBPjTHllTf5t77yEFgK zSoMkgKV#KL^8bv@|1*~V_u8la;Kld+=hpi|`Ec_8zWl;_GXHNbyl z!55MLXRLfj<^R3zYg_)Gd^`Dn#_}!X|NYg^Ufjz63-8C}|NZm6i(BLWhT|*$FXo$; zZp`P`@t6N+)3rbH|BU5(%Kv-glkd*_Ke7BjW93oE|1(zJr2Ic)`62TEV!pGwnX~ps z{@;fScV|AJSmXa1D_^Vdyycvg*C+q)Uw`vmnIEWpF8P1P8XsH!UuWrEF8|M1`3Lg< zjMe|~g-6tLR{w|mzmGiUuFMA%EB`NM`G3Y*zx=;{@3<@T|FnJb|9ap2&dmSQboqbA z+P=_#c=2zpd1vPT$*+PqDY4ZP!d?t+d z^{l_hdGhp7=KtCGZG`z>^0v3<)6M_0^~*1l|7Wc7CI8QUukt1T&saX2{J)sx|K)sQ ztnjHXzC2&v%CV8cwZHINIm_3T|7Yu)5B{o<@XKr z|69AOG9ye=28PpXWaL=JuYMoR5d&ulzr&f5giFGhRA9nE8Lki>E^W zdhq{@HU6*szq~#REdS3q%R3GJpVgPM!7q^iXIx!t%ltoMjjtyE&saX5{6DLo=YyXv z|L+oq{?Oq6882x3`r!W=tG`+PpRv|2|Ib+W8~J~Bzfiuh{6FK>kPj{Y&v+^LMDqWP zjn&&;v>zf1SC;9uPF&^u!eF9-@T%m1_csq&tKAGT_&`?vf*yMI?h z|FQf(W3_MP{~0TvO#Yv-{E~0qb=Yz63mre_51yT~{5|=9wtjt2CI2sG`G2;2O_%>? z)8z}w|1(zmOa7nDFP8sj)75^G{};3TKjZ$%uFU_7S^i(l^8bwWJ)rzQWAp!Fmj4&C z{J)sx{~62Ylm8d9{6Ay8Z;}5Ov;03}J%7soGgkk){J)$-|DOCmWAp!vb$sOi84rg% zM)`lnLv#Bw|Id!^$U+!TJNSRbdcKnXXDoj+oZtNSdcHdSzh9KI{4M!^Rz6i8nC1T&7iafo{$I?>|BG4vU(E9VjO8!L|1&NHUs3*_vGTU%|HUl-&sh5} z|1W0wf5y5#)|7)z5nVmj4&C{6AyukNiJl{a*f`v3@WA z&+Z3e`G3YLKl1;K&HuZ^TmE0n^8bwWK0yAT-M_^0|BQ8hb{-3d?%l|WOEc9mnU(R9wH2$x#_D}wwvG!m7pRxST(0ZJUj$gmQ@wX1$l(UvE|Id#1>UaG= zW919V|BG4vpRxIWG0XomR{Qlk!T+=Jqvy|Ek9u@IUG1xH?|rP}(4Nd$$LqdlJU(Z= zKal@t%QycoX8C`{@+sy28Lx$WYWaW0i{X8Z{6FI??=kp)#>?S*V)=i@i=lkU|1(ye zviv_|)}?`Lj&R?hR`{hspw?0D(>j2r&^XY=Xu{pOzZ z^Eoet^1A2Oej#W1s^R;doXa6U^E-!rDd$>fFaA^Cb8=Su^0WW$IeagaPuKek`G2-O zYM;sfGuHU>%KtOgc<}Q7jP?Fj{-3d~NBMuoIzICMjO9zp|1;M3o$~*THU6snKV!AG zrv-_9$Q|Di~VfSCCyU_x4Zb+}69h z@WERj%(=g3PvMz|KjpYo|GS(u|KE0f+VNYT|LMH^>U#b3fBQ_%Jt4ns$K(D!XZdeS zryj~#^UMFU@~Q2W|7WcE<^LJ$`j`I~v;05f*1qeq@qdk5dao_~##g_XACK0aT?P4n z`Sg$MMSDF9U9a#Qf%*y|>`Q-=7|Fh}x1Lgl2cXwTv`G3Z}Jv%c0 z&sgXGS;7A^?(5#2`G3Z}UAwaUKV$8W{6AxDzx=wUDOf7kDQIp**2_hkBh{e#|r zqmM}D{?acT>uhm84397UJ~H$3xPLq!DdzHdez<(*J#zcGK9(0AkI|0(?s#zgU-HP< zfSbQK?0vtMG4JRfPj1SG3-8NvmOuC7H#{w8`HO%0>^pL<*Xx=8XTMjz+tCM~l1~@Q z|9kmUXEJ|K{+j$hW98|||1(~jX%yuD8Oyhm|7Xh=%l|W$pC|v%cyVrP{9ohKVf}af z)|2x6JrR7mcm3s$<*eV!|FikU^8al8^84if{o_lgGyiXTcFX@WuFh`xf5w%WiOl~q zmJcZZ&scuqABX%u^mH%g~@tNiSHQqIq z`F}^2RxMhN%>R4eHI2;wn|$OWGyl){(5d6Dd=FK8-sb5_)lI)Kl;8Mz;P}AH zbKdv6FgxewKOe?xj(@N65VOVuzV9c#adFqjKAib}^K;eA|1+MQ33-XZ|1)mPjb-_N zSJywB`G2)AKCt{hWBF+E|K4)%hcf@KTItUGKjU(#J@fyJOTn*`|7Wb}^8aF%|7R>e zQ2w8-Pd=gizm})ppZSZ*f*Cs~`*WCX1`TD0CV})BD`1Hj$^nEDv0UPzv!dE``cR9~bj;Q^4@iou< zVCDzT27grkpW5v50mbtFf+Lste+%LF%KwX5`F}Bo?`QJgYyQx_b{yK@InMcWeUot$u<=Z2lGCbeqtm)zTFXwW-U(bg* zR~iGE|7ZInpYYz|-TCp>`waPiHeD?L&scty{6Ay!|BU4a%KtOg_h0h=j7MvGGyl(c zGUPGH|BLyS1Am&c^4#SA+5VTS*Ju8pac6j*mH%hlRok8Uf5v*=mH%g~=SBH{G0Xpp zS^l4~elP#eSb6U6_@y^r;?Tde^W|^KxgPqnK~K;XFL)7HTi$W<+;(!|1%z+ z8P4+mat{47%KwX5cX}?UDaytns_$|Jm}z%KtN#|0w^@xI2uGB>&HN=W1`} z|HZ8QKjYr;{#O29%<}(?dqVz%{6AwYU;bar^8buG!uY((|1;M9$^SDhhT|vy&se^n z{6Ay850d|9e0{inl>ZmA^8bvB6W3?{pYeFeCzbzato}9S{~0$n`!oM<{xkPx-wP`r z?(Vle_M)+T68V3hy8YhF2h{iZ^8btvhW--yf5z%x`GNASIqQA6{J)QX@SZFWP(JMW zZ#>-bH|pneR{zkQx1V(^|L>WPz9;hq)n6q4Z}4BXd_m={$p16e_-iMhd&2P--+#=p z{J*X<7jr*Q{-3eFrcX}yvg4C7jv#1 zEN1@S4?p$p%m>u?#CQDj>_ubwd&>XYdDY#S519FU!T&RsFC_mjX8C{L|G0O3HxF>j z|BG4vU(E9V-uzAP|K0d2cRBwr=Foq5@#N>X{J&D@Uy}b9^PRunck$~_duQhNsl2@I zTRo2D|Jii)Kgs_y)_BVD|7>~k1Lgl2%Quq$XRPVU|BG4vpRvXtmH%hU7i;`qu{x9_&~RnKqb|Jn43Fg~yRKjXD?_00c^S^l5#LdfS+{-3e( z`Q-n_EdS4V?(9V7{~6ETRL%T9W921&W8!1^{Mx_%4?K{wj>pL#`B2XC>z?s_@6TEJ zd2f8peL2sD@uWY#{O+7}e!lM$cjv6}WE*$9)3N+NJ3b>f3>SW+?N4(a3qGOzKbyW8 z@+6i2XS{xLEc5@2mCrZ$v%i;57vIqNyN-Y6kA5fTmE*<2n@_(wXVri5|7>~6SCRi` zto~W~f5ytwlmBO|>*sC%`_6p-%3=ARdHHj5HviA&H~-Jr{6Ay$|H}U})_Az`|BNR? zf3p0)oP#eX|1ZBDP7Y-LpRw}w#Y&scte{6DLYt@U&sg=F{6FLA zkOw6H&scuF{6D)tsDE7kpYcYxAISeRUJ3UX`G3ap`{e%_%O{loXDlCG{$I@U|Lp#y z{$u%nF^3ld1!FBw{-51X&mvgxP%m0g6{-3e> zm*xK%tN&f&{~D{mS>yj2YrI_ff5yt&)A+x}%Hz}czs7n#lmBO|=QH_#wm;_o8LPc3 z|1an8{H6RqV^8bvLS0ewnqU5(O_x6^|Ib+8H_87qR(X>DXRPNL`F}CX|BG4v zU(E9VjP-mV|Ib+8N6G&)*71`6XZ49#{-5#CLU-o>8S8r_<^RPj|1W0c{~4=3l>ZmA z{6Ay)WAgv3zBK>OSnYfHe=*Ddv-(-n<^RPj|IgU`znJC!8SD9a?3(Y}FqZ%Jf{PD} zxGnSl?0%v0qVa!?rt>_LggR=B)1zTkhF)iNo)I`ssUeR(X;C zXZJUqFZqAQdVbaTzs7ohH1}U^j$idB9XadyU;dxnU*!WT|Ib+4C;u;I`G3ZZrT)zS zi}?rk7B}qvuJWM#znJC!8JqtXv;03}^Z$(H_sRb=UJ1|N^8c*8A(sDVtmVu9Ggf(! z|7Wc7B>&G?;~mKVGuHE%{6FLA)xOOCGu{Z#hw}f7*F$-3+_AEew`aremH!uW`3dVA zpRc`R<1fDT=uO@KS~@p#*8NZZpUuA(zUR36pAI>G<7OfV|4PpC|K9b> zznZhIx3@p$xjE~4eB;u8&sp{5D_WkHv)W(s|ExUd{iysulmBO|JTduyG0Xom z*845_f5yuHlK*Gi6Z|6ie^y_17I$X;-zDA}|JUkk`9m-M=5OZp|L(yZh5H_ONzS_l zf^YZc-*UXM<7FFmf70~nFJEH$IltQXiVeHpiSK&LD>tmYq4iDP`6|bEeB;#{)?U&4 zZ+PG}Icxq;y!E$pmM?VO3xCJ)%1^vDXZber|7>}hU;dx9m(2gO_i18{|7-8-#Pa`Q zmjAc%3-8YSzf%9M%>VnwZGV~hf8%{y`G04B;ys!FC!bROpRxQs`G3apyPooqKic@4 zKYCy0^Jsk!{m(znS^k#%KYM>Hmj7ogKT7_ev8K!a%ei-N=KmSX=aK)HbNIddKYM?v z-^>3q*7nQ)GuHMi|1W0we=*Ddi&_3(%<}(Ymj4&C{J)r${};3TznJC!8OzU<|7Y*F zwY~EHj5S>@ow1I;{*PJypRw}jOCjZZPf7h1(XDmNT{-3e(-{k+<`PcmN|BU6s$^SF% zY2Taqf5u&{y9@IFjCXYGF8ti<{%+&b7v7)ck?iUU&yT_XGnTI=|IfG>^5NwF8FvLg zP5z&;{InmP`)tHJGyl)lr|p;jXS}z4%m0g6{-5!lw(AO`|K|(&{_hLFm;YzSL+h9S zXY-5Y|HUl-&$y%Yx`O;a`@NPg|Ib+4Bmd7>exCe4W98$?|BLylQ(wzDs$>(lYm z_`k+Fej5MRj@RD(JF@YAja%AwXXF1G_qOfH{6DK-#Pa`)<>zVqUz=a!<0}8priw9(|rydcCj5{J&yv=zopI*Ja+^X#aqlJ~QZjFm5k> zHTrD5{T*(3?D5>&fqco5&;P5A z`TW0;kr8)(#>RYp-$2=O5&ob2y0|>a=Zaar9$Eh1SHHaF|IO8BGXKwbVQQ`*|L@*^ z+4BG7!^!_M)_AG%|BRI%cXsV(9KZ63&(2x-cmME`XE}c9Z$9&$UG4Mvc){}jjLrYc zxm?Nozgw5*GXHO?Hj(*%#_|E>{~60ylmBNdzwf0Vy(3?~wqO3AO_$&JqH8X(#)tjn z+)w7yH6Cwx9?E&OF(lZ-xAGG?&j)|3`otg4S>x5p z|FivFtZn&!G0Xq6R?mru;u+ZJ+Z0jJ18r|I0b# zAIkqT*7=nGXFNMQo8|u*YkBhjj8(qm{~2q4<^Saz@)70#8Ox89|7W}&^7ZZn6v!GUw_@_^WUEce)0>KKX-BS2@hmG;mN6LVen-Skr$ z4_K@h3n5!N=hmUt!oR-ZuX5hsANqgZ@!p(!O9Pqz7seRQe98V=U*`WA4}|fj<^LJW zkCguxv;03>zx+-4f5!FTYs&vKuGWV$|1ajR@4A>DU-^Ra|Lk~cf93z#{9^fk#Xy&ey{~`c}vC|Lk}xk5m4ivA&0s|7R?JQ~sav zP^m5R|BTyep}#Qrf5sh?A>TRpf5tjLpZ}@f%hx|WUnxB8d2h^leW6;o`nTVZ^Fm{! z@UlPt-Ag>(Rj9o0^*Jxi_GJE_Eq``C&yQ$u7vAH{-3elrz!t0X8C`{>QDIeOJ0$0-^lE~!tHN*dCr>tfA4--&g$=a@yA}8 zv-*SN|5OYN7_VK5^FlYUK?71&+{LEKAKWEMV!MEO-v-;Qm{OQljmoJw8 zXZy2vYRmtNS^l4KPslsf_`fmB|1<6l`Ka>$VwV4Btm7&F&$uu2_sIXd#O+!BpK2qgmng3_3{66LX z#Vr5NSU#WpKjZ1JKKXw+-&o4>|BU5xDgVz{{+7o7HJ0Be|Ib+dp8P*!`FryJat=P1 z{J)sx|K%L!m;V>D{J%@Q<^RPj|1Up2!AFz-7qk379QSmjmzpRvlb{6Aw|5Ay$P|HShDjMYD^{6Cw2 z{=`6*|7WaxmzRb7KV$ie^8bvdP8Ku&&saX7{6Ay)v!4n6pIr~~YnA_JJQ-O2Uw%D> z@-F|+SiY%Kx+aV(HXY{-5#k=}PAR86P@P&ip^)gU3sm|7WcIk^g6`JVyC{ zR$s}7mj7p55A~(|KdaxA2P6N_>c`p8KdbydWA(?%|1(zqzWhI9`F-;LtUg`}{n7IO zjFnF#|IhgF$&t+eGhPehiOc^p&g!$^{~4=(m;Yz?1C5A>Ege>cYfWrS3ct7FRnQb$1`U=Kg$2J-;3q{8EgD5 z`F}BoXFNEwC-eV|<)6y`GwuxKN&cU)e9Q2E&Rw&u+4#RUT|S}w zznJC!8S8oIv#kU@;BuF87sd~{$I}F_{;w@*72ABcZoYQ z|Ig}6^Z$(H@5%p*S^l5Z&zdg(&sh0$^8bw0{#X8=vAzeA|7Wc8BmXaE`G3ZGK34vp z-5*q*eQ2w9YUp4-N{6AxDpZvd=<^LIL`$GFXXKkPSKfAxnPn7>>tnwiL&se`# z{-3dp|7&dipRxIWG0Xq6_J-z{|7Wc8E&tD0cWu5%SUG|HZ8Q zKV#()%KtN7SPAcEg8ygjE3HrdU(E9VE?o7_%>R>bDE}{J`F}RQ{6qPF#&cnO0QrB$ z%3qWJXFL_2m*xN2_NYA||Ib+dzx+RAwJ+uW#Vr5NSowMK|BPqD^N##KW6S@u^C6c1 zm-Bc1znJC!8E+om%Kx+SWd5H`H~-Jr{6Ay)dGh~amj9P?Xz$4Xi&_4kvDz>4|BR>B zLcVJ7|BQ9~<^RPj|Ic_nv^V7c8P6`aW%+-`D&NZgGgkRl{@*3u^8bug9_9ZT>w8A| zf5!6lyrC{$I@U|6-Q^XS@>LPssl>J{Z2&RQ{jwW_Z6L|Ib)? zee(Z|)xMJdXDr`O{-1GWW`E}Y8SDNd|Ib+8N67!P@}T$E^8bw0K9c`utoOb0|BRIn zCjZY^ev|yanC1T&%iog!XZ4|cG3Eam%P&&?pVhx&`F~db%LkJGXRPrRPfxyd!|q2{ z4P0B0{}*#;uW#7>O+Mg>`(LqP?FsQeKkro=)?UecsC}>Au=a^q{-3e=f5ztj#r(vt z{Ek~*&--7Sv-aoy-+!Is$A01U8}>d-(_ee`4IB1;O)US<-q&gU^8bvLCno>zCm#Qo zng6Hbqx`?(#(OgVPkCw@|M%Xr_htT{d_MVq#`4MJ{~604l>c}5RqxOIKjmM^|1*}q zDF4siXDd%k{-3e@E%|@OIzRINjOBkR|1W0we=*Ddv-h7_epm4SjI})Zf5zHh`G3Yb zUh@B9mj4&C{J)sx{~2e#S@8d2mj7q0<1hcuSjS)fpRs&J`F}CX|Fixim4EqvG0Xom zR(X+1@Bo%}!J%>OI> zW4=G)KWq7dWBGr!fBVDozw+au?Uny$)5XgFi#hf&=x;Iq zEycBdpO-f|*yDT;=KXPb{5^d$`hZROdjsAlEQR9}?_Vn4kbYXq&tu*nx0lTA=kn>> zF+Z==f&Bw>elqj-$ef?d<45NF950&rha>IY|C<^2e%|z$&+jXhw#VhNU)~VLJ0(vB ze=aUB*IxHNI~=f34#44hO20Cd{7mqJ}JLd0kc@wjKeBT={-0ar>q?>Pb zeCwfOjvq0%==jE(KVS0m;{8#6U(BiVD}ODXpXXEK0mswHYYl(>uh#wfQ2t%~`|mX~ zAC%>LcHaAsWchRP_ASkO|MCKS%=0+D%EOF*zq07ZSDsq(d5jZS-qf<6e|BxbE$`Io zvg2cmetC0qb8fnP=XiTg1z$GiTUJ*c-*D#8WqEePm)~0Osp930FZkv6Px|vupON)l z_k^zxTgLkR^2@&doT&TqR;v5*S)cdEPdsv;CW0mnlNzWzKt z>&yFrvj6^}f%Cnx=p*8Bg< zvHHj2=`A5YC1&NR#H{|Vm^q!Se3f|q6sx~8o}cR@tH14X^QYD)pD_OYm9p|Z`K z`H}JbDOP_%JU@>wnd>LZ=ZlwDKH!fp=O+&z^4mj}9~duR{z%O7N4}S={B^6exeM*X zj*t%@Pj9bW=eQT^Tbl6g)zyYSAF1aH<*CK%+b+vrh<~sAx0vPs#jNjjVpbk{%sYY) z6tjGfn3dliGndzm=LPwa@%+kLj9K6J#9R#iMa+C2V0q&2Q{{p4^La+&H^=Me{*n3o znPNVlvb~<-!SMZ3ynXWDw!`|~EuLS#=jE8?hs^R<$MaQc`{d)r>z9ulv%W99EaUeY z4?CWp&yRfml;0E2&-Y0hzcZdbh3%2w8&7ZI;8(fn;8b}TUH116GN13{^Tq4q^-JdO z<)g;GSN>?sd|s6w7*8k5UyrBD$BMb>evkXD{JVJmH9SxAel8y`o<@Cwc~4oKNU}x-xRaP-;9~-=l09T zis#=hb9pJ|_K@Y@#oM!^*PoA_eZIZO?d=%!^Vhol@vL_F{q1kN#;vcf)gSL&Eq=Q4 z$l~o&URlh_7uybBAI1ZX=O<_WRFr2$9`5qTi@dkfZ~y+_KgR3R_@puSbo=AO<;kCn z=hyh6F>|{7ymgAYuQ)KyL@$Uz^ zeS4*|+qaiGy8Qg|$Kv0oc%akQhhuI2e$m7jKa@TV$I~Qpf64Oe;_W97xB2PxhqyhQ z&f`hnicDXMoLU~|@9y^Z>#i<;{CU23eiqyP{d=X$pD&J|O5ZKTRrqTa_;mE+CNMwq z^T_n=$jtAX>GQ{n`$y*XlQ}=v&;6rcmtyAejr95Jk$H9W*LeN2{E&x{2gvOw(~oQN z{d)ZNGCwc%d+r~(sXjq{Q*HD0S*_jIcdSo%y>mL5^^N@IxW1Vf^Y3q`;cIo4t8V^| zQpGX-!0~avJWi({I8iFQ<RaZkvnbNdHBkiH+8{$IW3*H926`N%0hg?=4Q5`uDl&T{cy)mc+_JYKj!9J9RJXP6~`CC_{VYiWxgMoei~WhL&wV_bAI}A zEKez4mGiI6_~S)pc_VXq++L1{yf`!K_E&k9@&0rA*~LXS{RDhE{(fbC!Oc%UPkEH_ z`j%Ga9WSr?-=AJtchiqAEIU^IWW2o9x?eue=Y`WJ-26|!&6l^wA3NlxuPiqlFE04< zH@D!AAFuz_s;_UCO8$P)U-I>3@0fqz#rp&6U*(6!`_JQl20r9*)c5qI=_glee*3Bu zV{Uz{|5;zmR{Za$OMd?*tG++2UMsrgSEu~++O(g(5XRe%_kX_Or}O>oBz!^oc=Ye+ z?=^AA>x|d0JkOZ9e`Mu@#`8~C{QlCPAFTP~H$Lj?k5eaZaLfC_bLTG0XV0E>(+?j$ z?D)pRtB#K>`|_?l(0KdLgz@TQuCDv~dkjACt~I~B-Ru5-F|_3CXY#%^-#)r-uISc( z-J(Cf*Dv|w*FELWSKq8Z{vC6k_fGofv!1H&ALy-hxb^pA{w79$Ci^RrjQ%tBZzcV| z#P9k3ll{HyZ{zwoKbie`WG;`)^^-L|cw8RW;Iq;HqMyb0^JL{2#LK5Ir@Xy*dQ*Q( z$bX5av;UX2{r1!U8Fu3K6Si*%IAw&`FxJy|8f6$yp-1$|DO9p|8F6T zXB^MJ6vjJ_S^1VREB`WP`mUUwVxE6;$}d|8;~~e}L!Lh3>zAp+c)y$QhuOcX@zLV- zt;2UG(`Qq@PW*f2;l!-*d1FrbeabJ2=VyIO-;I78c@f7$`9SgV$@EWCOh1+7ndLLt z|Bv%QUz6vLtUR1}|HwT4WFBvx4~-ufFMl!QdBsd$hfJS_-)FHsNT#1ff2Zkt5cq*zf`QxQLv-o(Cd3-os`DgL(=|j=qpijm2qVoUZJD>wKO`@p#Dhi?^444tZ*>)y-drKdSut zczMdZkD2w$5Xv*pFPZ0)=bP6fuUDRrlrO3L$$0zu{6^;bw#%vQ?*tO%@4ngzFvyCeaicb z*GK03WaYEPzbDgwOfmgGu8+PVr*r+O=^g#PJ<&Pf+Yc$ftFy!VaUJcK_y2acdVj5L zzyE!c|JUi~r(c&k-z-05`gUacZuIB4y&6w7E)PTS8I{i#Pv36&=k~L_aC(ZlKW*^+ zG#+!jy@P$ee9#}GA4Z>Ru*=^cQ=H1*;_{og-QQn_yM6u6@l8|Pv)$=U+XMfwyVtkh z$n>9>Uq*k7m$?uqu-V)pUgL;Uzhql z{lf9V%kMvr2g?)phsSrh)3?9q|MB{wPe`Wk$m7TPxjy>5Waj6g$4p)axz`Ec#X(<@>8R5JZ8`hcmtDCP^2 z=`%5}js6b(Jo-;$&d=pBAM5bkjJuyRFKuSd`#|))QcS;*$CKxC4&z17R($zl-X58G zjy(R{o)q(ZSEs$7L1sSS((If&zRRa>bbR8Gk9ItJ{$|H*v-6HGV0kygZ)2X_>XKhS z{k9wD{qmV-$K}-*y}weMtGn%E9v^vg-j_F)PhJmXmUsGpTt4#>H6C=_ekF7Hyk1#9 zkhwfEuP-vo3w^`cNq_ts7$2I~*O@bC-2Ps;?U9bB7yS9>^~3YW{o($fMn3DYQQu!# zEEe7RhllO8R))^8@?m$bA1w z=KS;n*&noiu;|VY^L)rDzd_?0#q}foE&6Jye80gtUq0ABNA6g}`{z|(-q`;_URd_? zFRl9Z^Zh^jBk04?Cm?hFl>gUC1Aer-% znV&#r`64r4kW4?2)321dzbUSvKaAH~1$lM!0m<|O=Wg)#!<93aXXXnwFhBF)Qh9G0 zFE%b;^ug%2ZP)ip`DmO@ziskp(QO~+Pw@ouPR9@X_jzUHw{ZRB)cSaQwmU!9S3^GD zm6re1@9A5mSmW=;<%j<7cA3{deO=z)G=6=&e)_yArcclMj(%Bv*|(n>E53hrYSp)Y z7LXT6zi#!o-+tzAZkrSSD*ZolDu0Om|Kuh3q2x{EyRIW&mi{K0<%8w<;6dNMSw+4S zzZc;BnA7Qd&{r8n{ug~h=6mt`jvCsdY%h)=zenQ%$K^f6%nM^a9eu#^wC_J|;za%! zeIs(}_|PAt55?&zKZ^b({WIAbN+tOW1i^;@_x_nGw3_ghdhkD{X@uCHl&0Jz+f8xctzEr7w8JoXDSJ z{vQ1_`hVm~m#<&R^y%o2asG0rzdzF7`(88s!|kr0z8g8^({cLPfPY?H>nXbOvee<< zS8;vho*sWZIlb2J*H`NH=d-ofzmM35^PN1u7%!Ijdi42b2L1Z!Z;|P<(MKb5e)?Ht z`eN(7{&*hh@#o_pjvs$dzi++Q_vey%ewrA5;6xZdIj&z;;A@hZr^oX{e~>n z+}}o@?;oY_%i~SIk@#5hhuhc-k7ne`}i}`!>JLsEnyj8A``Ctpv-jAaHL%%P@%=@&|B=&q{VbQgZ#6aO@5k-no>AX_TpjWE^BVlYS>(;GHoOnXEEZg4nLoHhGdq%?J|A8kum=~(KG7H zcju6w-recjcO7lsH{c!KPI-!9WfBlG=zGyC#JAB1^$93Pp-mrS34+`K*h{>%J?B^*Dl zkA7jwcjNw%IX)Jd>nGDMC8zQSc|OS8-X_NQ&P~Syd0-r$nb#Zp=g1ttnE7rT@0GqD zeZJKAzV!LHJdVdpX1?8anfZET=9$s&DIM|Uy@K&ed3?$A!`2TL-TjyT5dAPt=klBK zTF}2r-;X{Y>u36Lyk1!UrKa;&z$WD}7%2gtN&1q#w{UzB9^u>Ux;N z{?mUXb9`qq%LA|9wS)e6(nsL=B{RQ~enDz{V)`K*-*Mms%-0*n_`38P#wWcmM8Azp|EmM-XZm*Z@#xc$xxVc(eY~dMBfp&A1Esc~ z%j5c(|H%CxF8lh4%;k|ezV&uF<*Rc4n2*T)`x4TbtSo2mJkt?VF`Temd`m^YH!X*OPgFCv*Po`hU#J zn?^qU#+rZMw6=2j=k4vbN7Rscrl-q4?^Zhe{jA*X zr_)~}4|Vz97d!p$J39UQ?k?oT(chtuNap;h{pay(V)%T_FKo2?_f=%>?*Q@;*iwg>R)7B`ceZ=qjmzWszVsQ%m0_RnF*oGT7kP8g@BezgKi|{HL%dFQ4@7Qrnl>Kl+RG|HeCfd$rQ-w}-zcr|J*p z0doA`k#_(5L|&+RUxB_wDxWXqhtOvr)2E={wO;qzw^FOP_8xt$CZ6XApQ~K;e&tfh*T>5k|Cr-p(r+QtS4owx zu?c_t$0vPxpnpdnE46+uuZin^{i*y&=2I?~y?=Rn&HEmsH{R&VSM}zb9Unh=#4+>u~OR%6K5FEgXwcccGEzmoOmBF2B`_`$3%N_BsKV12{!$XT9vz489Q z`sYfS*DK3E>u>sa^#96bfBz$MelD*zUUcP&<*~Qq+vDA1{`@l!lHYsm9ropW--ut| zDBAmE=6UmZjqNKwzcN4k(1gE!h8Gsx{*Ns$JKnRr=D2P1kmJ1@-uK?Ke);M9HvRqJ zx&xlCT07vDfA#93f!`1E zdzPm01G@e1Ie$l&U;n-q|NfHiZ#vtqbH{`4m&m>QuXXd2hxhpRk0X2i`~&;_`i9$g zx#e;Dx;wn@SLyV>Uq*f+^Zzyv`{$$bQGdS}J?QT*wSz^sJ@l!D5BTTr0lbfAe+ZfV zBkZ3hbN*g@zfT^+_K@kbe6N{)4VgX}{l6>C=cA9n{*M%=w(m-h7mo*h81|3Q52Vk; z{xEKT3F9}{)_r|MuC95%l+5y9#CToYKKhf~e@^H5nW4{i!e7tTlfJz)aoS(sP5FVR z{B-(*L->7>! z^cN4T`Sr8D;PuM&k$HYNemnF1CYOABWPHiDmnJa&JNv)aG2ZiuGyeUY-<3??m(1%g#VH?<*Du>cyx-6lTts^$ zRsS=8h|KcK`zQ03hcKQo$1~;k7W9Gmy#~iW<@luZUC3M>{XY6r^o7Wrzcl6h+s7Ne zKb3iV^#69${rtP&+tFuh^1EjI`spvxhib}aYWVts`$y*X>_-0IUVIOf`aOL(`hQ$s zFUFsyk4WyC@Xur9JvBdl-=seu^jpaE3A<|k_t%#F^Xrb9f4=4Nu9TU-nOa^dZ;|75 zPEPvmr;nJ*N2Gs8Uyk{Ry#C0{2PM;=Ol=>RPv-Tv591;4$N1H$-*fva)BgC<$0YOk z_0Rj~4f>QLv%WpR_8aR@a#Q{#b zd1s%0U$?6t$1}m-YyXh`ADQ`m^#4*!ACUQp!(IOT(zm0J$MVAR!SciTxje3qyj_2f zd4}`@nU};orJg?T%aEJKTkZGv2TtevapvhYy&s29#QqEVSN-r&==YKN{XeI7cY8mq ztII!s)5jz8_hk0ZG%lbJVD8usrWnO{erjd^e*1O9lAVtiWW!;$I#P51icG0(5k>)THweV1qY zdnu;h$Ni-bM}Kd-%;k|e{x6xwkA5c4AIIZOZ7=61)4!u%$MJSkOn;B}8`l5K`{VMt zJ!JYUGvj5~exeURrk_D(z7q44QcVAZOka{qU^t%Z(o`R3c{I!*eKOd>wae_$fUo%m&<;BGS^3@Pe|tdl+#(i zvV4z>cwd0b@s?S?rLG_Pe!PDAOTIqo8^8Saqg};$LoXb^|3zxyut6Q z+K|`WJ>>Ui_u{&{p7tzlIR5@6?*s1GJm99&|JyFp2c$o^d&T>Ie$V5RVlJQk{bc45HkSSSsIfJF zy;ctR>xF(9nLY#kMEWp1eko2JkJNOopUm+#$<4l>uRrKh@ceLn&{j=oZW&ggEOrNK?=Rj^gtH}ck{`rH;OV#hwtN#2juP-&8FPBgMk>zLYgl}JNp7zi48>jsH?AbGZ{>8KY zeaZ&>-gWrBOQ(GMm(1&(<9qY^Sw8BQ$NGo$Rf>7NZkOrvkvX1XKo7e{VPc zX9j*c@Au@CKgjzJ?`QOf*?!~oKDzARFI1NjyyCAft}iuyA^it3{T=#j^#8`{zQ3M% zZe;py9n;>&V}2l++e_wns${m0$;>|+gm1|4g~{ArPUrDVG5tU0A(H9mbyofP;dJ_Y z%&($PN1w18<72nLCnR%u+hzKZ!_uBBzs6<(c&XwvE@ zuTCHK^*zV$T{`0LkIWa`E;G-X{$DCzm(R1?W%_<(`i67JYo2P#^YiDIdAPh^@p?}A z!_4pFc&_xpn2$%ljnm2W_sF|i{P(XM-<7@>eXbO9ds4i&>nivBc0InIrT@o#IQn2$ z>i?yDL7p!%^8q=1_n^PO>>cv=*Oc#A)nVbyLw|45I& zACaeeeE%f#9JoDXu8;WL#J>++81wxV2Z#Lo4l?s|CW`+31pP5GeKa!1XHEHo+o}dh-cYOW?<=J8#qH(wLuUD9d7yvU7%RHt(>>yO2<400M`j)*%M;tD^zS)8r}O?g zitk@opV7bL{H$M@XG%YhejS%VX!;YEPw}1VVo8Gc<+A*i^T|MEZ)BmGCc=g7no4>HU;(5;J85V~9 z^YZmQ{(1YVcJCJz@IBepy?*|k1K!u#HRz}F`^V01-@fhW@cr*8|8Hlz|NTz-j4l5A z`}TeQ{aNdt>)i3#z1z3n$$R$r_CA^UiR9fae*L@ld*5%o&HIR(lSQ|EyAJ#I^X?E=EZypaG@6_+PJTiYz=K6U2n3utP zuGIRte`NliT*UbpKH$$E^Xxd@ZOVtCUqc^DJ~!P zzh6D!m(TIXxIF%z(?^gO$nrs+pYy)<%(U-c;dpMf1wTLiJTmLcRDUj~)0ZYUmVEtH zneq2;=Gic>D&+%Q@pO#;x83pm*xycWMczvLqHj;|e9%u^SoZz72sU@eoFtZ zsee6@-^o1Bxih{!d;CnrwHFQ^^X&!J2dpp1lSlpa$^0OW-c&T^ykU+`x*!Q`=H7}&*cN&N4!%1 zkK4=rVIDW1Z~1;?2<=DSpN6LW`yl3fj?{d8P%Pnn$*8}-?Hlp)U*C7NYtM0fU5>BH zd^IxtJu-bhPA7AIj^|3I|HnMHl<&vs^#3@Wyrb8DuS?(W8ce_T3iANz1Jds!)Au9O z_ahG#eR)jzejJ~;uiL->?CfU{PPUg$L%50ucRNy{6F?rY}fze@h3C?FIB#p%3Gg*p5XbT??q;Q8uQoa(=p$U zz83qF8zcUFvHy5uz_&-%kcYR@<==NLb@=x=wN~FgtHW1g{gm>nQuPP@Gv<*nKalSL_J{I#a{KB3(Klp%6`A={<7HpJlIia;kBiLt$;>yRzd`?y z^*?lwrk_=*c|W2lFR|kNp+4l<^jG}$(+486yfS}^^OJeJ$ef?~c=UZ(K3QG{2mSqO zc+|fyz4?}#-1FVze(+Yu$Bu6}J~>r&yg6QUe0bcSk3;ZZ=|9b3{AcE;Ey3^O_}par zeq@f9x>)wx%koph_|wG+-=8tk@V}=o#`DGTsOjHv`<9Vc$>o!;)c@mn#^V@InA?BL z!+rUA*3FM_<>5kO#xeax)(`ZB$KY2DV!Yo}zF!Ubi@d&?cw)kBFa1iMFV;_-&ho_k z%=uAY|Fb@zZ_V<=`kPGulztlP3;MeJ{)P1&ncGiJ-9LCfxP1DO^-L|wUci7 z`wkp*ynEem-?a;~Zh8UvjP%uaBH#UC`+a-&`Y!+emU(||@By2iH#+?L?$%bn{1%K) zoZ>yL{{0?(yQaK8Jr;AHRoZ9va{Ov;Ug? zmt^{XO+4qHxBEFh68e*vpThnkGV`b^i@raB{o(YlIQ}e|zb7*vhwEpa7yI9Nyy>TL zd&uE~i?@3>-yy4&PjIa6f#^XibBDFm%FXYtk zc|JKm_iyB&e;#1}Sc;i%#r`+?In3*uK3#P64fDcQFkUX#N2bq1KaYM-{g_|>>TzG+ zF<-29(9h5QJ}$qs>HTKKK?&FhNe)Q6+FQ4;E z{`r98Ba-O@*5w#Uh-EFlE$74Prne+4bTq!fpZbzR#-aGsK`C-0Yirad9s-s{6PPYKHqx3e;y`td1P*HqtD-8 zm?t=a@q&4MFb|Q;>xJcm?D6lDIGx9j%=Jy;{PKKE4*BO# z`hwgZ@^L)^sBeQ&xS>JFv zk2mX|6!ZMD{PFstzsvfb`Fb4BnmoMUmmhM<|Ks$YR^LA8N-*;TQ_MU<`Ug!6-;cf$ znSKPv=OoilYvP)J|KIEfdS8RS0`r0BCv*<^`$N~Tf1gGFk9mRgAu6MOdGssjOVSUa zKgRtbb9tlVe*2jZMSq6=9(^OuPad17x&ES&s{h`+>3mlFbZ#HZAM^LR`KP5 z$A{&IJ}S#6eNFmOWF8+f_xA+yGH=6pk;Mz%=PEz?5$<>&IpckgapX~+Ltfs^6D9Y1 z`gk0#mrS3H$7=-R6SI7!nE8G@|72b-%zI1mRL%Qk%)dJh|LkzN?2cb*{8QFH%#Y-F z)v0{IGV+hUk>;8BQP5SzGcej5&H6E37y8`HtL(+~d!*#g$0qXXSib1vv3xc$d~*76^z-P~ z(NAPvcgnBl{gll5lGDk|_ak%sV1D1l_ZLH5{(e5#;h#U4FMnoX#g+fU;Uk_8`8+`S zeB0&&N8R$72YB5f@Bdx3vF_$CtgU*UYB=5jU%UVx@2Xb+Jau)Oe;(xcyz~K?@6Yyg z$6jCGaQs~6=`}IN_uaGadbfYu_W6(pnEHLn@8fvFd-nPFqt!0Iy(braeX{eAZ|_`x zpy>8*Zo{_+IeskrS10DZZ^`~g_7}3hf&DY7{tAwNG&JS=cR5}em&fsdhZp_(A@*;R z`Tn2G{tx!wli7cArOfSN{{($F`egL!*gwPm7IJEQL(Wg%fX8pU$AkVwQ{Ex+^SJ-1 zl372I+5gFW4)zz9r@VhoKa9-!i1lBJ*&j~k^4T9u|Bp;xfqvh1^N=_{ z`@hNb6-sqqzjJ=_cKhF%zqF(7->2=K_U#ESe;B?G^SGF|!||EvcQgNQ{(yhKdk{YD z#u4A%r0+-WJ?Zc7UB}Qqg>O`z-R0T`Q*+)wSX%SfAM110_w?(?%->_a9+#J5)=#{j zk-0pcAGUX@v;O+0FUmYgwx1eH{`hhIWZs{7zesWF_iXQ^nA^wWN#^`4FWi3K|CoIGy>fyr1%UfYZsmUdbGPlT6?2d(FIm^LdHWo9^!z@0sI2^M09P-tXuO(g!4S z{ww8)318n%PWtu%j|Y!eW5(CFHMB3-{vkK{e(>|yej)SsJRV#hndgJ;zyH_F`iz|V zzAjb2r>67yj?Y89Uy!+c-VZkyeS2$t-ur_bznbM|qU_(tkU1VNeZT#qXnz*{`yA%Y zUEkx!gSf84`(f9#`R_sL_wCqsm22N|dMdB)N_{{6p5yP5IUXEx8}$LaLx=>IW)uhj3`>!Urs{9J?bbnTEYKg3cPC59;GC|2~QNl6?by{?zvIcq}2mko!;ni9Qjx{}9GU+U)fA8y-)t zkIea5{+qbd`$sHqEWcbI^XA5f{P|1e>(T$5L%zc_$A<&c-(>mX_;KW!LBG8`K0JS9 z&R^^D$CKA5k1y*pa>{RGeh!(}d!^sMFXi#)_OU$i{PTE_>5FpzIDQxN`#3+D*XKfq zzrMNsWR`DEPi=ospRaE?{uuKit1bS1$o|UWUjO{E7yXYdZN5E7zprDzZ*Ous$15ZA z_w)e=_oF?5@dD|S(4S(y6a7E>RrG^~C#tS}N`HcW1ecd$=JC-Nqc71j?)yi2Oa6Yw z{U_7MOZk7yU!uQ8=Ju26KQ-}~&qJ%1eE%_z|8|)^56?IK4Kmlq^UwXIKgHj3|5N^9 zYC7}Ww#(eU3i8hygZ}(1mb{-eb>Nu0UQXQl7{|AtzuEDr`jq1nW$y=^negkIX?TBg zcFOxkoK7E#ek6}4_n+s7+;n_Kd|qS&%=(J{SiSC#Cw)wwPx@rc|63^e?V)embbXh6 zUTPiV_tN*H4@lo^e8l(n%+~z!ANzg$vGu=hpj6Q-EQkIei?jyFuE@7LGo`$zeG2*20r==9GQZSDT~ zuGs0@4;%BV?)tj+koWC&96jKscW!upkGvm#ANl%&{`X}1e>;zQA92S9e8pMs|LunF zTfahz@a2d7iR7j{ z!3E!6#O-JP3j2@A>~AJ>e)d0be)i|`_uFMIpUnRJRR25sOH!OFKU_aKwfx~#|GYf1 z=KWLp8cq8L|E#*^-`{Zk>>uKEGS64){PX;z{D_nv$MLk7r@{O~<_mHA#~1wZ;q_Bp z@z*E!m&;>52AS6b$G_zMFdu~e0Q~~?kFq~C)gR9OSo(47-z788hrTlVuQ{E|YhvWh zr1r0O!rw2uuaHyy|LhMRpY-)J`}fIB`-}ef)cHwmAIIlo9w660Jm>2l`Y`0;qQ9P+ z>Oa&^Ge>;;bK!_@UoIW9v^!rc0p3M4yepo6$ zE>*v9`DEtrl35?KK4N=^K3MCb_eDG5Q*!xD_1l{N9)b6tWWEvd2~+nc9-kD`PviZS z+e=Qh54gQ#j;BrL@#XpB{?QNQ^+{%49+~am(t^LfIK6^=LvA0rKJUv1naijDM&|bM zc+oH9{hvIA`jE`+ie%ctNwYo7kPwiKahEUCXdzp^*CDf?bqS5e?Ku)^7m`5 zkL?$J@4)e=Q|*(~^7(sykHYUc$UI+7jP?|NPv4c_XRv)eG~kB@A^Zr8S_Y-8+ zU%Vgie#G{~H1e<~@%;yV(@Mp+pU1|0dv<8Z_ur=S)96#tN88ip-|x_$qrXR{??=Cn z%;mSY_{W#`7kePo)Uy%L=dAZa3-DJ*BrVm5Ej{8IA^5~b4 z>DOE-(?=sSe~x(swSND6Sn2i8m)!m)?()y4{9d2_4w*g?xoLg9{(SR%aJ*C=59Y@m z>hVEme>snDe^Z+uSS=r@wtXEh z?7#Z&*`L)uZxsy>X!}&k*Yf#yyZNKdXI(ugrYLB-%nd>e6?c{0J+WEY%caj&7?~wnH_tRfWKQZ~2 z&0g{jYW=Bp4w7%X81^DwDo>){o%w6!Gt}}+@@w*eYV#S&2kEbLPX5z_oot`O-Ms$M zUMsF&ZF!GZ;o zqy6N6{^Pel;(p3^y*W9L?SFKW2mG^_{MW&#ALWOK`Mjvj2U~i6OYKv-U-Cu0jm-C3 z-$`wMly6hZi&b_59ve@;7a8zBPDEc|5Q8e9(>hk6Ou_$@xf0*!df)efMkCjY8ymSEkmu7c(Cun@L$!YHYR6Bt^{>_P zeZ~Ky)E6_}_iR4DC(p8e9xOMbf8LP~_{+_o0# zpFYj+S5KZ~`I4S~`Y^6nEgvXPDBq_p@qvx0tgrsu@_%>z{GRjdD#stS@kX`Z@72b~ zjlY%nKjU4-3lB#5Jx1;Mt)JJUF2x(%E^lT$!tKT*)YixNx4ekj@*YnfW9K5r>r#B) zc!}pLY3uv3TK?dleSVK`d#G)H@3;Ji{9j3z{H=_4*^7kNJOU#qWJubkuG?EGqbI3KHBuesi{{J6T*|2&?2qU&L`JtBFdHKQ8_)~hmJ-*udsU0uW&IisHCGGo@e!=otYUg9M z<>k97^C7&L>lL;0`+)U@>lO73<>y#0Sbn{g>%(c*H?yoS+~4(1r<30&O4|P~xZZF* z;(F5d_jo03{k)!%cKvMq(EuYY|uzqd7}^Lv@s zr=FY6`gwfw1FQ8ve6pO+|Hi^!Yk4>Cmwep6TFd*5t4sB@znVX}!uu`d^RWpZXntP# zI{6LxKegrcvy$JsUQ9kizC*1aq5tn!Ti)ZzkCgZm{RPzK)7)9h^_F~2dnLd3$~&2V zwog9V9{vTp_-*Yi<@x1()GhcxwY-|z>)%?<_fOkjT{$1^Q}QR2hm+5sKeAx6|bPm3U%*Gr#8!w$h(U?fFXemuHiYled+RQ(Inr#`9Y`zxT)I&GARR*YjV& zf68y_59$8u?qdF5vNf0M$+?AGKP)We_8sDj_Gj;hy2AUx1KNI;cRaB^@_gHi`Ta?M zL-{m$x7CIGzUX-B@k(00(s-`pg~yXmH2y13Cl7BvXtjQU-T7=k+q0y-AD&Nbef0;F zM^o!}rxS!Wo;`!uR3;p;`)Kcf|MTb2-+lce^q-^T{eFcnyF5t#OkP$$K=mbl zo@(!x{kPKI``Ldgerv3U^xu;|E;5M^Zx9x z{iL7c!GHVtT^#Q}e@!0nCH{_$y^KFCtmpfMJeB;`)>e*Z`os0Mvpo-6$v<}5dA(io z6JNBF|I-gozE=Lv=TGhP?DH$HSLu)VJDOkD{P51NrSaME!SS%_PHf48I? z^)GFg=kR`&_=($U#!0P+OQ!~A|FU!XSr+9e;a@p1ik%VRPI5kz50l5!FIB$E^@{$i&Zlbk zFKPL|(tPIpq;~#O%S#^PpXdDQ^Psl8>m#-0ym%N(% zzvGu$KfOcz03Gkto?q?wQtF>>x4qQeQO0W>UrKz_V36~1zn|+X+g~kDwLi@H)AgA7 z=XblgKGWY$ersIqe5NiPPhL$v&GnA!jgt2KuD|978Bbh1$o6%-yCGB>yQtTHDI?{lZ$lugF(T zF68&AhiG}cXZWqC?@cBj_u156^MUe!9Wu@?{8{(KhLKhpuFD5LTPwM%;M z56jDWJ?>x9`{dX4{*>Co^0se#Hs4RZU&f0{e3!hC{%p3lTK~Dj)naP8@-Y4H~ z3;xgeom#&=`9t|iwb!GT$Ca;pNj~Nmjl4hlQ6AJYp62~Il|QXz|8#s%TYuX_?fK>Z zyncCQ`7-$}`7-_QEbs9~^Rt)6FYm9~=T~ic+t>Ty z{gMY%%j0=J)s|P=-feh6`=902)>j@-K4-WK&#|9=KPCRJ!~@EQ=%=KAlKF+rKfJV+ z-&5z-bNuOT2_i~SC{x9`J*=NslVSfeq-`fYWYUB{8CBluO(m8 zr~OKNh`ft@jQor3dC=`e`>W-t+&=6jPgdehmiIe4$ouhqFZr~0@N?(wD#!!zy9(e^bkKi^Qp@F z$!E!j$ph*qHzXhI2*1)ce4jkvxb5%rrhljXQ6Aj!&-RtimM1Lf4*sq3*lPU))$)ky zBl1P7OUEm1mrqpNzw96WA8MENzUwpp@8SBhvz*`SmuvaGzRvr}_IiF_cYUnip#8nS zmgBQLp#A&#UGjMP^QrawQ=9Ks{Tb)Gcbk0S!@K7(K74U~6Z*^1N$7iPxgK1c&-R;| z$nUo${%>k3zu!+z=J!~6J9#{hU()h_o=@%h7bdg5{=a7*-ci3p_1s+c&&9=Dzcw2g z&**n@{knLRdSR6OfblrL#~Y8U#0QV_ej2Zn|5JND>r>MD)fi9LpTu~&@nQW}^do2- zXS{IfEU#Z}JYQYn$Nt&di}7ptJNX9NPc0vzF7bcz3Tp4S+VY<7(M3LAkMYxz2T(t~ z&gXFgUeETGZz$@U%!E^Up5z^Ly`XE8FWyC-oOQ86S}U zTOq%b{tN0-e8zlG?ytXrejU$tb3U1B<#;;X&g+wRG`?+quo7Qa+HQPOe-`82YU7=1 z>#sJxZoJp{>bU%0DSqqu)aENxdwl({?Eh+chl(cuviyMaoxHm|{tA9?^5wOoTwfTE z-)!acx3{0Xr`mY8{mb^ye@cJ6Qu~+g$GH5Be2n=A&BrM(rJu0c`F~vPeB^p%<0RL| z>I$!Poa52B_0bQ>{^kD{Jpb@K*FVm0<7)pepf2%ot~b>3U?nZ@>H155-hJk0wSI`s z_h*+mzaPQB$P>CgmA@O1ztZu}=galH&x_CZ=5fxC`rD~p->ZEdec$kX!uwNtKXAL} zS8pEhe9@lHZzVp-`BXjVfmi(XZlWO@r-$&)` z+5!Py~O`5<$A#H@$w5L-a%ea9!ae~m3*B4*Kgow zw@tnpb!{%kZ~4Tn*&M&rotfO;g-?@zw0`n*@^j<*o5@Fd{LR^1|2%;&nXcvfUw=f~ zYhyZ(XZzYdYRjwTU-t12Fu$e!%l6Z+P2Q)(56Ke^mh%5zYW)|7AZyU{+-;C#<_L2uM9==x3{^xkJfj^}FhSp!+PoD0& zk?|6>$MbyhfojXEOZEGznf@X#$>%LUC0}EHKlv;DW4ib&mH1TS$;0)09x8r=_-B^* zOYir%+UHd*52$uLQOnz@9bX#D8BcP2R-Z29{B$y(<85jFmH$&4pRf4&Y~}Y0`vPk~>$}9y&EuW!r=Oxc-wFA1-Cv%|^+QR^ zU)sOa@@MMO`AXYuU+cHi&-KzqJN+U~+sQZo`-fL?fB)A{KZO2nl=sW)U9aVMtACo~ zz2mFnuj>)V1N|T6HRUZGUtM1wwUfsxwZF%g2bAAbf9(E_e|yXi@_h2wZdc3isa^m1 zJeIWcm)hfde)A{$e&Tx1|7RUElg}8e<$6iJZ#kpdX%E9#3sPUboBd$q%Y6ua^H?o6hfv=JS8ISb%YOmM$WdAt7pA7ZayU6Fk zc=N|<W;sydSIA zc|B@*2;=|q0c!Uz-9P<0 z{UPQ3^oLX%ueW{W71XvzN$YQAdHFv10JXf6eqSZ+dPTm;{^EK|UZkWwpMHjF&!<15 z=i58U`O5i0?R=@fpzDXj%UthtuJie;=*wJ>x!!O->z(BBTn`S;@_onEs}{c8J@eBjVVK@1{na%tjv(`v0kF`wx zSpDzh?ViBr$@|FzKAuV*?J4$g0U<*jdPDtU|cbjBAt#Lug zyqNr&T0Z1>F0V&kQ9VDO*JFMpc@+HvJ)ZePZ6EVr+8(x-yp8=$E#D)rR?45Mf1KLm ztL2CE2UHvHs_=jKEgAp2*+^bNeYBDMhWchJgOmQD4(gnp8k!V&-z@~^ZYlf$*btk zV||TR%6E+#d3?3kr?&p;694D(seho)zt5Z6=g;v{?f(C0Ee}}H@am4Yj)(Hgj(=)- zc6oID^Om=h|1ch|miLnH(l1c|o!Qm=p0u!@%M>Vr{^=lk$A@;CA# z@*pMuEP1F7yi)Ht=aYkjZAR3-2V>q(WsyI^N*i@ ziSqyU^KYTgnUC$S@}}0;>ya;2%NMFk{nzKq`guRBug~+i+WX=2Thj7p@_m*1;ul$} z@B4Q0eE;?C$GG2r|MBP0jwkY{&H4Pk?s%;~s@n0`=U;zD^Ov8rlSkICPwn_4Z?@ja z^^*DB9sf&Ozeag%pC|c7{T-dJY(K|Sudn1cSlVtr^iC(|6R$_z#-GyteLl?pEsw9? zZ;3B|zMbzUx0`vt-M^wYC_ko_|10Sc&+F3JWjvo7FOuJr_nUk1Cdwb&y$#*HO#b)Y z&GXnU52#<@mp3n>y!nCe@qEtX=lS_u#_#0c^uHUIpOg19U$1&@GQankKe$f*U$ymD zo8NbCGQYn)d-g2a)B4L7s&{7c`{dbnzOUB~a=lzX%>T0)Ka__vzAllMDJ-pl%UzDm52{HeB|@o3}Y#)SKdzPs^!UE-sh5}X|7GU) zEp0FHd-~;Beq}M&+qI?qo+p2&mj6>*eq1fjr(Rmg^?>AuB7#2Tb#-E z^Z4=zYV)hKX0m?fTTxq|=4`&NPtD}})!afJUw%-1I-Be3bNrcZ;Onkt^M1(xnLk+m zLw-fx#rn127uB0HIlt<^Cy%nTkn7V9{)cLL6|cwot4lnNJd(UsiTAo)Z^rzgpPqhg z`}mi6KfFHu;EvYvd#CXz^Iz(hp})u7R_5z0Y5Bl+_>TT|@@SXvL064zKkv6%K5(#_|BusOL4OhXwSF_tFYl+8 z_cQ;f)%q+-jAYQNq$T}Sp87d)^}VjpE#~|eBC4e zwd1F}w0yPN`M~*Gzb5^h9Bm#qKpP>0;jg! zXO3H)81M88RQK^u8^QZs4UXb?7rn#Kr=8wkYWclU9%}iWoz0BzFK;&Ee!cweUFctb z`#JQ>SIL8X3qSc4{EzKx{$I8JfR_jTIKOs zr2AW6{VuKVO*hAbfBW`BwD+GMehGaF|0z$`Tg&g$`u~pbpVAM{>$g9v-QV_jga7Jl zcr%|Twe|6Q@`jG*wzv9%{KabLBlG*}r>H;ka6A7WqdtJYlBZN#-uct(bAEAt^ZMi` zE${jL|A7B5Q2YOalbw8D(2v^pD~~tW$oD7zKcn{lKl&M)KfAk{$5%J{Ip21#lkb~- z@iLy@xtGcJtv=89Fa7___pATk)J+~=ZGPZ;gIqsM?Iy2#Z$8&^(|jLL%e$4dd|y#d z$8Jm36Oe*aSI|EC|}(zE9I|ex*Om???LcxWDlxor6 zpMR{DN7P@(L0BiE@XV^OX7v{gilv;JeMDw zYEH*|J-wCfufL%2&>i?Z~D2CBD%3xO{-yD}I^1ynkMw?mXZuz(JhA+Q z*Q=I4C~0{X&!<12evgC0?9a~U@;@c*`N!4rA?iwd!w<>h+J3HY)bdhl*H>-)d7Zyp zKRBN{f4W`m`blkhb!q+K`bO>k`WqhI<@b>OMfNZ2)4j_7TXe3oeD5~LyTS8j%ojVS zSzf=!tx?V|CH~L#f;^z>cl)RP-RIBe$LCG$dfNLvuD_$#r}lYpd~yCzJO8TX{nWOf z+V&n->sM=kD7Am-{mbK-ANph8ALX~z=DW6ioo`C>yW3rF>~{0{RaeUQr{ejo@N(UJ zUR^&`)+$7{}k<<>+ffM)>m`9S+C{uDu1Ehp8k5~^DXiO zb2)yM_&a$7wfn2({dOnwepy~^z8SSVh5mK&8S-D|YgBjVb3G{kr~jc^zbCKH|J$qO z|8^I$KGv_I@jEQFhwURjr*psQCEp}3C|{;74 z@#?pI_yF>O>WAn3mG6`Hbi4hf#GA^$mH59>zGnG8`(s5n@_Cd`vwr#`nooUqJ=eGL zgC5`ZDe-NVSL=W0{G@jNalBiDm(yRiG~Sf1w^z&eadoLZN_?N=x%zZ2@0Z&4w0)ef zZBOIr>KA)^@jTz{LL%5%xX$>W$WQ~pSQxcA-U8^7yx zqd$2+<+J|T`UoCEKGOD4TR;1s?Wcd1ywGTr`F+=aejn|%`?uu5zWFwJ6a5~Y|6d;E z{5?9(^@95JD7UNS1=ZGPaFF-k_Od-KKRnF-B!8&(eyV*we7^OY+a|wuf7prpqn1bX zdG~q!=}oT3YTvw$>-YC^zV>=5x}EhgzrDO;dnb8D`NxXh z&3sD!Kf(V;^|q3awmtoSmG56_dB2M0|3I$qE#GhE`&WCInct)2{p8>D%Tt&5zxu?ZsBi6A zeqWaV(=V{(-)DLGKJx+Vcc`|!{(tB2e=EcMez10&JgofRxc+(acxw41wf+sqhqG}% zjMooG$)6Z6RC_-4;&H|=)W%o!12jIVw!HCRP`Blz0C-4*I_x1kU-rf)U=jLI?=j1`=yBRN&7n<8kKMeW5 zC#yL=8c#94reDK9n*S@sr}URF-emqP<9TY!KbXt-mfHB8+W6w)Z1P*?t1`Z0JZNP( z@85PUkJoNy|9G~W@tBFd+&)FVWBI^tC%-?n_Vas~e3@E57~{jnr&s&gf9st*pIUy( z__zLcYWcm29%TD@{7U(L#^2m-{_PfguG;om+t2%LJl*o%54HTK+V-tz_&|9K$ET8( z&ym-c=Q$W<|MdR`9#5W5o=1Me>ls_a^Vxp#Kx(g7|1Nnx`FgjjEw6UIA6L8n_*m_F zcOVK2v{4t`YKcD`SX4sv|;{;5mr$JLYcm#H1)@k{=9!=rrv z8jN!NE&nOcCvUBmSJN*|{><~a9<%*jKiYrg{q!>|J^wzBYR8BDVcrk@0}lsze@f#; ziT`r`@Oa)2>+g8$c#J?$`f90}?ISPcdfD}U ziSL_!c0ay9xITCL!->zMyzBdtmJhVN?;GmIbiR+RPUZUF_apbWeSBYXf3^RQQu}`? zw|hLb?~Bum`G1$Km7HHUm$N;5KUJ6BPu*^QVR=A#Q{TU=ukUke`?uQjsaIEWeX>^1 z=dr{`43_f$!}4eH0_xgaj)&@!U!VSd@^)_bcy4!p`3LzzwfvmNm;cj`Ni7do(eQuf z|1I$|-e2<8`HTy)c>z^J@Sm^BUa1D$@{70ZOjkq_RezlM|mQ(^|@Hi z?|C8Rm-75CYWaQtbtB_puhyC|Kgs|7yqEFbKk=J- zca`y+-`~E8<9+w-*P%cB_+9A#fxq8>e*bN3|Jzp?KN{4sz3g8H^?ZMm-y4_ztMHul zd|#A*D{1*U^EInW$CKZ)ynLG4@*Yp#TWxud@Ay;X-IlYz%cnVi=s&x*lKWd;?f#AB ze8086UQg+IE922pjxUw*93I;1SC{Hn8h^YV`9HPoCx55b?@vF!gRLB2PWA`!{L4#J z_yKqW{e+7A2t1g4%(&Y6j;qb@D1WE6yjuSy`N|R>)@<*`{n+TVLhCOk-(>#X7JhE> zQu_JH19e-;kIDne>*%NF_L4uN^^*@%TfU@E4wBzEJsd^*%Fo>$ieE#ddY2Jjc@?*#6LiXOr(! z%M*Hk^qVa4oo<)El?PPY|I{8|ZF{`Ey^8j}xw{O#xt;6BPCa>~bN>IKU!mIP+wt1* z%>FFj==1Y+C;8FW`@OgxpBMc$^`Dd%S34e=UszsJUR{4VdB5gnzHe`><$70tX8q*! zoAduMXZYbcU(3sF;U6wf?EJ5Gy-?En{cUU{uheWdx z!QG9#fAW6*f2VRh>)*=$e0OmZ*DudE|1#gl%nxk&M|ZE{c=CRhS5G|8`Qzzrjwesf zbH2D&%lFs$+0=70`TlD@UHLwFzzQ!&eqVV!`M;H?`Tf-GtCJaD_x$RoPxE`V^_TB6 z|HSf4zOO7z=lA&8`TV|Te(be=zR&I)=kp`)r#61x8|3@B@tl&@Pr`Vf@jA8fK+W;B&!@9}p1_lc=ukS}wK{KL)% z^5CWQjl7xsp!1K~`Bi`2{fitgTKMHUU;eAL`F*Xw>(A|8uID%QGaez|(%8%Sv%=rP z3&{`JAJrxPN`E%<|GK{MdR?#k{8akuVZNVO-uDA}Li5|Yzx65g|Gi<3XS;)ZU$Q;b zrRUf3>eBe;{GqnLI6pYvs6C$AD*RtPc|-X<|DUC{yjtE* zE$_Fmn$P3na*i)6_2d)e!{qa}W^?@453Z!^aTyDJe%6{ zjjQFCO1i|0=vO5lqAu0f`_ov=|EI}=$dkyw3|4Y}Kd_Wr5uANC*br~N~I zPOaah+Vb*rmRE1oGM>1}{q=aBucVDHo8Q>u%frbFsx7bX*K>aA)pGoi_fyNSsZ0Ey z+WMOBv%= zXIqEQ>K-T0)*j{Y<*zFKX2WirPyaXl!PGmWgV=u;e>(ZG3J-LU^_BON7gNixsrAc~ zFDvnX_D{8ZtNg5fe1H7y*J!W*`TOsof4olK2ygdxwXIaXtFU9Uo`?-{Y6~j{Mjj-~OjIKe+ybCGGQKe^h(_N&Oxt4`{yOrPchtXMCeQ%<)}bPJgxYlN?`;4>R6rJWl^V zZb75T8^n(ZV1w{n*Ct6${%{K-X*XCBY^dP$p~ zSN}NqL$|9fU()h{wzt~*Rne!}pUodwYLC)(c{{cJvwe~GyTmJ${Qaz-{DJ3}?=U~# zUO&IL8oyq_Pi(4{-(MbY<#=VhVQTq{7$5)H@gw=SlAna-<@xmUD`}56F5h?mS@PuS z&&enDU?zDH`0_Do^J%N~Z(bec`&)OE{}1aN=KNG29fmRua^9Ct&dvXPwo7xKixY1oj#A-JIMpg?x&t><@heIQ+j^w zZ}Ow^XLHAS{};#~?DeVT@6`IS$*0;sTf>b1$`4w9uXl_5r*2pKyt}=mOXHio^ujRb zo6`RJFE14Ohy6u2iSJuj%kMApO|CcZFX#7`d$Y;& zeNH~!&nA<f+5CL2AIuNy|Ch~AV!o5*xm@r2eX~BF>w^-%CNHQi?O)n1uUF!++^&|-koS& z{ren0<>SWH*4OdR{K0B@dUb>TZT-j9<`3Rx{&YT3*WtbYUw-@l`$&HJeQJSEE%2!Y mKDEH77WmWxpIYEk3w&yUPc87N1wOUFrxy6s0{?$4@P7bls&+yE literal 0 HcmV?d00001 diff --git a/iros/feature_utils.py b/iros/feature_utils.py new file mode 100644 index 0000000..6effe43 --- /dev/null +++ b/iros/feature_utils.py @@ -0,0 +1,183 @@ +import cv +import cv2 +import math +import numpy as np +#from jds_image_proc.pcd_io import load_xyzrgb + +def automatic_find_holes(img): + #xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") + #img = rgb.copy() + + SIZEMIN = 21 + SIZEMAX = 33 + + COLMIN = 200 + COLMAX = 500 + + d_red = cv2.cv.RGB(150, 55, 65) + l_red = cv2.cv.RGB(250, 200, 200) + d_blue = cv2.cv.RGB(40, 55, 200) + + cv2.namedWindow("rgb") + cv2.imshow("rgb", img) + cv2.waitKey(10) + + gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + + detector = cv2.FeatureDetector_create('MSER') + fs = detector.detect(gray_img) + fs.sort(key = lambda x: -x.size) + + def supress(x): + for f in fs: + distx = f.pt[0] - x.pt[0] + disty = f.pt[1] - x.pt[1] + dist = math.sqrt(distx*distx + disty*disty) + if (f.size > x.size) and (dist < f.size/2): + return True + + def fil(f): + if (f.size > SIZEMIN) and (f.size < SIZEMAX) and (f.pt[0] > COLMIN) and (f.pt[0] < COLMAX): + return True + + sfs = [x for x in fs if not supress(x)] + circles = [c for c in sfs if fil(c)] + circles.sort(key = lambda c: c.pt[1], reverse=True) + + horiz_pairs = [] + diag_pairs = [] + for i in range(len(circles)/2): + horiz_pairs.append([]) + horiz_pairs[i].append(circles[2*i]) + horiz_pairs[i].append(circles[(2*i)+1]) + + for i in range(len(horiz_pairs)): + horiz_pairs[i].sort(key = lambda c: c.pt[0]) + + for i in range(len(horiz_pairs)-1): + diag_pairs.append([]) + diag_pairs[i].append(horiz_pairs[i][1]) + diag_pairs[i].append(horiz_pairs[i+1][0]) + + print 'num circles', len(circles) + print 'num horiz_pairs', len(horiz_pairs) + print 'num diag_pairs', len(diag_pairs) + + cv2.namedWindow("rgb with circles") + cv2.imshow("rgb with circles", img) + cv2.waitKey(100) + + for p in range(len(horiz_pairs)): + for c in horiz_pairs[p]: + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + cv2.imshow("rgb with circles", img) + cv2.waitKey(10) + #raw_input("Press enter for the next circle...") + + #d = 0 + #for p in range(len(diag_pairs)): + #for c in diag_pairs[p]: + #d += 1 + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + #cv2.imshow("rgb with circles", img) + #cv2.waitKey(10) + #raw_input("Circle %i. Press enter to continue..."%d) + + cv2.imshow("rgb with circles", img) + cv2.waitKey(100) + raw_input("Press enter to finish...") + cv2.destroyAllWindows() + + return horiz_pairs, diag_pairs + + + +def automatic_find_cut(img): + #xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") + #img = rgb.copy() + + SIZEMIN = 21 + SIZEMAX = 33 + + COLMIN = 200 + COLMAX = 500 + + d_red = cv2.cv.RGB(150, 55, 65) + l_red = cv2.cv.RGB(250, 200, 200) + d_blue = cv2.cv.RGB(40, 55, 200) + + cv2.namedWindow("rgb") + cv2.imshow("rgb", img) + cv2.waitKey(10) + + gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + + detector = cv2.FeatureDetector_create('MSER') + fs = detector.detect(gray_img) + fs.sort(key = lambda x: -x.size) + + def supress(x): + for f in fs: + distx = f.pt[0] - x.pt[0] + disty = f.pt[1] - x.pt[1] + dist = math.sqrt(distx*distx + disty*disty) + if (f.size > x.size) and (dist < f.size/2): + return True + + def fil(f): + if (f.size > SIZEMIN) and (f.size < SIZEMAX) and (f.pt[0] > COLMIN) and (f.pt[0] < COLMAX): + return True + + sfs = [x for x in fs if not supress(x)] + circles = [c for c in sfs if fil(c)] + circles.sort(key = lambda c: c.pt[1], reverse=True) + + horiz_pairs = [] + diag_pairs = [] + for i in range(len(circles)/2): + horiz_pairs.append([]) + horiz_pairs[i].append(circles[2*i]) + horiz_pairs[i].append(circles[(2*i)+1]) + + for i in range(len(horiz_pairs)): + horiz_pairs[i].sort(key = lambda c: c.pt[0]) + + for i in range(len(horiz_pairs)-1): + diag_pairs.append([]) + diag_pairs[i].append(horiz_pairs[i][1]) + diag_pairs[i].append(horiz_pairs[i+1][0]) + + print 'num circles', len(circles) + print 'num horiz_pairs', len(horiz_pairs) + print 'num diag_pairs', len(diag_pairs) + + cv2.namedWindow("rgb with circles") + cv2.imshow("rgb with circles", img) + cv2.waitKey(100) + + for p in range(len(horiz_pairs)): + for c in horiz_pairs[p]: + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + cv2.imshow("rgb with circles", img) + cv2.waitKey(10) + #raw_input("Press enter for the next circle...") + + #d = 0 + #for p in range(len(diag_pairs)): + #for c in diag_pairs[p]: + #d += 1 + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + #cv2.imshow("rgb with circles", img) + #cv2.waitKey(10) + #raw_input("Circle %i. Press enter to continue..."%d) + + cv2.imshow("rgb with circles", img) + cv2.waitKey(100) + raw_input("Press enter to finish...") + cv2.destroyAllWindows() + + return cut_line \ No newline at end of file From 9f74dd9aea30eff3cf919e4f5fc51be04f2151c7 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Fri, 8 Mar 2013 18:08:42 -0800 Subject: [PATCH 12/26] updates --- iros/dev/circle_finder.py | 96 +++++++++++++++++---------------- iros/dev/line_finder.py | 67 ++++++++--------------- iros/execute_suture_traj.py | 24 +++++++-- iros/feature_utils.py | 100 ++++++++--------------------------- iros/process_suture_bag.py | 102 +++++++++++++++++++++++------------- 5 files changed, 180 insertions(+), 209 deletions(-) diff --git a/iros/dev/circle_finder.py b/iros/dev/circle_finder.py index d0a71c3..a830420 100644 --- a/iros/dev/circle_finder.py +++ b/iros/dev/circle_finder.py @@ -82,10 +82,13 @@ def callback(self, event, x, y, flags, param): self.xy = (x,y) self.done = True -xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +#xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +#xyz, rgb = load_xyzrgb("suture_scene(findholescut)0.pcd") +xyz, rgb = load_xyzrgb("suture_scene(findneedle)0.pcd") img = rgb.copy() +img2 = rgb.copy() -d_red = cv2.cv.RGB(150, 55, 65) +d_red = cv2.cv.RGB(250, 55, 65) l_red = cv2.cv.RGB(250, 200, 200) d_blue = cv2.cv.RGB(40, 55, 200) @@ -93,29 +96,7 @@ def callback(self, event, x, y, flags, param): cv2.imshow("rgb", img) cv2.waitKey(10) -#rect_corners = [] - -#print colorize("click at the corners of the relevant area", 'red') - -#for i in xrange(2): - #gc = GetClick() - #cv2.setMouseCallback("rgb", gc.callback) - #while not gc.done: - #cv2.imshow("rgb", img) - #cv2.waitKey(10) - #rect_corners.append(gc.xy) - -#xy_tl = np.array(rect_corners).min(axis=0) -#xy_br = np.array(rect_corners).max(axis=0) -#cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) -#cv2.imshow("rgb", img) -#cv2.waitKey(100) - -#colmin, rowmin = xy_tl -#colmax, rowmax = xy_br -#print 'colmin,colmax', colmin, colmax - -SIZEMIN = 21 +SIZEMIN = 20 SIZEMAX = 33 COLMIN = 200 @@ -123,6 +104,10 @@ def callback(self, event, x, y, flags, param): gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) +######################################### +### MSER Detector Implementation +######################################### + detector = cv2.FeatureDetector_create('MSER') fs = detector.detect(gray_img) fs.sort(key = lambda x: -x.size) @@ -158,35 +143,56 @@ def fil(f): diag_pairs[i].append(horiz_pairs[i][1]) diag_pairs[i].append(horiz_pairs[i+1][0]) -print 'num circles', len(circles) -print 'num horiz_pairs', len(horiz_pairs) -print 'num diag_pairs', len(diag_pairs) +#print 'num circles', len(circles) +#print 'num horiz_pairs', len(horiz_pairs) +#print 'num diag_pairs', len(diag_pairs) -cv2.namedWindow("rgb with circles") -cv2.imshow("rgb with circles", img) +cv2.namedWindow("rgb with MSER circles") +cv2.imshow("rgb with MSER circles", img) cv2.waitKey(100) -#n = 0 -#for p in range(len(horiz_pairs)): - #for c in horiz_pairs[p]: - #n += 1 +n = 0 +for p in range(len(horiz_pairs)): + for c in horiz_pairs[p]: + n += 1 + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) + cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) + cv2.imshow("rgb with MSER circles", img) + cv2.waitKey(10) + #raw_input("Circle %i. Press enter to continue..."%n) + +#d = 0 +#for p in range(len(diag_pairs)): + #for c in diag_pairs[p]: + #d += 1 #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) #cv2.imshow("rgb with circles", img) #cv2.waitKey(10) - #raw_input("Circle %i. Press enter to continue..."%n) + #raw_input("Circle %i. Press enter to continue..."%d) + + +######################################### +### Hough Transform Implementation +######################################### +#cv2.HoughCircles(image, method, dp, minDist[, circles[, param1[, param2[, minRadius[, maxRadius]]]]]) +#circles = cv2.HoughCircles(img,cv2.cv.CV_HOUGH_GRADIENT,1,10,param1=100,param2=30,minRadius=5,maxRadius=20) +#for i in circles[0,:]: + #cv2.circle(cimg,(i[0],i[1]),i[2],(0,255,0),1) -d = 0 -for p in range(len(diag_pairs)): - for c in diag_pairs[p]: - d += 1 - cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) - cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) - cv2.imshow("rgb with circles", img) - cv2.waitKey(10) - raw_input("Circle %i. Press enter to continue..."%d) +circles = cv2.HoughCircles(gray_img, cv.CV_HOUGH_GRADIENT, 1, 50, param1=240, param2=20, minRadius=10, maxRadius=30) +circles = np.uint16(np.around(circles)) + +for c in circles[0,:]: + cv2.circle(img2, (c[0], c[1]), c[2], d_red, 2, cv2.CV_AA) + cv2.circle(img2, (c[0], c[1]), c[2], d_blue, 1, cv2.CV_AA) + +cv2.namedWindow("rgb with hough circles") +cv2.imshow("rgb with hough circles", img2) +cv2.waitKey(100) + -cv2.imshow("rgb with circles", img) +cv2.imshow("rgb with hough circles", img2) cv2.waitKey(100) raw_input("Press enter to finish...") cv2.destroyAllWindows() diff --git a/iros/dev/line_finder.py b/iros/dev/line_finder.py index 6681d09..f52207a 100644 --- a/iros/dev/line_finder.py +++ b/iros/dev/line_finder.py @@ -5,71 +5,48 @@ from jds_image_proc.pcd_io import load_xyzrgb from jds_utils.colorize import colorize -class GetClick: - xy = None - done = False - def callback(self, event, x, y, flags, param): - if self.done: - return - elif event == cv2.EVENT_LBUTTONDOWN: - self.xy = (x,y) - self.done = True - -xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +#xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") +#xyz, rgb = load_xyzrgb("suture_scene(findholescut)0.pcd") +xyz, rgb = load_xyzrgb("suture_scene(findneedle)0.pcd") img = rgb.copy() +img2 = rgb.copy() +gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) d_red = cv2.cv.RGB(150, 55, 65) l_red = cv2.cv.RGB(250, 200, 200) d_blue = cv2.cv.RGB(40, 55, 200) +clr = cv2.cv.RGB(0, 0, 0) cv2.namedWindow("rgb") cv2.imshow("rgb", img) cv2.waitKey(10) -#rect_corners = [] - -#print colorize("click at the corners of the relevant area", 'red') - -#for i in xrange(2): - #gc = GetClick() - #cv2.setMouseCallback("rgb", gc.callback) - #while not gc.done: - #cv2.imshow("rgb", img) - #cv2.waitKey(10) - #rect_corners.append(gc.xy) -#xy_tl = np.array(rect_corners).min(axis=0) -#xy_br = np.array(rect_corners).max(axis=0) -#cv2.rectangle(img, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) -#cv2.imshow("rgb", img) -#cv2.waitKey(100) +#cv2.HoughLinesP(image, rho, theta, threshold[, lines[, minLineLength[, maxLineGap]]]) lines +#cv2.HoughLinesP( img, lines, 1, CV_PI/180, 80, 30, 10 ) -#colmin, rowmin = xy_tl -#colmax, rowmax = xy_br -#print 'colmin,colmax', colmin, colmax +edges = cv2.Canny(gray_img, 80, 240) +cv2.imshow("edges", edges) +cv2.waitKey(100) -SIZEMIN = 21 -SIZEMAX = 33 +lines = cv2.HoughLinesP(edges, 1, cv.CV_PI/360, 1, minLineLength = 50, maxLineGap = 5) -COLMIN = 200 -COLMAX = 500 +vert_lines = [l for l in lines[0] if (math.atan2(abs(l[0] - l[2]) , abs(l[1] - l[3])) == 0.0)] + +for l in vert_lines: + cv2.line(img, (l[0], l[1]), (l[2], l[3]), clr, 2) -gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) +#cv2.line(img, (vert_lines[0][0], vert_lines[0][1]), (vert_lines[0][2], vert_lines[0][3]), clr, 2) -#cv2.HoughLinesP(image, rho, theta, threshold[, lines[, minLineLength[, maxLineGap]]]) lines -#cv2.HoughLinesP( img, lines, 1, CV_PI/180, 80, 30, 10 ) -edges = cv2.Canny(gray_img, 80, 120) -lines = cv2.HoughLinesP(edges, 1, math.pi/2, 2, None, 30, 1); +cv2.imshow("rgb with vertical lines", img) +cv2.waitKey(100) - for l in lines[0]: - cv2.line(img, (l[0], l[1]), (l[2], l[3]), d_red, 2) - cv2.imshow("rgb with lines", img) - cv2.waitKey(10) - #raw_input("Circle %i. Press enter to continue..."%d) + cv2.line(img2, (l[0], l[1]), (l[2], l[3]), clr, 2) -cv2.imshow("rgb with lines", img) +cv2.imshow("rgb with all lines", img2) cv2.waitKey(100) + raw_input("Press enter to finish...") cv2.destroyAllWindows() diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 5b65590..4e085ee 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -227,7 +227,7 @@ def get_holes_cut_cloud(listener): def get_needle_clouds(listener): xyz_tfs = [] rgb_plots = [] - num_clouds = 30 + num_clouds = 10 if args.cloud_topic == 'test': num_clouds = 5 @@ -479,10 +479,24 @@ def keyfunc(fname): ################################################ - - - best_left_path = plan_follow_traj(robot, "rightarm", left_hmats, ds_traj[:,:7]) - best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:]) + brett.update_rave() + + leftarm_inds = robot.GetManipulator("leftarm").GetArmIndices() + rightarm_inds = robot.GetManipulator("rightarm").GetArmIndices() + + def remove_winding(arm_traj, current_arm_vals): + arm_traj = arm_traj.copy() + for i in [2,4,6]: + dof_jump = current_arm_vals[i] - arm_traj[0,i] + winds = np.round(dof_jump / (2*np.pi)) + if winds > 0: print "unwound joint %i by 2pi*%i"%(i,winds) + arm_traj[:,i] += winds * 2 * np.pi + return arm_traj + + trajoptpy.SetInteractive(False) + + best_left_path = plan_follow_traj(robot, "leftarm", left_hmats, remove_winding(ds_traj[:,:7], robot.GetDOFValues(leftarm_inds))) + best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, remove_winding(ds_traj[:,7:], robot.GetDOFValues(rightarm_inds))) left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) diff --git a/iros/feature_utils.py b/iros/feature_utils.py index 6effe43..9c86141 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -4,7 +4,7 @@ import numpy as np #from jds_image_proc.pcd_io import load_xyzrgb -def automatic_find_holes(img): +def automatic_find_holes(img, task): #xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") #img = rgb.copy() @@ -89,8 +89,13 @@ def fil(f): cv2.waitKey(100) raw_input("Press enter to finish...") cv2.destroyAllWindows() - - return horiz_pairs, diag_pairs + + if task == 'InterruptedSuture': + return horiz_pairs + elif task == 'RunningSuture': + return diag_pairs + else: + return None @@ -98,86 +103,27 @@ def automatic_find_cut(img): #xyz, rgb = load_xyzrgb("suture_scene(holes).pcd") #img = rgb.copy() - SIZEMIN = 21 - SIZEMAX = 33 - - COLMIN = 200 - COLMAX = 500 - - d_red = cv2.cv.RGB(150, 55, 65) - l_red = cv2.cv.RGB(250, 200, 200) - d_blue = cv2.cv.RGB(40, 55, 200) - - cv2.namedWindow("rgb") - cv2.imshow("rgb", img) - cv2.waitKey(10) - gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + edges = cv2.Canny(gray_img, 80, 240) + cv2.imshow("edges", edges) + cv2.waitKey(100) - detector = cv2.FeatureDetector_create('MSER') - fs = detector.detect(gray_img) - fs.sort(key = lambda x: -x.size) - - def supress(x): - for f in fs: - distx = f.pt[0] - x.pt[0] - disty = f.pt[1] - x.pt[1] - dist = math.sqrt(distx*distx + disty*disty) - if (f.size > x.size) and (dist < f.size/2): - return True - - def fil(f): - if (f.size > SIZEMIN) and (f.size < SIZEMAX) and (f.pt[0] > COLMIN) and (f.pt[0] < COLMAX): - return True - - sfs = [x for x in fs if not supress(x)] - circles = [c for c in sfs if fil(c)] - circles.sort(key = lambda c: c.pt[1], reverse=True) - - horiz_pairs = [] - diag_pairs = [] - for i in range(len(circles)/2): - horiz_pairs.append([]) - horiz_pairs[i].append(circles[2*i]) - horiz_pairs[i].append(circles[(2*i)+1]) - - for i in range(len(horiz_pairs)): - horiz_pairs[i].sort(key = lambda c: c.pt[0]) + lines = cv2.HoughLinesP(edges, 1, cv.CV_PI/360, 1, minLineLength = 50, maxLineGap = 5) - for i in range(len(horiz_pairs)-1): - diag_pairs.append([]) - diag_pairs[i].append(horiz_pairs[i][1]) - diag_pairs[i].append(horiz_pairs[i+1][0]) - - print 'num circles', len(circles) - print 'num horiz_pairs', len(horiz_pairs) - print 'num diag_pairs', len(diag_pairs) + vert_lines = [l for l in lines[0] if (math.atan2(abs(l[0] - l[2]) , abs(l[1] - l[3])) == 0.0)] + + for l in vert_lines: + cv2.line(img, (l[0], l[1]), (l[2], l[3]), clr, 2) - cv2.namedWindow("rgb with circles") - cv2.imshow("rgb with circles", img) - cv2.waitKey(100) + #cv2.imshow("rgb with vertical lines", img) + #cv2.waitKey(100) - for p in range(len(horiz_pairs)): - for c in horiz_pairs[p]: - cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) - cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) - cv2.imshow("rgb with circles", img) - cv2.waitKey(10) - #raw_input("Press enter for the next circle...") - - #d = 0 - #for p in range(len(diag_pairs)): - #for c in diag_pairs[p]: - #d += 1 - #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_red, 2, cv2.CV_AA) - #cv2.circle(img, (int(c.pt[0]), int(c.pt[1])), int(c.size/2), d_blue, 1, cv2.CV_AA) - #cv2.imshow("rgb with circles", img) - #cv2.waitKey(10) - #raw_input("Circle %i. Press enter to continue..."%d) + for l in lines[0]: + cv2.line(img, (l[0], l[1]), (l[2], l[3]), clr, 2) - cv2.imshow("rgb with circles", img) + cv2.imshow("rgb with all lines", img) cv2.waitKey(100) - raw_input("Press enter to finish...") - cv2.destroyAllWindows() + + cut_line = vert_line[0] return cut_line \ No newline at end of file diff --git a/iros/process_suture_bag.py b/iros/process_suture_bag.py index d1da7cc..13351e0 100644 --- a/iros/process_suture_bag.py +++ b/iros/process_suture_bag.py @@ -22,6 +22,7 @@ import numpy as np import cv2 import simple_clicker as sc +import feature_utils as fu # find data files, files to save to SAVE_TRAJ = False @@ -135,16 +136,9 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): # determine which keypoints matter for each segment based on user input print 'getting all look_time point clouds...' look_clouds = bp.get_transformed_clouds(bag, look_times) -print 'saving look_time point clouds...' -import cloudprocpy -#grabber=cloudprocpy.CloudGrabber() -#for i in range(SEGNUM): - #xyzrgb = look_clouds[i].getXYZRGB() - #look_clouds[i].save("suture_scene(look_cloud%s).pcd"%i) -#raw_input("saved point clouds. press enter to continue") window_name = "Find Keypoints" - +keypt_list = ['lh','rh','ct', 'ne', 'nt', 'ntt', 'auto'] keypoints_locations = [] keypoints_names = [] @@ -155,90 +149,124 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): while (True): sc.show_pointclouds(look_clouds[s], window_name) - kp = raw_input('which key points are important for this segment? choices are: {hc, ne, nt, ntt}. (please only enter one key point at a time): ') + kp = raw_input("which key points are important for this segment? choices are: " + str(keypt_list) + ". (please only enter one key point at a time): ") - if kp not in ['hc', 'ne', 'nt', 'ntt']: + if kp not in keypt_list: print 'incorrect input. try again!' continue + + elif kp == 'auto': + print colorize("Looking for Holes and Cut automatically...", 'green', bold=True) + + xyz_tf = look_clouds[s][0].copy() + rgb_plot = look_clouds[s][1].copy() + xyz_tf[np.isnan(xyz_tf)] = -2 + + holes = fu.automatic_find_holes(rgb_plot, args.task) + + elif kp == 'lh': + print colorize("Looking for Left Hole...", 'green', bold=True) + + xyz_tf = look_clouds[s][0].copy() + rgb_plot = look_clouds[s][1].copy() + xyz_tf[np.isnan(xyz_tf)] = -2 + np.save(pcf + 'seg%s_lh_xyz_tf.npy'%s, xyz_tf) + np.save(pcf + 'seg%s_lh_rgb_pl.npy'%s, rgb_plot) + + hole_loc = sc.find_hole('left_hole', xyz_tf, rgb_plot, window_name) + keypt_locs.append(hole_loc) + keypt_names.append('left_hole') - elif kp == 'hc': - look_for_holecut_times = [] - look_for_holecut_times.append(look_times[s]) - print colorize("Looking for Holes and Cut...", 'green', bold=True) + elif kp == 'rh': + print colorize("Looking for Right Hole...", 'green', bold=True) + + xyz_tf = look_clouds[s][0].copy() + rgb_plot = look_clouds[s][1].copy() + xyz_tf[np.isnan(xyz_tf)] = -2 + np.save(pcf + 'seg%s_rh_xyz_tf.npy'%s, xyz_tf) + np.save(pcf + 'seg%s_rh_rgb_pl.npy'%s, rgb_plot) + + hole_loc = sc.find_hole('right_hole', xyz_tf, rgb_plot, window_name) + keypt_locs.append(hole_loc) + keypt_names.append('right_hole') + + elif kp == 'ct': + print colorize("Looking for Cut...", 'green', bold=True) xyz_tf = look_clouds[s][0].copy() rgb_plot = look_clouds[s][1].copy() - np.save(pcf + 'seg%s_xyz_tf.npy'%s, xyz_tf) - np.save(pcf + 'seg%s_rgb_plot.npy'%s, rgb_plot) + xyz_tf[np.isnan(xyz_tf)] = -2 + np.save(pcf + 'seg%s_ct_xyz_tf.npy'%s, xyz_tf) + np.save(pcf + 'seg%s_ct_rgb_pl.npy'%s, rgb_plot) - hole1_loc, hole2_loc, tcut_loc, mcut_loc, bcut_loc = sc.find_holes_cut(xyz_tf, rgb_plot, window_name) - keypt_locs.append(hole1_loc) - keypt_locs.append(hole2_loc) + tcut_loc, mcut_loc, bcut_loc = sc.find_cut(xyz_tf, rgb_plot, window_name) keypt_locs.append(tcut_loc) keypt_locs.append(mcut_loc) keypt_locs.append(bcut_loc) - keypt_names.append('holes_and_cut') - - del look_for_holecut_times + keypt_names.append('cut') elif kp == 'ne': xyz_tfs = [] rgb_plots = [] - look_for_needle_times = [] + needle_look_times = [] num_clouds = 15 for t in range(num_clouds): - look_for_needle_times.append(look_times[s] + t) + needle_look_times.append(look_times[s] + t) print colorize("Looking for Needle End...", 'green', bold=True) print 'getting the needle point clouds...' - needle_clouds = bp.get_transformed_clouds(bag, look_for_needle_times) + needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) for i in range(num_clouds): xyz_tfs.append(needle_clouds[i][0].copy()) rgb_plots.append(needle_clouds[i][1].copy()) - np.save(pcf + 'seg%s_xyz_tfs.npy'%s, xyz_tfs) - np.save(pcf + 'seg%s_rgb_plots.npy'%s, rgb_plots) + xyz_tfs[i][np.isnan(xyz_tfs[i])] = -2 + np.save(pcf + 'seg%s_ne_xyz_tfs.npy'%s, xyz_tfs) + np.save(pcf + 'seg%s_ne_rgb_pls.npy'%s, rgb_plots) needle_loc = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) keypt_locs.append(needle_loc) keypt_names.append('needle_end') - del look_for_needle_times + del needle_look_times del xyz_tfs del rgb_plots elif kp in ['nt', 'ntt']: xyz_tfs = [] rgb_plots = [] - look_for_needle_times = [] - num_clouds = 10 + needle_look_times = [] + num_clouds = 15 for t in range(num_clouds): - look_for_needle_times.append(look_times[s] + t) + needle_look_times.append(look_times[s] + t) print colorize("Looking for Needle Tip...", 'green', bold=True) print 'getting the needle point clouds...' - needle_clouds = bp.get_transformed_clouds(bag, look_for_needle_times) + needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) for i in range(num_clouds): xyz_tfs.append(needle_clouds[i][0].copy()) rgb_plots.append(needle_clouds[i][1].copy()) - np.save(pcf + 'seg%s_xyz_tfs.npy'%s, xyz_tfs) - np.save(pcf + 'seg%s_rgb_plots.npy'%s, rgb_plots) + xyz_tfs[i][np.isnan(xyz_tfs[i])] = -2 needle_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) if kp == 'nt': keypt_locs.append(needle_loc) - keypt_names.append('needle_tip') + keypt_names.append('needle_tip') + np.save(pcf + 'seg%s_nt_xyz_tfs.npy'%s, xyz_tfs) + np.save(pcf + 'seg%s_nt_rgb_pls.npy'%s, rgb_plots) else: keypt_locs.append((0,0,0)) keypt_names.append('empty') np.save(kpf + '_needle_world_loc.npy', needle_loc) - - del look_for_needle_times + np.save(pcf + 'seg%s_ntt_xyz_tfs.npy'%s, xyz_tfs) + np.save(pcf + 'seg%s_ntt_rgb_pls.npy'%s, rgb_plots) + + del needle_look_times del xyz_tfs del rgb_plots From 33913cc95274504f8469e0c520f82c4280d69ae8 Mon Sep 17 00:00:00 2001 From: John Schulman Date: Sat, 9 Mar 2013 00:26:18 -0800 Subject: [PATCH 13/26] self collision avoidance --- iros/execute_suture_traj.py | 14 +++++++++++--- iros/follow_pose_traj.py | 1 + 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 5b65590..d151a8e 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -248,7 +248,7 @@ def get_needle_clouds(listener): return xyz_tfs, rgb_plots -def plan_follow_traj(robot, manip_name, new_hmats, old_traj): +def plan_follow_traj(robot, manip_name, new_hmats, old_traj, other_manip_name = None, other_manip_traj = None): n_steps = len(new_hmats) assert old_traj.shape[0] == n_steps @@ -280,6 +280,10 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj): "data":[x.tolist() for x in init_traj] } } + if other_manip_name is not None: + request["scene_states"] = [] + other_dof_inds = robot.GetManipulator(other_manip_name).GetArmIndices() + poses = [openravepy.poseFromMatrix(hmat) for hmat in new_hmats] for (i_step,pose) in enumerate(poses): @@ -292,6 +296,9 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj): "timestep":i_step } }) + if other_manip_name is not None: + request["scene_states"].append( + {"timestep": i_step, "obj_states": [{"name": "pr2", "dof_vals":other_manip_traj[i], "dof_inds":other_dof_inds}] }) s = json.dumps(request) @@ -390,6 +397,7 @@ def keyfunc(fname): nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) exec_keypts.append(nl) + T_g_n = np.linalg.inv(T_w_g).dot(T_w_n) elif demo_keypts_names[s][k] in ['needle_tip', 'empty']: @@ -481,8 +489,8 @@ def keyfunc(fname): ################################################ - best_left_path = plan_follow_traj(robot, "rightarm", left_hmats, ds_traj[:,:7]) - best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:]) + best_left_path = plan_follow_traj(robot, "leftarm", left_hmats, ds_traj[:,:7]) + best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:], "leftarm", best_left_path) left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py index 1b48265..07b46ac 100644 --- a/iros/follow_pose_traj.py +++ b/iros/follow_pose_traj.py @@ -148,6 +148,7 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj): "data":[x.tolist() for x in init_traj] } } + poses = [openravepy.poseFromMatrix(hmat) for hmat in new_hmats] for (i_step,pose) in enumerate(poses): From 328adeac3283dbb2a6ad07ac14a30578ee5dccae Mon Sep 17 00:00:00 2001 From: John Schulman Date: Sat, 9 Mar 2013 09:53:46 -0800 Subject: [PATCH 14/26] minor --- iros/execute_suture_traj.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index d151a8e..d5473cc 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -319,6 +319,9 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj, other_manip_name = demo_keypts_names = np.load(osp.join(IROS_DATA_DIR, kpf + "_keypoints_names.npy")) demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf + "_needle_world_loc.npy")) +needletip = openravepy.RaveCreateKinBody(env, "") +needletip.SetName("needletip") + def keyfunc(fname): return int(osp.basename(fname).split("_")[0][6:]) # sort files with names like pt1_larm.npy @@ -397,7 +400,6 @@ def keyfunc(fname): nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) exec_keypts.append(nl) - T_g_n = np.linalg.inv(T_w_g).dot(T_w_n) elif demo_keypts_names[s][k] in ['needle_tip', 'empty']: From 58cd2000c9b17b43714afd0c2b6cc215c7d72331 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Sat, 9 Mar 2013 11:50:32 -0800 Subject: [PATCH 15/26] cv stuff --- iros/feature_utils.py | 44 ++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 43 insertions(+), 1 deletion(-) diff --git a/iros/feature_utils.py b/iros/feature_utils.py index 9c86141..0dd545a 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -2,6 +2,8 @@ import cv2 import math import numpy as np +import os +import os.path as osp #from jds_image_proc.pcd_io import load_xyzrgb def automatic_find_holes(img, task): @@ -126,4 +128,44 @@ def automatic_find_cut(img): cut_line = vert_line[0] - return cut_line \ No newline at end of file + return cut_line + + +######################################### +### feature matching +######################################### +IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") +task1 = 'InterruptedSuture5' +task2 = 'InterruptedSuture6' +pcf1 = osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt0seg2_lh_rgb_pl.npy') +pcf2 = osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt0seg2_lh_rgb_pl.npy') + +kpf1 = osp.join(IROS_DATA_DIR, 'key_points', task1) +kpf2 = osp.join(IROS_DATA_DIR, 'key_points', task2) + +rgb1 = np.load(pcf1) +rgb2 = np.load(pcf2) + +kpts1 = np.load(kpf1 + '/pt0_keypoints.npy') +kpts2 = np.load(kpf2 + '/pt0_keypoints.npy') +kpts_names1 = np.load(kpf1 + '/pt0_keypoints_names.npy') +kpts_names2 = np.load(kpf2 + '/pt0_keypoints_names.npy') + +for n in range(len(kpts_names1)): + if kpts_names1[n] == ['left_hole', 'right_hole', 'cut']: + kps1 = kpts1[n] + break + +for n in range(len(kpts_names2)): + if kpts_names2[n] == ['left_hole', 'right_hole', 'cut']: + kps2 = kpts2[n] + break + +print 'rgb1 kps', kps1 +print 'rgb2 kps', kps2 + +cv2.imshow("rgb1", rgb1) +cv2.waitKey(100) + +cv2.imshow("rgb2", rgb2) +cv2.waitKey(100) \ No newline at end of file From d2637d4f36ae066bd8fa221f3ae6ccc5fef70386 Mon Sep 17 00:00:00 2001 From: John Schulman Date: Sat, 9 Mar 2013 11:51:18 -0800 Subject: [PATCH 16/26] start generalizing ee frames --- experiments/brute_force_matching.py | 0 iros/execute_suture_traj.py | 29 ++++++++++++++++++++--------- iros/suture_demos++.yaml | 0 3 files changed, 20 insertions(+), 9 deletions(-) create mode 100644 experiments/brute_force_matching.py create mode 100644 iros/suture_demos++.yaml diff --git a/experiments/brute_force_matching.py b/experiments/brute_force_matching.py new file mode 100644 index 0000000..e69de29 diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index d5473cc..c01dc17 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -104,6 +104,10 @@ def transform_hmats(f, hmats): tf_hmats[:,:3,3] = newpts_mg return tf_hmats +def translation_matrix(xyz): + out = np.eye(4) + out[:3,3] = xyz + def adaptive_resample(x, tol, max_change=None, min_steps=3): """ resample original signal with a small number of waypoints so that the the sparsely sampled function, @@ -248,7 +252,7 @@ def get_needle_clouds(listener): return xyz_tfs, rgb_plots -def plan_follow_traj(robot, manip_name, new_hmats, old_traj, other_manip_name = None, other_manip_traj = None): +def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_manip_name = None, other_manip_traj = None): n_steps = len(new_hmats) assert old_traj.shape[0] == n_steps @@ -292,7 +296,7 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj, other_manip_name = "params":{ "xyz":pose[4:7].tolist(), "wxyz":pose[0:4].tolist(), - "link":"%s_gripper_tool_frame"%manip_name[0], + "link":ee_link, "timestep":i_step } }) @@ -362,6 +366,11 @@ def keyfunc(fname): num_kps = len(demo_keypts_names[s]) exec_keypts = [] + # this is the frame whose trajectory we'll adapt to the new situation + # in some segments it's the needle tip + left_ee_link = "l_gripper_tool_frame" + right_ee_link = "r_gripper_tool_frame" + for k in range(num_kps): print colorize("Key point from demo is: " + demo_keypts_names[s][k] + ". Looking for this key point now...", 'green', bold=True) @@ -415,9 +424,11 @@ def keyfunc(fname): nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - if demo_keypts_names[s][k] == 'empty': + if demo_keypts_names[s][k] == 'empty': # this is segment where robot looks for tip exec_needle_tip_loc = nl exec_keypts.append((0,0,0)) + needletip.SetTransform(translation_matrix(nl)) + robot.Grab(needletip) else: exec_keypts.append(nl) @@ -467,8 +478,8 @@ def keyfunc(fname): for row in ds_traj: robot.SetActiveDOFValues(row) - left_hmats.append(robot.GetLink("l_gripper_tool_frame").GetTransform()) - right_hmats.append(robot.GetLink("r_gripper_tool_frame").GetTransform()) + left_hmats.append(robot.GetLink(left_ee_link).GetTransform()) + right_hmats.append(robot.GetLink(right_ee_link).GetTransform()) left_hmats_old = left_hmats left_hmats = transform_hmats(f, left_hmats) @@ -491,8 +502,8 @@ def keyfunc(fname): ################################################ - best_left_path = plan_follow_traj(robot, "leftarm", left_hmats, ds_traj[:,:7]) - best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:], "leftarm", best_left_path) + best_left_path = plan_follow_traj(robot, "leftarm", left_ee_link, left_hmats, ds_traj[:,:7]) + best_right_path = plan_follow_traj(robot, "rightarm", right_ee_link, right_hmats, ds_traj[:,7:], "leftarm", best_left_path) left_diffs = np.abs(best_left_path[1:] - best_left_path[:-1]) @@ -514,8 +525,8 @@ def keyfunc(fname): for (i,row) in enumerate(joint_traj): print "step",i robot.SetActiveDOFValues(row) - lhandle = env.drawarrow(robot.GetLink("l_gripper_tool_frame").GetTransform()[:3,3], left_hmats[i][:3,3]) - rhandle = env.drawarrow(robot.GetLink("r_gripper_tool_frame").GetTransform()[:3,3], right_hmats[i][:3,3]) + lhandle = env.drawarrow(robot.GetLink(left_ee_link).GetTransform()[:3,3], left_hmats[i][:3,3]) + rhandle = env.drawarrow(robot.GetLink(right_ee_link).GetTransform()[:3,3], right_hmats[i][:3,3]) viewer.Idle() else: from brett2 import trajectories diff --git a/iros/suture_demos++.yaml b/iros/suture_demos++.yaml new file mode 100644 index 0000000..e69de29 From 405c942745bb553f1e9128599f550d4e54419f39 Mon Sep 17 00:00:00 2001 From: John Schulman Date: Sat, 9 Mar 2013 13:13:23 -0800 Subject: [PATCH 17/26] more detailed yaml sketch --- experiments/discrete_matching.py | 31 ++++++++++++++ iros/feature_utils.py | 3 ++ iros/suture_demos++.yaml | 72 ++++++++++++++++++++++++++++++++ 3 files changed, 106 insertions(+) create mode 100644 experiments/discrete_matching.py diff --git a/experiments/discrete_matching.py b/experiments/discrete_matching.py new file mode 100644 index 0000000..ffa8f95 --- /dev/null +++ b/experiments/discrete_matching.py @@ -0,0 +1,31 @@ +import scipy.spatial.distance as ssd +from trajoptpy.kin_utils import shortest_paths +def match(xfeat_nk, xpos_nd, yfeat_mk, ypos_md, feature_metric = "euclidean", feature_coeff = 1, direction_metric = "cosine"): + """ + M > N + return list of length N + """ + N,K = x_nk.shape + D = xpos_nk.shape[1] + M = yfeat_mk.shape[0] + + assert xfeat_nk.shape == (N,K) + assert xpos_nk.shape == (N,D) + assert yfeat_mk.shape == (M,K) + assert ypos_md.shape == (M,D) + + nodecosts_nm = ssd.cdist(xfeat_nk, yfeat_mk, metric = feature_metric) * feature_coeff + edgecosts_nmm = np.empty((N-1,M,M)) + for n in xrange(N-1): + dir_d = xpos_nd[n+1] - xpos_nd[n] + dir_mmd = ypos_md[:,None,:] - ypos_md[None,:,:] + dir_mm_d = dir_mmd.reshape(M*M,D) + dists_mm_1 = ssd.cdist(dir_mm_d, dir_d, metric = direction_metric) + edgecosts_nmm[n] = dists_mm_1[:,0].reshape(M,M) + + paths_mn, costs_m = shortest_paths(nodecosts_nm, edgecosts_nmm) + best_path = paths_mn[np.argmin(costs_m)] + return best_path + + + \ No newline at end of file diff --git a/iros/feature_utils.py b/iros/feature_utils.py index 0dd545a..be4293b 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -140,6 +140,9 @@ def automatic_find_cut(img): pcf1 = osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt0seg2_lh_rgb_pl.npy') pcf2 = osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt0seg2_lh_rgb_pl.npy') +xyz1 = osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt0seg2_lh_xyz_tf.npy') +xyz2 = osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt0seg2_lh_xyz_tf.npy') + kpf1 = osp.join(IROS_DATA_DIR, 'key_points', task1) kpf2 = osp.join(IROS_DATA_DIR, 'key_points', task2) diff --git a/iros/suture_demos++.yaml b/iros/suture_demos++.yaml index e69de29..cf84962 100644 --- a/iros/suture_demos++.yaml +++ b/iros/suture_demos++.yaml @@ -0,0 +1,72 @@ +#segment#: +# hole1 center: (x y z) +# hole2 center: (x y z) +# top of cut: (x y z) +# middle of cut: (x y z) +# bottom of cut: (x y z) +# needle tip: (x y z) + +InterruptedSuture1: + pierce: + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg1.bag + db_file: pierce.hd5 + pt_num: 0 + seg_num: 8 + +InterruptedSuture2: + pierce: + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg2.bag + db_file: pierce.hd5 + pt_num: 0 + seg_num: 9 + +InterruptedSuture3: + pierce: + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg3.bag + db_file: pierce.hd5 + pt_num: 0 + seg_num: 7 + +InterruptedSuture4: + pierce: + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg4.bag + db_file: pierce.hd5 + pt_num: 0 + seg_num: 7 + +InterruptedSuture5: + pierce: + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg5.bag + db_file: pierce.hd5 + pt_num: 0 + seg_num: + +InterruptedSuture6: +# pierce: +# demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg6.bag +# db_file: pierce.hd5 +# pt_num: 0 +# seg_num: 8 + + - part_name: pierce + segments: + - description: grab needle + - description + - kp_depends: x y z + kp_extract: a b c + left_ee: asdf + - kp_depends: x y z + kp_extract: a b c + left_ee: asdf + - kp_depends: x y z + kp_extract: a b c + left_ee: asdf + - kp_depends: x y z + kp_extract: a b c + left_ee: asdf + - kp_depends: x y z + kp_extract: a b c + left_ee: asdf + + + - part_name: two_loop_knot \ No newline at end of file From 2b7d54021c1571ff30c23f1399fd9b1c421c0c18 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Sat, 9 Mar 2013 14:03:14 -0800 Subject: [PATCH 18/26] updates --- iros/execute_suture_traj.py | 3 ++- iros/feature_utils.py | 8 ++++---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 0d00e5d..c3a2bb8 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -40,7 +40,7 @@ IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") -task_file = osp.join(IROS_DATA_DIR, "suture_demos.yaml") +task_file = osp.join(IROS_DATA_DIR, "suture_demos_old.yaml") with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: task_info = yaml.load(fh) @@ -506,6 +506,7 @@ def remove_winding(arm_traj, current_arm_vals): trajoptpy.SetInteractive(False) best_left_path = plan_follow_traj(robot, "leftarm", left_hmats, remove_winding(ds_traj[:,:7], robot.GetDOFValues(leftarm_inds))) + best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, remove_winding(ds_traj[:,7:], robot.GetDOFValues(rightarm_inds))) diff --git a/iros/feature_utils.py b/iros/feature_utils.py index 0dd545a..dc99b2b 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -164,8 +164,8 @@ def automatic_find_cut(img): print 'rgb1 kps', kps1 print 'rgb2 kps', kps2 -cv2.imshow("rgb1", rgb1) -cv2.waitKey(100) +#cv2.imshow("rgb1", rgb1) +#cv2.waitKey(100) -cv2.imshow("rgb2", rgb2) -cv2.waitKey(100) \ No newline at end of file +#cv2.imshow("rgb2", rgb2) +#cv2.waitKey(100) \ No newline at end of file From 7e2bbfb72351e3a99a35e5bd4c78e9fcf5405bb2 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Sat, 9 Mar 2013 19:23:27 -0800 Subject: [PATCH 19/26] more updates --- iros/process_suture_bag.py | 26 ++++++++------------- iros/suture_demos.yaml | 47 ++++++++++++++++++++++++++++++++++++++ 2 files changed, 56 insertions(+), 17 deletions(-) create mode 100644 iros/suture_demos.yaml diff --git a/iros/process_suture_bag.py b/iros/process_suture_bag.py index 13351e0..01faa87 100644 --- a/iros/process_suture_bag.py +++ b/iros/process_suture_bag.py @@ -3,7 +3,7 @@ import argparse parser = argparse.ArgumentParser() parser.add_argument("task") -parser.add_argument("part_name") +parser.add_argument("part_index",type=int) args = parser.parse_args() @@ -22,7 +22,7 @@ import numpy as np import cv2 import simple_clicker as sc -import feature_utils as fu +#import feature_utils as fu # find data files, files to save to SAVE_TRAJ = False @@ -33,12 +33,13 @@ with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: task_info = yaml.load(fh) -bag = task_info[args.task][args.part_name]["demo_bag"] +#bag = task_info[args.task][args.part_index]["demo_bag"] +bag = '/mnt/storage/mtayfred/data/bags/pierce_w_startstopseg7.bag' bag = rosbag.Bag(bag) -jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) -kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) -pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(task_info[args.task][args.part_name]["pt_num"])) +jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(args.part_index)) +kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(args.part_index)) +pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(args.part_index)) ### extract kinematics info from bag def extract_kinematics(np_file, info): @@ -138,7 +139,7 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): look_clouds = bp.get_transformed_clouds(bag, look_times) window_name = "Find Keypoints" -keypt_list = ['lh','rh','ct', 'ne', 'nt', 'ntt', 'auto'] +keypt_list = ['lh','rh','ct', 'ne', 'nt', 'ntt'] keypoints_locations = [] keypoints_names = [] @@ -154,16 +155,7 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): if kp not in keypt_list: print 'incorrect input. try again!' continue - - elif kp == 'auto': - print colorize("Looking for Holes and Cut automatically...", 'green', bold=True) - - xyz_tf = look_clouds[s][0].copy() - rgb_plot = look_clouds[s][1].copy() - xyz_tf[np.isnan(xyz_tf)] = -2 - - holes = fu.automatic_find_holes(rgb_plot, args.task) - + elif kp == 'lh': print colorize("Looking for Left Hole...", 'green', bold=True) diff --git a/iros/suture_demos.yaml b/iros/suture_demos.yaml new file mode 100644 index 0000000..3ee4ee4 --- /dev/null +++ b/iros/suture_demos.yaml @@ -0,0 +1,47 @@ +InterruptedSuture6: + - part_name: pierce + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg6.bag + segments: + - description: grab needle from stand + - description: look at needle tip + extra_info: [left_grab] + - description: grab flap + - description: pierce + left_end_effector: needle_tip + - description: push needle through + - description: grab needle with right hand + + - part_name: two_loop_knot + +InterruptedSuture7: #includes look time for after needle grab with right hand + - part_name: pierce + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg7.bag + segments: + - description: grab needle from stand + - description: look at needle tip + extra_info: [left_grab] + - description: grab flap + - description: pierce + left_end_effector: needle_tip + - description: push needle through + - description: grab needle with right hand + - description: pass needle back to left hand + - description: pull thread + - description: pull thread, put needle back in stand + + - part_name: two_loop_knot + +InterruptedSuture8: #includes additional look time for after passing the needle back to the left hand ##NOT processed yet + - part_name: pierce + demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg8.bag + segments: + - description: grab needle from stand + - description: look at needle tip + extra_info: [left_grab] + - description: grab flap + - description: pierce + left_end_effector: needle_tip + - description: push needle through + - description: grab needle with right hand + + - part_name: two_loop_knot \ No newline at end of file From c2bbc9c38b922bb8089e669d71afe70626c6008c Mon Sep 17 00:00:00 2001 From: John Schulman Date: Sun, 10 Mar 2013 03:49:49 -0700 Subject: [PATCH 20/26] feature matching --- experiments/brute_force_matching.py | 0 iros/feature_utils.py | 101 ++++++++++++++++++++------ iros/image_registration.py | 108 ++++++++++++++++++++++++++++ iros/suture_demos++.yaml | 72 ------------------- jds_utils/shortest_paths.py | 34 +++++++++ 5 files changed, 222 insertions(+), 93 deletions(-) delete mode 100644 experiments/brute_force_matching.py create mode 100644 iros/image_registration.py delete mode 100644 iros/suture_demos++.yaml create mode 100644 jds_utils/shortest_paths.py diff --git a/experiments/brute_force_matching.py b/experiments/brute_force_matching.py deleted file mode 100644 index e69de29..0000000 diff --git a/iros/feature_utils.py b/iros/feature_utils.py index be4293b..0cc5142 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -4,6 +4,7 @@ import numpy as np import os import os.path as osp +import scipy.ndimage as ndi #from jds_image_proc.pcd_io import load_xyzrgb def automatic_find_holes(img, task): @@ -134,41 +135,99 @@ def automatic_find_cut(img): ######################################### ### feature matching ######################################### +from glob import glob +PART_NUM = 0 +SEG_NUM = 2 + IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") -task1 = 'InterruptedSuture5' -task2 = 'InterruptedSuture6' -pcf1 = osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt0seg2_lh_rgb_pl.npy') -pcf2 = osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt0seg2_lh_rgb_pl.npy') +task1 = 'InterruptedSuture6' +task2 = 'InterruptedSuture7' +pcf1 = glob(osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt%iseg%i_*_rgb_*.npy'%(PART_NUM, SEG_NUM)))[0] +pcf2 = glob(osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt%iseg%i_*_rgb_*.npy'%(PART_NUM, SEG_NUM)))[0] -xyz1 = osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt0seg2_lh_xyz_tf.npy') -xyz2 = osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt0seg2_lh_xyz_tf.npy') +xyzfile1 = glob(osp.join(IROS_DATA_DIR, 'point_clouds', task1, 'pt%iseg%i_*_xyz_tf*.npy'%(PART_NUM, SEG_NUM)))[0] +xyzfile2 = glob(osp.join(IROS_DATA_DIR, 'point_clouds', task2, 'pt%iseg%i_*_xyz_tf*.npy'%(PART_NUM, SEG_NUM)))[0] kpf1 = osp.join(IROS_DATA_DIR, 'key_points', task1) kpf2 = osp.join(IROS_DATA_DIR, 'key_points', task2) rgb1 = np.load(pcf1) rgb2 = np.load(pcf2) +xyz1 = np.load(xyzfile1) +xyz2 = np.load(xyzfile2) +if xyz1.ndim == 4: xyz1 = xyz1[0] +if xyz2.ndim == 4: xyz2 = xyz2[0] +if rgb1.ndim == 4: rgb1 = rgb1[0] +if rgb2.ndim == 4: rgb2 = rgb2[0] -kpts1 = np.load(kpf1 + '/pt0_keypoints.npy') -kpts2 = np.load(kpf2 + '/pt0_keypoints.npy') -kpts_names1 = np.load(kpf1 + '/pt0_keypoints_names.npy') -kpts_names2 = np.load(kpf2 + '/pt0_keypoints_names.npy') +kpts1 = np.load(kpf1 + '/pt%i_keypoints.npy'%PART_NUM) +kpts2 = np.load(kpf2 + '/pt%i_keypoints.npy'%PART_NUM) +kpts_names1 = np.load(kpf1 + '/pt%i_keypoints_names.npy'%PART_NUM) +kpts_names2 = np.load(kpf2 + '/pt%i_keypoints_names.npy'%PART_NUM) -for n in range(len(kpts_names1)): - if kpts_names1[n] == ['left_hole', 'right_hole', 'cut']: - kps1 = kpts1[n] - break -for n in range(len(kpts_names2)): - if kpts_names2[n] == ['left_hole', 'right_hole', 'cut']: - kps2 = kpts2[n] - break +kps1 = kpts1[SEG_NUM] +kps2 = kpts2[SEG_NUM] + print 'rgb1 kps', kps1 print 'rgb2 kps', kps2 -cv2.imshow("rgb1", rgb1) +def xyz2rc(xyz, xyz_img): + diffs_rc = ((xyz_img - xyz)**2).sum(axis=2) + diffs_rc[np.isnan(diffs_rc)] = 1e100 + mindist = diffs_rc.min() + if mindist > 1e-4: + print "warning: nonzero minimum distance:",mindist + return np.unravel_index(diffs_rc.argmin(), diffs_rc.shape) + + +RED = (0,0,255) +GREEN = (0,255,0) +BLUE = (255,0,0) +YELLOW = (0,255,255) + +rcs1 = [xyz2rc(xyz, xyz1) for xyz in kps1] +rcs2 = [xyz2rc(xyz, xyz2) for xyz in kps2] + +font = cv.InitFont(cv.CV_FONT_HERSHEY_SIMPLEX, 1, 1, 0, 3, 8) + +rgb1_plot = rgb1.copy() +rgb2_plot = rgb2.copy() + +import image_registration as ir + +pred_rcs2 = ir.register_images(rgb1, rgb2, [(c,r) for (r,c) in rcs1]) + +for (i_kp, (r,c)) in enumerate(rcs1): + cv2.putText(rgb1_plot, str(i_kp), (c,r), cv2.FONT_HERSHEY_PLAIN, 1.0, RED, thickness = 2) + + _xys, _vs = ir.get_matches(rgb1, (c,r), rgb2, max_num_matches=1) + (cpredlocal, rpredlocal) = _xys[0] + rgroundtruth, cgroundtruth = rcs2[i_kp] + + cv2.putText(rgb2_plot, str(i_kp), (c,r), cv2.FONT_HERSHEY_PLAIN, 1.0, RED, thickness = 2) + cv2.putText(rgb2_plot, str(i_kp), (cgroundtruth,rgroundtruth), cv2.FONT_HERSHEY_PLAIN, 1.0, BLUE, thickness = 2) + cv2.putText(rgb2_plot, str(i_kp), (cpredlocal,rpredlocal), cv2.FONT_HERSHEY_PLAIN, 1.0, GREEN, thickness = 2) + + cpredglobal, rpredglobal = pred_rcs2[i_kp] + cv2.putText(rgb2_plot, str(i_kp), (cpredglobal,rpredglobal), cv2.FONT_HERSHEY_PLAIN, 1.0, YELLOW, thickness = 2) + + + + +cv2.imshow("rgb1", rgb1_plot) +cv2.waitKey(100) + +cv2.imshow("rgb2", rgb2_plot) cv2.waitKey(100) -cv2.imshow("rgb2", rgb2) -cv2.waitKey(100) \ No newline at end of file + +cv2.startWindowThread() + +print """ +Red: original coordinates of keypoints in rgb1 +Blue: ground truth (human labeling) of keypoints +Green: keypoint prediction using only NCC (local) +Yellow: keypoint prediction using NCC + dynamic programming +""" \ No newline at end of file diff --git a/iros/image_registration.py b/iros/image_registration.py new file mode 100644 index 0000000..4a51f10 --- /dev/null +++ b/iros/image_registration.py @@ -0,0 +1,108 @@ +import numpy as np +import cv2 +import scipy.ndimage as ndi +import itertools as it +import scipy.spatial.distance as ssd +from jds_utils.shortest_paths import shortest_paths + +DEBUG_PLOTTING = False +PLOT_COUNTER = 0 +class Colors: + RED = (0,0,255) + GREEN = (0,255,0) + BLUE = (255,0,0) + + +def register_images(src_img, targ_img, src_xys_n): + xys_n = [] + vs_n = [] + rankvs_n = [] + for src_xy in src_xys_n: + targ_xys, vs = get_matches(src_img, src_xy, targ_img) + xys_n.append(targ_xys) + vs_n.append(vs) + rankvs_n.append(0*np.arange(len(vs))) + + matchinds_n = dp_match(xys_n, rankvs_n, src_xys_n) + return [xys_n[i][m] for (i,m) in enumerate(matchinds_n)] + + +def dp_match(xys_n, vs_n, src_xys_n): + N = len(xys_n) + assert len(vs_n) == N + assert len(src_xys_n) == N + + nodecosts = vs_n + edgecosts = [] + + for n in xrange(N-1): + xys_ad = xys_n[n] + xys_bd = xys_n[n+1] + A = len(xys_ad) + B = len(xys_bd) + D = len(xys_ad[0]) + diff_d = (np.array(src_xys_n[n]) - np.array(src_xys_n[n+1]))[None,:] + diff_abd = xys_ad[:,None,:] - xys_bd[None,:,:] + diffdiff_abd = diff_abd - diff_d + edgecosts_ab = np.sqrt((diffdiff_abd**2).sum(axis=2)) + edgecosts.append(edgecosts_ab) + + paths_mn, costs_m = shortest_paths(nodecosts, edgecosts) + bestpath_n = paths_mn[np.argmin(costs_m)] + return bestpath_n + + + +def get_matches(src_img, xy, targ_img, patch_size = 59, max_deficit = .3, min_match_distance = 10, max_num_matches = 20): + assert patch_size % 2 == 1 + patch_radius = patch_size // 2 + assert src_img.ndim == 3 + col_keypoint, row_keypoint = xy + + assert row_keypoint - patch_radius >= 0 + assert row_keypoint + patch_radius < src_img.shape[0] + assert col_keypoint - patch_radius >= 0 + assert col_keypoint + patch_radius < src_img.shape[1] + + + patch = src_img[row_keypoint-patch_radius:row_keypoint+patch_radius+1, + col_keypoint-patch_radius:col_keypoint+patch_radius+1, :] + + heatmap = cv2.matchTemplate(targ_img, patch, cv2.TM_CCOEFF_NORMED) + + sorted_heatmap_values = np.sort(heatmap.flatten()) + abs_thresh = sorted_heatmap_values[-1] - max_deficit + + heatmap_maxes = ndi.maximum_filter(heatmap, size=(min_match_distance, min_match_distance)) + rows_local_maxima, cols_local_maxima = np.nonzero(heatmap_maxes == heatmap) + + + rc_good_local_maxima = [] + vals_good_local_maxima = [] + + for (row_lm, col_lm) in zip(rows_local_maxima, cols_local_maxima): + val = heatmap[row_lm, col_lm] + if val >= abs_thresh: + rc_good_local_maxima.append((row_lm, col_lm)) + vals_good_local_maxima.append(val) + + rc_good_local_maxima = np.array(rc_good_local_maxima) + vals_good_local_maxima = np.array(vals_good_local_maxima) + sort_inds = (-vals_good_local_maxima).argsort()[:max_num_matches] + + rc_good_local_maxima = rc_good_local_maxima[sort_inds] + vals_good_local_maxima = vals_good_local_maxima[sort_inds] + + + if DEBUG_PLOTTING: + plot_img = cv2.cvtColor(heatmap, cv2.COLOR_GRAY2BGR) + for (i,(row, col), v) in zip(it.count(), rc_good_local_maxima, vals_good_local_maxima): + cv2.putText(plot_img, "%i:%.2f"%(i,v), (col, row), cv2.FONT_HERSHEY_PLAIN, 1.0, Colors.RED, thickness = 1) + cv2.circle(plot_img, (col, row), 3, Colors.GREEN) + global PLOT_COUNTER + cv2.imshow("get_matches_heatmap%i"%PLOT_COUNTER, plot_img) + PLOT_COUNTER += 1 + while cv2.waitKey(10) == -1: pass + + return rc_good_local_maxima[:,::-1] + patch_radius, vals_good_local_maxima + diff --git a/iros/suture_demos++.yaml b/iros/suture_demos++.yaml deleted file mode 100644 index cf84962..0000000 --- a/iros/suture_demos++.yaml +++ /dev/null @@ -1,72 +0,0 @@ -#segment#: -# hole1 center: (x y z) -# hole2 center: (x y z) -# top of cut: (x y z) -# middle of cut: (x y z) -# bottom of cut: (x y z) -# needle tip: (x y z) - -InterruptedSuture1: - pierce: - demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg1.bag - db_file: pierce.hd5 - pt_num: 0 - seg_num: 8 - -InterruptedSuture2: - pierce: - demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg2.bag - db_file: pierce.hd5 - pt_num: 0 - seg_num: 9 - -InterruptedSuture3: - pierce: - demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg3.bag - db_file: pierce.hd5 - pt_num: 0 - seg_num: 7 - -InterruptedSuture4: - pierce: - demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg4.bag - db_file: pierce.hd5 - pt_num: 0 - seg_num: 7 - -InterruptedSuture5: - pierce: - demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg5.bag - db_file: pierce.hd5 - pt_num: 0 - seg_num: - -InterruptedSuture6: -# pierce: -# demo_bag: /mnt/storage/mtayfred/data/bags/pierce_w_startstopseg6.bag -# db_file: pierce.hd5 -# pt_num: 0 -# seg_num: 8 - - - part_name: pierce - segments: - - description: grab needle - - description - - kp_depends: x y z - kp_extract: a b c - left_ee: asdf - - kp_depends: x y z - kp_extract: a b c - left_ee: asdf - - kp_depends: x y z - kp_extract: a b c - left_ee: asdf - - kp_depends: x y z - kp_extract: a b c - left_ee: asdf - - kp_depends: x y z - kp_extract: a b c - left_ee: asdf - - - - part_name: two_loop_knot \ No newline at end of file diff --git a/jds_utils/shortest_paths.py b/jds_utils/shortest_paths.py new file mode 100644 index 0000000..53dc096 --- /dev/null +++ b/jds_utils/shortest_paths.py @@ -0,0 +1,34 @@ +import numpy as np + +def shortest_paths(ncost_nk,ecost_nkk): + """ + Find minimum cost paths through graph (one path for each end point) + where all nodes in nth row are connected to all nodes in (n+1)st row + ncost_nk: node costs + ecost_nkk: edge costs + + returns: (paths, costs) where + paths is a K x N array of integers. Each row gives the minimum-cost path + to its final node. + costs has length K and gives the cost of each path + """ + N = len(ncost_nk) + assert len(ecost_nkk) == N-1 + + cost_nk = [None for _ in xrange(N)] + prev_nk = [None for _ in xrange(N-1)] + cost_nk[0] = ncost_nk[0] + for n in xrange(1,N): + cost_kk = ecost_nkk[n-1] + cost_nk[n-1][:,None] + ncost_nk[n][None,:] + cost_nk[n] = cost_kk.min(axis=0) + prev_nk[n-1] = cost_kk.argmin(axis=0) + + + path_costs = cost_nk[N-1] + paths = [None for _ in xrange(N)] + + paths[N-1] = np.arange(len(ncost_nk[-1])) + for n in xrange(N-1,0,-1): + paths[n-1] = prev_nk[n-1][paths[n]] + + return np.array(paths).T, path_costs \ No newline at end of file From 2c8e0053253c8aa74d0074cee03ff41f37b67943 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Sun, 10 Mar 2013 10:17:46 -0700 Subject: [PATCH 21/26] feature_utils --- iros/feature_utils.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/iros/feature_utils.py b/iros/feature_utils.py index 0c20509..04ec589 100644 --- a/iros/feature_utils.py +++ b/iros/feature_utils.py @@ -146,6 +146,9 @@ def automatic_find_cut(img): kpf1 = osp.join(IROS_DATA_DIR, 'key_points', task1) kpf2 = osp.join(IROS_DATA_DIR, 'key_points', task2) +#xyz1, rgb1 = load_xyzrgb("suture_scene0.pcd") +#xyz2, rgb2 = load_xyzrgb("suture_scene1.pcd") + rgb1 = np.load(pcf1) rgb2 = np.load(pcf2) From 0b722d80c786d24166e30e2266f666ca1795fcff Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Tue, 12 Mar 2013 15:52:07 -0700 Subject: [PATCH 22/26] clean-up --- iros/execute_suture_traj.py | 327 +++++++++++++++++++----------------- 1 file changed, 172 insertions(+), 155 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 92ca891..7f5f918 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -1,7 +1,7 @@ import argparse parser = argparse.ArgumentParser() parser.add_argument("mode", choices=["openrave", "gazebo", "reality"]) -parser.add_argument("cloud_topic", default="/drop/points") +parser.add_argument("--cloud_topic", default="/camera/depth_registered/points") parser.add_argument("task") parser.add_argument("part_index",type=int) parser.add_argument("--segment_index", type=int, default=0) @@ -44,14 +44,14 @@ import iros IROS_DIR = osp.dirname(iros.__file__) -task_file = osp.join(IROS_DIR, "suture_demos.yaml") +task_file = osp.join(IROS_DIR, "suture_demos2.yaml") with open(osp.join(IROS_DATA_DIR,task_file),"r") as fh: task_info = yaml.load(fh) -jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(args.part_index)) -kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(args.part_index)) -pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(args.part_index)) +jtf = osp.join(IROS_DATA_DIR, args.task, 'joint_trajectories', 'pt' + str(args.part_index)) +kpf = osp.join(IROS_DATA_DIR, args.task, 'keypoints', 'pt' + str(args.part_index)) +pcf = osp.join(IROS_DATA_DIR, args.task, 'point_clouds', 'pt' + str(args.part_index)) if args.mode == "openrave": env = openravepy.Environment() @@ -78,7 +78,8 @@ brett.join_all() brett.update_rave() -needle_tip = mk.create_dummy_body(env, name="needle_tip") +#needle_tip = mk.create_dummy_body(env, name="needle_tip") +needle_tip = mk.create_spheres(env, [(0,0,0)], radii=.02, name = "needle_tip") demo_env=env.CloneSelf(1) demo_env.StopSimulation() @@ -197,6 +198,7 @@ def segment_trajectory(larm, rarm, lgrip, rgrip): assert len(lgrip)==n_steps assert len(rgrip)==n_steps + # indices BEFORE transition occurs l_openings = np.flatnonzero((lgrip[1:] >= thresh) & (lgrip[:-1] < thresh)) r_openings = np.flatnonzero((rgrip[1:] >= thresh) & (rgrip[:-1] < thresh)) @@ -221,53 +223,83 @@ def binarize_gripper(angle): return traj_segments -def get_kp_cloud(listener): - print "waiting for messages on cloud topic %s"%args.cloud_topic - msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) - print "got msg!" - xyz, rgb = ru.pc2xyzrgb(msg) - - #import matplotlib.pyplot as plt - #plt.imshow(xyz[:,:,2]) - #plt.title("xyz") - #plt.show() - - if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") +#def get_kp_cloud(listener): + #print "waiting for messages on topic %s"%args.cloud_topic + #msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) + #print "got msg!" + #xyz, rgb = ru.pc2xyzrgb(msg) - xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - xyz_tf[np.isnan(xyz_tf)] = -2 - rgb_plot = rgb.copy() + #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - #import matplotlib.pyplot as plt - #plt.imshow(xyz_tf[:,:,2]) - #plt.title("xyz_tf") - #plt.show() - - - return xyz_tf, rgb_plot + #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + #xyz_tf[np.isnan(xyz_tf)] = -2 + #rgb_plot = rgb.copy() + + #return xyz_tf, rgb_plot -def get_needle_clouds(listener): +def get_kp_clouds(listener, num_clouds): xyz_tfs = [] rgb_plots = [] - num_clouds = 30 - - if args.cloud_topic == 'test': num_clouds = 5 + #num_clouds = 30 + + class MessageGetter: + + def __init__(self, n_msgs): + self.n_msgs = n_msgs + self.msgs = [] + self.done = False + def callback(self,msg): + if self.done: + return + elif len(self.msgs) < self.n_msgs: + self.msgs.append(msg) + else: + self.done = True + + def get_msgs(n_msgs, topic, msgtype): + print "waiting for %i messages on topic %s"%(n_msgs, topic) + mg = MessageGetter(n_msgs) + sub = rospy.Subscriber(topic, msgtype, mg.callback) + while not mg.done: + rospy.sleep(.05) + sub.unregister() + return mg.msgs + + msgs = get_msgs(num_clouds, args.cloud_topic, sm.PointCloud2) - for i in range(num_clouds): - - print "waiting for messages on cloud topic %s"%args.cloud_topic - msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) - print "got msg %s!"%i + if num_clouds == 1: + msg = msgs[0] xyz, rgb = ru.pc2xyzrgb(msg) - - if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + rgb_plot = rgb.copy() + + return xyz_tf, rgb_plot + + else: + for i in range(num_clouds): + msg = msgs[i] + xyz, rgb = ru.pc2xyzrgb(msg) + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - xyz_tfs.append(xyz_tf) - rgb_plots.append(rgb) + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + + xyz_tfs.append(xyz_tf) + rgb_plots.append(rgb) + + return xyz_tfs, rgb_plots - return xyz_tfs, rgb_plots +#def GetLinkMaybeAttached(robot,ee_link): + #link = robot.GetLink(ee_link) + #if link is not None: return link + #grabbed_bodies = robot.GetGrabbed() + #for grabbed_body in grabbed_bodies: + #link = grabbed_body.GetLink(ee_link) + #if link: return link + #return None def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_manip_name = None, other_manip_traj = None): @@ -275,8 +307,12 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani assert old_traj.shape[0] == n_steps assert old_traj.shape[1] == 7 + arm_inds = robot.GetManipulator(manip_name).GetArmIndices() + + ee_linkname = ee_link.GetName() + init_traj = old_traj.copy() - init_traj[0] = robot.GetDOFValues(robot.GetManipulator(manip_name).GetArmIndices()) + init_traj[0] = robot.GetDOFValues(arm_inds) request = { "basic_info" : { @@ -291,7 +327,7 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani }, { "type" : "collision", - "params" : {"coeffs" : [10],"dist_pen" : [0.025]} + "params" : {"coeffs" : [10],"dist_pen" : [0.005]} } ], "constraints" : [ @@ -305,7 +341,6 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani request["scene_states"] = [] other_dof_inds = robot.GetManipulator(other_manip_name).GetArmIndices() - poses = [openravepy.poseFromMatrix(hmat) for hmat in new_hmats] for (i_step,pose) in enumerate(poses): request["costs"].append( @@ -313,8 +348,10 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani "params":{ "xyz":pose[4:7].tolist(), "wxyz":pose[0:4].tolist(), - "link":ee_link, - "timestep":i_step + "link":ee_linkname, + "timestep":i_step, + "pos_coeffs":[15,15,15], + "rot_coeff":[0,0,0] } }) if other_manip_name is not None: @@ -327,8 +364,19 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani result = trajoptpy.OptimizeProblem(prob) # do optimization traj = result.GetTraj() - - + saver = openravepy.RobotStateSaver(robot) + pos_errs = [] + for i_step in xrange(1,n_steps): + row = traj[i_step] + robot.SetDOFValues(row, arm_inds) + tf = ee_link.GetTransform() + pos = tf[:3,3] + pos_err = np.linalg.norm(poses[i_step][4:7] - pos) + pos_errs.append(pos_err) + pos_errs = np.array(pos_errs) + + print "planned trajectory for %s. max position error: %.3f. all position errors: %s"%(manip_name, pos_errs.max(), pos_errs) + return traj @@ -338,13 +386,12 @@ def plan_follow_traj(robot, manip_name, ee_link, new_hmats, old_traj, other_mani ###### Load demo from np files ####################################### -demo_keypts = np.load(osp.join(IROS_DATA_DIR, kpf + "_keypoints.npy")) -demo_keypts_names = np.load(osp.join(IROS_DATA_DIR, kpf + "_keypoints_names.npy")) +demo_keypts = np.load(osp.join(IROS_DATA_DIR, kpf + "/keypoints.npy")) def keyfunc(fname): - return int(osp.basename(fname).split("_")[0][6:]) # sort files with names like pt1_larm.npy + return int(osp.basename(fname).split("_")[0][3:]) # sort files with names like seg0_larm.npy -lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(jtf + "seg*%s.npy"%partname), +lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(jtf + "/seg*%s.npy"%partname), key = keyfunc) for partname in ("lgrip", "rgrip", "larm", "rarm")] @@ -373,6 +420,7 @@ def keyfunc(fname): listener = ru.get_tf_listener() handles = [] +exec_keypts = {} if args.segment_index > 0: #HACK so we can start in the middle start_segment_info = task_info[args.task][args.part_index]["segments"][args.segment_index] @@ -381,17 +429,19 @@ def keyfunc(fname): robot.Grab(needle_tip) demo_needle_tip.SetTransform(demo_robot.GetManipulator("leftarm").GetTransform()) demo_robot.Grab(demo_needle_tip) - - for s in range(args.segment_index, SEGNUM): segment_info = task_info[args.task][args.part_index]["segments"][s] + keypt_names = segment_info["keypts_to_look_for"] + num_kps = len(keypt_names) - print "trajectory segment %i"%s + print colorize("trajectory segment %i"%s, 'blue', bold=True, highlight=True) - num_kps = len(demo_keypts_names[s]) - exec_keypts = [] + # keep track of keypts seen during each segment + exec_keypts[s] = {} + exec_keypts[s]["names"] = [] + exec_keypts[s]["locations"] = [] # this is the frame whose trajectory we'll adapt to the new situation # in some segments it's the needle tip @@ -414,106 +464,74 @@ def keyfunc(fname): brett.update_rave() for k in range(num_kps): - print colorize("Key point from demo is: " + demo_keypts_names[s][k] + ". Looking for this key point now...", 'green', bold=True) + print colorize("Key point from demo is: " + keypt_names[k] + ". Looking for this key point now...", 'green', bold=True) + rospy.sleep(0.5) - if demo_keypts_names[s][k] in ['left_hole', 'right_hole', 'stand']: - if args.cloud_topic == 'test': - if demo_keypts_names[s][k] == 'left_hole': - xyz_tf = np.load(pcf + 'seg%s_lh_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_lh_rgb_pl.npy'%s) - elif demo_keypts_names[s][k] == 'right_hole': - xyz_tf = np.load(pcf + 'seg%s_rh_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_rh_rgb_pl.npy'%s) - else: - xyz_tf = np.load(pcf + 'seg%s_stand_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_stand_rgb_pl.npy'%s) - else: - xyz_tf, rgb_plot = get_kp_cloud(listener) - - kp_loc = sc.find_kp(demo_keypts_names[s][k], xyz_tf, rgb_plot, window_name) - exec_keypts.append(kp_loc) - - elif demo_keypts_names[s][k] == 'cut': - if args.cloud_topic == 'test': - xyz_tf = np.load(pcf + 'seg%s_ct_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + 'seg%s_ct_rgb_pl.npy'%s) - else: - xyz_tf, rgb_plot = get_kp_cloud(listener) + if keypt_names[k] == 'none': + kp_loc = ((0, 0, 0)) + print colorize("No keypoint for this segment", 'green', bold=True) + + elif args.cloud_topic == 'test': + xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) + + elif keypt_names[k] in ['left_hole', 'right_hole', 'stand', 'top_cut', 'mid_cut', 'bot_cut']: + xyz_tf, rgb_plot = get_kp_clouds(listener, 1) + kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) + + elif keypt_names[k] == 'needle_end': + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + kp_loc, pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + if pts > 0: break + else: print colorize("Couldn't find the needle end! Trying again","red", True, True) + + elif keypt_names[k] == 'needle_tip': + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + kp_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') + if kp_loc[2] > 0.8: break + else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - tcut_loc, mcut_loc, bcut_loc = sc.find_cut(xyz_tf, rgb_plot, window_name) - exec_keypts.append(tcut_loc) - exec_keypts.append(mcut_loc) - exec_keypts.append(bcut_loc) + elif keypt_names[k] == 'tip_transform': # this is segment where robot looks for tip + demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) + + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') + if exec_needle_tip_loc[2] > 1: break + else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - elif demo_keypts_names[s][k] == 'needle_end': - if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_ne_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_ne_rgb_pls.npy'%s) - else: - xyz_tfs, rgb_plots = get_needle_clouds(listener) + kp_loc = ((0, 0, 0)) + + def grab_needle_tip(lr): + for demo in [False, True]: + if demo: + tip_loc = demo_needle_tip_loc + grabbing_robot = demo_robot + grabbed_needle_tip = demo_needle_tip + else: + tip_loc = exec_needle_tip_loc + grabbing_robot = robot + grabbed_needle_tip = needle_tip + grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) + grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) - nl = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) - exec_keypts.append(nl) - - elif demo_keypts_names[s][k] == 'needle_tip': - if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_nt_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_nt_rgb_pls.npy'%s) + if "extra_info" in segment_info: + if "left_grab" in segment_info["extra_info"]: + grab_needle_tip('l') + elif "right_grab" in segment_info["extra_info"]: + grab_needle_tip('r') - else: - while True: - xyz_tfs, rgb_plots = get_needle_clouds(listener) - nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - if (nl[2] > 0.8) and (demo_keypts_names[s][k] == 'needle_tip'): - break - else: - print colorize("didn't find a high enough point! trying again","red", True, True) - - exec_keypts.append(nl) - - elif demo_keypts_names[s][k] == 'empty': # this is segment where robot looks for tip - demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf + "seg%s_needle_world_loc.npy"%s)) - - if args.cloud_topic == 'test': - xyz_tfs = np.load(pcf + 'seg%s_ntt_xyz_tfs.npy'%s) - rgb_plots = np.load(pcf + 'seg%s_ntt_rgb_pls.npy'%s) - else: - while True: - xyz_tfs, rgb_plots = get_needle_clouds(listener) - nl = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - if (nl[2] > 1) and (demo_keypts_names[s][k] == 'empty'): - break - else: - print colorize("didn't find a high enough point! trying again","red", True, True) + else: + print "Invalid keypoint name! Aborting..." + sys.exit(1) - exec_needle_tip_loc = nl - exec_keypts.append((0,0,0)) - - def grab_needle_tip(lr): - for demo in [False, True]: - if demo: - tip_loc = demo_needle_tip_loc - grabbing_robot = demo_robot - grabbed_needle_tip = demo_needle_tip - else: - tip_loc = exec_needle_tip_loc - grabbing_robot = robot - grabbed_needle_tip = needle_tip - grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) - grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) + exec_keypts[s]["names"].append(keypt_names[k]) + exec_keypts[s]["locations"].append(kp_loc) - if "extra_info" in segment_info: - if "left_grab" in segment_info["extra_info"]: - grab_needle_tip('l') - elif "right_grab" in segment_info["extra_info"]: - grab_needle_tip('r') - - - #print 'exec_keypts', exec_keypts - demopoints_m3 = np.array(demo_keypts[s]) - newpoints_m3 = np.array(exec_keypts) - del exec_keypts + newpoints_m3 = np.array(exec_keypts[s]["locations"]) if args.mode in ["gazebo", "reality"]: handles = [] @@ -534,7 +552,7 @@ def grab_needle_tip(lr): - for (i,mini_segment) in enumerate(mini_segments[s]): + for (i, mini_segment) in enumerate(mini_segments[s]): brett.update_rave() @@ -604,11 +622,11 @@ def remove_winding(arm_traj, current_arm_vals): seg_arms = task_info[args.task][args.part_index]["segments"][s]["mini-segments"][i]["arms_used"] if 'l' in seg_arms: - best_left_path = plan_follow_traj(robot, "leftarm", left_ee_linkname, left_hmats, remove_winding(ds_traj[:,:7], robot.GetDOFValues(leftarm_inds))) + best_left_path = plan_follow_traj(robot, "leftarm", left_ee_link, left_hmats, remove_winding(ds_traj[:,:7], robot.GetDOFValues(leftarm_inds))) else: best_left_path = ds_traj[:,:7] if 'r' in seg_arms: - best_right_path = plan_follow_traj(robot, "rightarm", right_ee_linkname, right_hmats, remove_winding(ds_traj[:,7:], robot.GetDOFValues(rightarm_inds)), "leftarm", best_left_path) + best_right_path = plan_follow_traj(robot, "rightarm", right_ee_link, right_hmats, remove_winding(ds_traj[:,7:], robot.GetDOFValues(rightarm_inds)), "leftarm", best_left_path) else: best_right_path = ds_traj[:,7:] @@ -640,7 +658,6 @@ def remove_winding(arm_traj, current_arm_vals): from brett2 import trajectories #def follow_body_traj2(pr2, bodypart2traj, times=None, wait=True, base_frame = "/base_footprint"): bodypart2traj = {} - print "lgrip, rgrip", mini_segment.lgrip_angle, mini_segment.rgrip_angle brett.lgrip.set_angle(mini_segment.lgrip_angle) brett.rgrip.set_angle(mini_segment.rgrip_angle) brett.join_all() From 52415c215c6cddf4d1adb44055ff91251fc580f8 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Tue, 12 Mar 2013 21:43:54 -0700 Subject: [PATCH 23/26] minor update before tuning --- iros/execute_suture_traj.py | 164 ++++++++++++++------------ iros/process_suture_bag.py | 223 +++++++++++++++++++++++------------- iros/simple_clicker.py | 143 +++++++++-------------- 3 files changed, 293 insertions(+), 237 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 7f5f918..8c57185 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -19,6 +19,7 @@ import brett2.ros_utils as ru from jds_utils.colorize import colorize from jds_utils import conversions +from jds_utils.yes_or_no import yes_or_no from brett2 import mytf import yaml import cv2 @@ -28,7 +29,7 @@ import os import os.path as osp from glob import glob -import subprocess, sys +import subprocess, sys, time import sensor_msgs.msg as sm from time import sleep @@ -65,7 +66,7 @@ else: import rospy from brett2.PR2 import PR2 - if rospy.get_name() == "/unnamed": rospy.init_node("follow_pose_traj", disable_signals=True) + if rospy.get_name() == "/unnamed": rospy.init_node("execute_suture", disable_signals=True) rviz = ru.RvizWrapper() brett = PR2() @@ -223,24 +224,9 @@ def binarize_gripper(angle): return traj_segments -#def get_kp_cloud(listener): - #print "waiting for messages on topic %s"%args.cloud_topic - #msg = rospy.wait_for_message(args.cloud_topic, sm.PointCloud2) - #print "got msg!" - #xyz, rgb = ru.pc2xyzrgb(msg) - - #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - - #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - #xyz_tf[np.isnan(xyz_tf)] = -2 - #rgb_plot = rgb.copy() - - #return xyz_tf, rgb_plot - def get_kp_clouds(listener, num_clouds): xyz_tfs = [] rgb_plots = [] - #num_clouds = 30 class MessageGetter: @@ -292,6 +278,30 @@ def get_msgs(n_msgs, topic, msgtype): return xyz_tfs, rgb_plots + +def find_last_kp_loc(exec_keypts, desired_keypt, current_seg): + + if search_seg < 1: + print "Reached beginning of execution and couldn't find desired keypoint! Aborting..." + sys.exit(1) + else: + search_seg = current_seg - 1 + + while(True): + search_seg_names = exec_keypts[search_seg]["names"] + search_seg_locs = exec_keypts[search_seg]["locations"] + + for k in range(len(search_seg_names)): + if search_seg_names[k] == desired_keypt: + kp_loc = search_seg_locs[k] + kp_found = True + + if kp_found: + return kp_loc, search_seg + else: + search_seg -= 1 + + #def GetLinkMaybeAttached(robot,ee_link): #link = robot.GetLink(ee_link) #if link is not None: return link @@ -465,68 +475,76 @@ def keyfunc(fname): brett.update_rave() for k in range(num_kps): print colorize("Key point from demo is: " + keypt_names[k] + ". Looking for this key point now...", 'green', bold=True) - rospy.sleep(0.5) + time.sleep(1) #time.sleep or rospy.sleep?? + sc.show_pointclouds(get_kp_clouds(listener, 1), window_name) - if keypt_names[k] == 'none': - kp_loc = ((0, 0, 0)) - print colorize("No keypoint for this segment", 'green', bold=True) - - elif args.cloud_topic == 'test': - xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) - - elif keypt_names[k] in ['left_hole', 'right_hole', 'stand', 'top_cut', 'mid_cut', 'bot_cut']: - xyz_tf, rgb_plot = get_kp_clouds(listener, 1) - kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) + if yes_or_no(colorize("Is the keypoint visible?", "red")): - elif keypt_names[k] == 'needle_end': - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - kp_loc, pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) - if pts > 0: break - else: print colorize("Couldn't find the needle end! Trying again","red", True, True) + if keypt_names[k] == 'none': + kp_loc = ((0, 0, 0)) + print colorize("No keypoint for this segment", 'green', bold=True) - elif keypt_names[k] == 'needle_tip': - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - kp_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') - if kp_loc[2] > 0.8: break - else: print colorize("Didn't find a high enough point! Trying again","red", True, True) + elif args.cloud_topic == 'test': + xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) + rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) + + elif keypt_names[k] in ['left_hole', 'right_hole', 'stand', 'top_cut', 'mid_cut', 'bot_cut']: + xyz_tf, rgb_plot = get_kp_clouds(listener, 1) + kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) + + elif keypt_names[k] in ['needle_end', 'razor']: + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + kp_loc, pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + if pts > 0: break + else: print colorize("Couldn't find the keypoint! Trying again","red", True, True) - elif keypt_names[k] == 'tip_transform': # this is segment where robot looks for tip - demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) - - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') - if exec_needle_tip_loc[2] > 1: break - else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - - kp_loc = ((0, 0, 0)) - - def grab_needle_tip(lr): - for demo in [False, True]: - if demo: - tip_loc = demo_needle_tip_loc - grabbing_robot = demo_robot - grabbed_needle_tip = demo_needle_tip - else: - tip_loc = exec_needle_tip_loc - grabbing_robot = robot - grabbed_needle_tip = needle_tip - grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) - grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) - - if "extra_info" in segment_info: - if "left_grab" in segment_info["extra_info"]: - grab_needle_tip('l') - elif "right_grab" in segment_info["extra_info"]: - grab_needle_tip('r') + elif keypt_names[k] == 'needle_tip': + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + kp_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') + if kp_loc[2] > 0.8: break + else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - else: - print "Invalid keypoint name! Aborting..." - sys.exit(1) + elif keypt_names[k] == 'tip_transform': # this is segment where robot looks for tip + demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) + + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) + exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') + if exec_needle_tip_loc[2] > 1: break + else: print colorize("Didn't find a high enough point! Trying again","red", True, True) + + kp_loc = ((0, 0, 0)) + + def grab_needle_tip(lr): + for demo in [False, True]: + if demo: + tip_loc = demo_needle_tip_loc + grabbing_robot = demo_robot + grabbed_needle_tip = demo_needle_tip + else: + tip_loc = exec_needle_tip_loc + grabbing_robot = robot + grabbed_needle_tip = needle_tip + grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) + grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) + + if "extra_info" in segment_info: + if "left_grab" in segment_info["extra_info"]: + grab_needle_tip('l') + elif "right_grab" in segment_info["extra_info"]: + grab_needle_tip('r') + + else: + print "Invalid keypoint name! Aborting..." + sys.exit(1) + else: # keypoint occluded + kp_loc, found_seg = find_last_kp_loc(exec_keypts, keypt_names[k], s) + print "keypoint %s found in seg %s at %s" %(keypt_names[k], found_seg, kp_loc) + + exec_keypts[s]["names"].append(keypt_names[k]) exec_keypts[s]["locations"].append(kp_loc) diff --git a/iros/process_suture_bag.py b/iros/process_suture_bag.py index 470d56f..b9e5c31 100644 --- a/iros/process_suture_bag.py +++ b/iros/process_suture_bag.py @@ -6,7 +6,6 @@ parser.add_argument("part_index",type=int) args = parser.parse_args() - import lfd import iros from lfd import bag_proc as bp @@ -22,14 +21,12 @@ import numpy as np import cv2 import simple_clicker as sc -#import feature_utils as fu # find data files, files to save to -SAVE_TRAJ = False IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") IROS_DIR = osp.dirname(iros.__file__) -task_file = osp.join(IROS_DIR, "suture_demos.yaml") +task_file = osp.join(IROS_DIR, "suture_demos2.yaml") with open(osp.join(IROS_DIR, task_file),"r") as fh: task_info = yaml.load(fh) @@ -37,19 +34,21 @@ bag = task_info[args.task][args.part_index]["demo_bag"] bag = rosbag.Bag(bag) -jtf = osp.join(IROS_DATA_DIR, 'joint_trajectories', args.task, 'pt' + str(args.part_index)) -kpf = osp.join(IROS_DATA_DIR, 'key_points', args.task, 'pt' + str(args.part_index)) -pcf = osp.join(IROS_DATA_DIR, 'point_clouds', args.task, 'pt' + str(args.part_index)) +jtf = osp.join(IROS_DATA_DIR, args.task, 'joint_trajectories', 'pt' + str(args.part_index)) +kpf = osp.join(IROS_DATA_DIR, args.task, 'keypoints', 'pt' + str(args.part_index)) +pcf = osp.join(IROS_DATA_DIR, args.task, 'point_clouds', 'pt' + str(args.part_index)) + +#kpf = osp.join(IROS_DATA_DIR, 'InterruptedSuture0', 'keypoints', 'pt0') ### extract kinematics info from bag def extract_kinematics(np_file, info): for i in range(len(info)): - savefile = np_file + 'seg%s'%i - print 'Writing to', savefile + savefile = np_file + '/seg%s'%i + print 'Writing to', np_file if osp.exists(savefile + '_larm.npy'): - if yes_or_no(savefile + ' already exists. Overwrite?'): + if yes_or_no('/seg%s already exists. Overwrite?'%i): os.remove(savefile + '_larm.npy') os.remove(savefile + '_rarm.npy') os.remove(savefile + '_lgrip.npy') @@ -68,7 +67,7 @@ def extract_kinematics(np_file, info): np.save(savefile + '_lgrip.npy' , np.array(lgrip)) np.save(savefile + '_rgrip.npy' , np.array(rgrip)) - print 'saved all' + print 'Saved all trajectories for %i segments'%i # creates the text for the yaml file for the demo @@ -115,8 +114,8 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): SEGNUM = len(look_times) -if SAVE_TRAJ == True: - raw_input("press enter to extract kinematics info from bag file") +if yes_or_no('Do you want to extract kinematics info from bag file?'): + #raw_input("press enter to extract kinematics info from bag file") link_names = ["r_gripper_tool_frame", "l_gripper_tool_frame"] kinematics_info = bp.extract_kinematics_from_bag(bag, link_names) @@ -132,14 +131,14 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): extract_kinematics(jtf, forced_segs_info) - raw_input("extracted segments. press enter to continue") + raw_input("Extracted segments. Press enter to continue") # determine which keypoints matter for each segment based on user input -print 'getting all look_time point clouds...' +print 'Extracting look_time point clouds...' look_clouds = bp.get_transformed_clouds(bag, look_times) window_name = "Find Keypoints" -keypt_list = ['lh','rh','ct', 'ne', 'nt', 'ntt', 'stand'] +keypt_list = ['lh', 'rh', 'tc', 'mc', 'bc', 'ne', 'nt', 'ntt', 'stand', 'rzr', 'none'] keypoints_locations = [] keypoints_names = [] @@ -147,113 +146,183 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): print 'look time for segment %s'%s keypt_names = [] keypt_locs = [] + k = 0 while (True): sc.show_pointclouds(look_clouds[s], window_name) - kp = raw_input("which key points are important for this segment? choices are: " + str(keypt_list) + ". (please only enter one key point at a time): ") + kp = raw_input("Which key points are important for this segment? choices are: " + str(keypt_list) + ". (please only enter one key point at a time): ") if kp not in keypt_list: - print 'incorrect input. try again!' + print 'Incorrect input. Try again!' continue - elif kp in ['lh', 'rh', 'stand']: + elif kp in ['lh', 'rh', 'bc', 'mc', 'tc', 'stand']: print colorize("Looking for %s..."%kp, 'green', bold=True) xyz_tf = look_clouds[s][0].copy() rgb_plot = look_clouds[s][1].copy() xyz_tf[np.isnan(xyz_tf)] = -2 - np.save(pcf + 'seg%s_'%s + kp + '_xyz_tf.npy', xyz_tf) - np.save(pcf + 'seg%s_'%s + kp + '_rgb_pl.npy', rgb_plot) - kp_loc = sc.find_kp(kp, xyz_tf, rgb_plot, window_name) keypt_locs.append(kp_loc) if kp == 'lh': keypt_names.append('left_hole') elif kp == 'rh': keypt_names.append('right_hole') elif kp == 'stand': keypt_names.append('stand') + elif kp == 'bc': keypt_names.append('bot_cut') + elif kp == 'mc': keypt_names.append('mid_cut') + elif kp == 'tc': keypt_names.append('top_cut') + + np.save(pcf + '/seg%s_%s_xyz_tf.npy'%(s,keypt_names[k]), xyz_tf) + np.save(pcf + '/seg%s_%s_rgb_pl.npy'%(s,keypt_names[k]), rgb_plot) + + elif kp == 'rzr': + xyz_tfs = [] + rgb_plots = [] + num_clouds = 10 - elif kp == 'ct': - print colorize("Looking for Cut...", 'green', bold=True) - - xyz_tf = look_clouds[s][0].copy() - rgb_plot = look_clouds[s][1].copy() - xyz_tf[np.isnan(xyz_tf)] = -2 - np.save(pcf + 'seg%s_ct_xyz_tf.npy'%s, xyz_tf) - np.save(pcf + 'seg%s_ct_rgb_pl.npy'%s, rgb_plot) + while True: + razor_look_times = [] + + print colorize("Looking for Razor...", 'green', bold=True) + print 'getting %s point clouds...'%num_clouds + + for t in range(num_clouds): + razor_look_times.append(look_times[s] + t) + + razor_clouds = bp.get_transformed_clouds(bag, razor_look_times) - tcut_loc, mcut_loc, bcut_loc = sc.find_cut(xyz_tf, rgb_plot, window_name) - keypt_locs.append(tcut_loc) - keypt_locs.append(mcut_loc) - keypt_locs.append(bcut_loc) - keypt_names.append('cut') + for i in range(num_clouds): + xyz_tfs.append(razor_clouds[i][0].copy()) + rgb_plots.append(razor_clouds[i][1].copy()) + + rzr_loc, valid_pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + if (valid_pts > 0) or (num_clouds >= 20): + del razor_look_times + break + else: + print colorize("Couldn't find the razor! Trying again with more point clouds", "red", True, True) + del needle_look_times + num_clouds += 5 + + keypt_locs.append(rzr_loc) + keypt_names.append('razor') + + np.save(pcf + '/seg%s_%s_xyz_tfs.npy'%(s,keypt_names[k]), xyz_tfs) + np.save(pcf + '/seg%s_%s_rgb_pls.npy'%(s,keypt_names[k]), rgb_plots) + + del xyz_tfs + del rgb_plots elif kp == 'ne': xyz_tfs = [] - rgb_plots = [] - needle_look_times = [] - num_clouds = 15 + rgb_plots = [] + num_clouds = 10 - for t in range(num_clouds): - needle_look_times.append(look_times[s] + t) + while True: + needle_look_times = [] - print colorize("Looking for Needle End...", 'green', bold=True) - print 'getting %s needle point clouds...'%num_clouds - needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) + print colorize("Looking for Needle End...", 'green', bold=True) + print 'getting %s point clouds...'%num_clouds - for i in range(num_clouds): - xyz_tfs.append(needle_clouds[i][0].copy()) - rgb_plots.append(needle_clouds[i][1].copy()) - xyz_tfs[i][np.isnan(xyz_tfs[i])] = -2 - np.save(pcf + 'seg%s_ne_xyz_tfs.npy'%s, xyz_tfs) - np.save(pcf + 'seg%s_ne_rgb_pls.npy'%s, rgb_plots) - - needle_loc = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) - + for t in range(num_clouds): + needle_look_times.append(look_times[s] + t) + + needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) + + for i in range(num_clouds): + xyz_tfs.append(needle_clouds[i][0].copy()) + rgb_plots.append(needle_clouds[i][1].copy()) + + needle_loc, valid_pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) + if (valid_pts > 0) or (num_clouds >= 20): + del needle_look_times + break + else: + print colorize("Couldn't find the needle end! Trying again with more point clouds", "red", True, True) + del needle_look_times + num_clouds += 5 + keypt_locs.append(needle_loc) - keypt_names.append('needle_end') + keypt_names.append('needle_end') + + np.save(pcf + '/seg%s_%s_xyz_tfs.npy'%(s,keypt_names[k]), xyz_tfs) + np.save(pcf + '/seg%s_%s_rgb_pls.npy'%(s,keypt_names[k]), rgb_plots) - del needle_look_times del xyz_tfs del rgb_plots - elif kp in ['nt', 'ntt']: + elif kp == 'nt': + xyz_tfs = [] + rgb_plots = [] + num_clouds = 10 + + while(True): + needle_look_times = [] + + print colorize("Looking for Needle Tip...", 'green', bold=True) + print 'getting %s needle point clouds...'%num_clouds + + for t in range(num_clouds): + needle_look_times.append(look_times[s] + t) + + needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) + + for i in range(num_clouds): + xyz_tfs.append(needle_clouds[i][0].copy()) + rgb_plots.append(needle_clouds[i][1].copy()) + + needle_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'process') + if yes_or_no("Is this a good point?"): + break + else: + del needle_look_times + num_clouds += 5 + print ("Trying again with more point clouds.") + + keypt_locs.append(needle_loc) + keypt_names.append('needle_tip') + np.save(pcf + '/seg%s_%s_xyz_tfs.npy'%(s,keypt_names[k]), xyz_tfs) + np.save(pcf + '/seg%s_%s_rgb_pls.npy'%(s,keypt_names[k]), rgb_plots) + + del xyz_tfs + del rgb_plots + + elif kp == 'ntt': xyz_tfs = [] rgb_plots = [] needle_look_times = [] - if kp == 'nt': num_clouds = 20 - else: num_clouds = 10 + num_clouds = 10 + + print colorize("Looking for Needle Tip...", 'green', bold=True) + print 'getting %s needle point clouds...'%num_clouds for t in range(num_clouds): needle_look_times.append(look_times[s] + t) - - print colorize("Looking for Needle Tip...", 'green', bold=True) - print 'getting %s needle point clouds...'%num_clouds + needle_clouds = bp.get_transformed_clouds(bag, needle_look_times) for i in range(num_clouds): xyz_tfs.append(needle_clouds[i][0].copy()) rgb_plots.append(needle_clouds[i][1].copy()) - xyz_tfs[i][np.isnan(xyz_tfs[i])] = -2 - needle_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name) - - if kp == 'nt': - keypt_locs.append(needle_loc) - keypt_names.append('needle_tip') - np.save(pcf + 'seg%s_nt_xyz_tfs.npy'%s, xyz_tfs) - np.save(pcf + 'seg%s_nt_rgb_pls.npy'%s, rgb_plots) - else: - keypt_locs.append((0,0,0)) - keypt_names.append('empty') - np.save(kpf + 'seg%s_needle_world_loc.npy'%s, needle_loc) - np.save(pcf + 'seg%s_ntt_xyz_tfs.npy'%s, xyz_tfs) - np.save(pcf + 'seg%s_ntt_rgb_pls.npy'%s, rgb_plots) + needle_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'process') + + keypt_locs.append((0,0,0)) + keypt_names.append('tip_transform') + np.save(kpf + '/seg%s_needle_world_loc.npy'%s, needle_loc) + np.save(pcf + '/seg%s_%s_xyz_tfs.npy'%(s,keypt_names[k]), xyz_tfs) + np.save(pcf + '/seg%s_%s_rgb_pls.npy'%(s,keypt_names[k]), rgb_plots) del needle_look_times del xyz_tfs - del rgb_plots + del rgb_plots + + elif kp == 'none': + keypt_locs.append((0,0,0)) + keypt_names.append('none') if yes_or_no('Key point %s saved for this segment. Is there another key point for this segment?'%kp): + k += 1 continue else: keypoints_locations.append(keypt_locs) @@ -265,8 +334,8 @@ def add_new_entry_to_yaml_file(data_dir, new_entry_text): raw_input("Finished processing point clouds. Press enter to save key points to numpy file") -np.save(kpf + '_keypoints.npy', keypoints_locations) -np.save(kpf + '_keypoints_names.npy', keypoints_names) +np.save(kpf + '/keypoints.npy', keypoints_locations) +np.save(kpf + '/keypoints_names.npy', keypoints_names) #raw_input("press enter to add new entry to yaml file") diff --git a/iros/simple_clicker.py b/iros/simple_clicker.py index f886e31..6dba74b 100644 --- a/iros/simple_clicker.py +++ b/iros/simple_clicker.py @@ -50,6 +50,7 @@ def callback(self, event, x, y, flags, param): cv2.imshow(window_name, rgb_plot) cv2.waitKey(100) + xyz_tf[np.isnan(xyz_tf)] = -2 x, y, z = xyz_tf[col_kp, row_kp] print kp, "3d location", x, y, z @@ -81,22 +82,22 @@ def callback(self, event, x, y, flags, param): xy_m = [] xy_b = [] - print colorize("click at the top of the cut line", 'red', bold=True) - gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) - while not gc.done: - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(10) - xy_t.append(gc.x) - xy_t.append(gc.y) + #print colorize("click at the top of the cut line", 'red', bold=True) + #gc = GetClick() + #cv2.setMouseCallback(window_name, gc.callback) + #while not gc.done: + #cv2.imshow(window_name, rgb_plot) + #cv2.waitKey(10) + #xy_t.append(gc.x) + #xy_t.append(gc.y) - x_tcut, y_tcut, z_tcut = xyz_tf[xy_t[1], xy_t[0]] - tcut_loc = (x_tcut, y_tcut, z_tcut) - cv2.circle(rgb_plot, (xy_t[0], xy_t[1]), 5, (0, 0, 255), -1) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) + #x_tcut, y_tcut, z_tcut = xyz_tf[xy_t[1], xy_t[0]] + #tcut_loc = (x_tcut, y_tcut, z_tcut) + #cv2.circle(rgb_plot, (xy_t[0], xy_t[1]), 5, (0, 0, 255), -1) + #cv2.imshow(window_name, rgb_plot) + #cv2.waitKey(100) - print colorize("now click the middle of the cut line", 'red', bold=True) + print colorize("click the cut line in between the holes", 'red', bold=True) gc = GetClick() cv2.setMouseCallback(window_name, gc.callback) while not gc.done: @@ -111,36 +112,33 @@ def callback(self, event, x, y, flags, param): cv2.imshow(window_name, rgb_plot) cv2.waitKey(100) - print colorize("now click the bottom of the cut line", 'red', bold=True) - gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) - while not gc.done: - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(10) - xy_b.append(gc.x) - xy_b.append(gc.y) - - x_bcut, y_bcut, z_bcut = xyz_tf[xy_b[1], xy_b[0]] - bcut_loc = (x_bcut, y_bcut, z_bcut) - - #cv2.line(rgb_plot, tuple(xy_m), tuple(xy_b), (0, 255, 0), 2) - #cv2.line(rgb_plot, tuple(xy_t), tuple(xy_m), (0, 255, 0), 2) - - cv2.circle(rgb_plot, (xy_b[0], xy_b[1]), 5, (0, 0, 255), -1) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) + #print colorize("click the bottom of the cut line", 'red', bold=True) + #gc = GetClick() + #cv2.setMouseCallback(window_name, gc.callback) + #while not gc.done: + #cv2.imshow(window_name, rgb_plot) + #cv2.waitKey(10) + #xy_b.append(gc.x) + #xy_b.append(gc.y) + + #x_bcut, y_bcut, z_bcut = xyz_tf[xy_b[1], xy_b[0]] + #bcut_loc = (x_bcut, y_bcut, z_bcut) + + #cv2.circle(rgb_plot, (xy_b[0], xy_b[1]), 5, (0, 0, 255), -1) + #cv2.imshow(window_name, rgb_plot) + #cv2.waitKey(100) - print 'cut top 3d location', x_tcut, y_tcut, z_tcut + #print 'cut top 3d location', x_tcut, y_tcut, z_tcut print 'cut middle cut 3d location', x_mcut, y_mcut, z_mcut - print 'cut bottom 3d location', x_bcut, y_bcut, z_bcut + #print 'cut bottom 3d location', x_bcut, y_bcut, z_bcut - return tcut_loc, mcut_loc, bcut_loc + return mcut_loc ######################################### ### find needle ######################################### -def find_needle_tip(xyz_tfs, rgb_plots, window_name): +def find_needle_tip(xyz_tfs, rgb_plots, window_name, caller): ### clicking set-up class GetClick: @@ -208,14 +206,16 @@ def callback(self, event, x, y, flags, param): max_needle.append(yneedle[ind]) max_needle.append(zneedle[ind]) - #cv2.circle(rgb_plots[ind], (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) - #cv2.imshow(window_name, rgb_plots[ind]) - #cv2.waitKey(100) - - cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) - + if caller == 'process': + cv2.circle(rgb_plots[ind], (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow(window_name, rgb_plots[ind]) + cv2.waitKey(100) + + else: + cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) + print 'needle tip 3d location', max_needle # plot the point cloud with a circle around "highest" point @@ -226,7 +226,6 @@ def callback(self, event, x, y, flags, param): #mlab.show() #raw_input("press enter when done looking") - #print "at end of needle tip func" return max_needle @@ -273,6 +272,7 @@ def callback(self, event, x, y, flags, param): high_red_xyz = [] high_red_rc = [] + valid_pts = 0 # extract depths from drawn rectangle FOAM_HEIGHT = .85 @@ -285,55 +285,24 @@ def callback(self, event, x, y, flags, param): s=hsv[:,:,1] v=hsv[:,:,2] - color_mask = ((h<10) | (h>150)) & (s > 100) & (v > 100) - height_mask = z_rectangle > FOAM_HEIGHT + .05 + color_mask = ((h<20) | (h>150)) & (s > 100) & (v > 90) + height_mask = z_rectangle > FOAM_HEIGHT + .025 total_mask = color_mask & height_mask - print "%ith image has %i valid points (above foam and red)"%(i, total_mask.sum()) + print "%ith image has %i valid points (above foam and red)"%(i, total_mask.sum()) + valid_pts += total_mask.sum() high_red_xyz.extend(xyz_tfs[i][rowmin:rowmax, colmin:colmax, :][total_mask]) xyz_avg = np.median(high_red_xyz,axis=0) - #from jds_image_proc.pcl_utils import xyz2uv - #row, col = xyz2uv(xyz_avg).astype('int')[0] + from jds_image_proc.pcl_utils import xyz2uv + row, col = xyz2uv(xyz_avg).astype('int')[0] + + cv2.circle(rgb_plot, (row, col), 3, (255, 0, 0), 2) + cv2.imshow(window_name, rgb_plot) + cv2.waitKey(100) print 'Needle end location', xyz_avg - return xyz_avg - -######################################### -### find needle stand -######################################### -def find_stand(xyz_tf, rgb_plot, window_name): - ### clicking set-up - class GetClick: - x = None - y = None - done = False - def callback(self, event, x, y, flags, param): - if self.done: - return - elif event == cv2.EVENT_LBUTTONDOWN: - self.x = x - self.y = y - self.done = True - - print colorize("click on the center of the needle stand", 'red', bold=True) - gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) - while not gc.done: - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(10) - row_stand = gc.x - col_stand = gc.y - - cv2.circle(rgb_plot, (row_stand, col_stand), 5, (0, 0, 255), -1) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) - - x_stand, y_stand, z_stand = xyz_tf[col_stand, row_stand] - - print "needle stand 3d location", x_stand, y_stand, z_stand - - return (x_stand, y_stand, z_stand) \ No newline at end of file + return xyz_avg, valid_pts \ No newline at end of file From 10ad5a48663fe20a515c7da7bd6fcccf040ad831 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Wed, 13 Mar 2013 09:49:01 -0700 Subject: [PATCH 24/26] major cleanup --- iros/execute_suture_traj.py | 228 +++++++++++++------------------ iros/simple_clicker.py | 260 ++++++++++++++++++++++-------------- 2 files changed, 254 insertions(+), 234 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 8c57185..67053f1 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -224,82 +224,82 @@ def binarize_gripper(angle): return traj_segments -def get_kp_clouds(listener, num_clouds): - xyz_tfs = [] - rgb_plots = [] +#def get_kp_clouds(listener, num_clouds): + #xyz_tfs = [] + #rgb_plots = [] - class MessageGetter: + #class MessageGetter: - def __init__(self, n_msgs): - self.n_msgs = n_msgs - self.msgs = [] - self.done = False - def callback(self,msg): - if self.done: - return - elif len(self.msgs) < self.n_msgs: - self.msgs.append(msg) - else: - self.done = True + #def __init__(self, n_msgs): + #self.n_msgs = n_msgs + #self.msgs = [] + #self.done = False + #def callback(self,msg): + #if self.done: + #return + #elif len(self.msgs) < self.n_msgs: + #self.msgs.append(msg) + #else: + #self.done = True - def get_msgs(n_msgs, topic, msgtype): - print "waiting for %i messages on topic %s"%(n_msgs, topic) - mg = MessageGetter(n_msgs) - sub = rospy.Subscriber(topic, msgtype, mg.callback) - while not mg.done: - rospy.sleep(.05) - sub.unregister() - return mg.msgs + #def get_msgs(n_msgs, topic, msgtype): + #print "waiting for %i messages on topic %s"%(n_msgs, topic) + #mg = MessageGetter(n_msgs) + #sub = rospy.Subscriber(topic, msgtype, mg.callback) + #while not mg.done: + #rospy.sleep(.05) + #sub.unregister() + #return mg.msgs - msgs = get_msgs(num_clouds, args.cloud_topic, sm.PointCloud2) + #msgs = get_msgs(num_clouds, args.cloud_topic, sm.PointCloud2) - if num_clouds == 1: - msg = msgs[0] - xyz, rgb = ru.pc2xyzrgb(msg) + #if num_clouds == 1: + #msg = msgs[0] + #xyz, rgb = ru.pc2xyzrgb(msg) - if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - rgb_plot = rgb.copy() + #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + #rgb_plot = rgb.copy() - return xyz_tf, rgb_plot + #return xyz_tf, rgb_plot - else: - for i in range(num_clouds): - msg = msgs[i] - xyz, rgb = ru.pc2xyzrgb(msg) + #else: + #for i in range(num_clouds): + #msg = msgs[i] + #xyz, rgb = ru.pc2xyzrgb(msg) - if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - xyz_tfs.append(xyz_tf) - rgb_plots.append(rgb) + #xyz_tfs.append(xyz_tf) + #rgb_plots.append(rgb) - return xyz_tfs, rgb_plots + #return xyz_tfs, rgb_plots -def find_last_kp_loc(exec_keypts, desired_keypt, current_seg): +#def find_last_kp_loc(exec_keypts, desired_keypt, current_seg): - if search_seg < 1: - print "Reached beginning of execution and couldn't find desired keypoint! Aborting..." - sys.exit(1) - else: - search_seg = current_seg - 1 + #if search_seg < 1: + #print "Reached beginning of execution and couldn't find desired keypoint! Aborting..." + #sys.exit(1) + #else: + #search_seg = current_seg - 1 - while(True): - search_seg_names = exec_keypts[search_seg]["names"] - search_seg_locs = exec_keypts[search_seg]["locations"] + #while(True): + #search_seg_names = exec_keypts[search_seg]["names"] + #search_seg_locs = exec_keypts[search_seg]["locations"] - for k in range(len(search_seg_names)): - if search_seg_names[k] == desired_keypt: - kp_loc = search_seg_locs[k] - kp_found = True + #for k in range(len(search_seg_names)): + #if search_seg_names[k] == desired_keypt: + #kp_loc = search_seg_locs[k] + #kp_found = True - if kp_found: - return kp_loc, search_seg - else: - search_seg -= 1 + #if kp_found: + #return kp_loc, search_seg + #else: + #search_seg -= 1 #def GetLinkMaybeAttached(robot,ee_link): @@ -457,8 +457,7 @@ def keyfunc(fname): # in some segments it's the needle tip left_ee_linkname = segment_info.get("left_end_effector", "l_gripper_tool_frame") right_ee_linkname = segment_info.get("right_end_effector", "r_gripper_tool_frame") - - + if left_ee_linkname == "needle_tip": left_ee_link = needle_tip.GetLinks()[0] demo_left_ee_link = demo_needle_tip @@ -473,81 +472,47 @@ def keyfunc(fname): demo_right_ee_link = demo_robot.GetLink(right_ee_linkname) brett.update_rave() - for k in range(num_kps): - print colorize("Key point from demo is: " + keypt_names[k] + ". Looking for this key point now...", 'green', bold=True) - time.sleep(1) #time.sleep or rospy.sleep?? - sc.show_pointclouds(get_kp_clouds(listener, 1), window_name) - - if yes_or_no(colorize("Is the keypoint visible?", "red")): - - if keypt_names[k] == 'none': - kp_loc = ((0, 0, 0)) - print colorize("No keypoint for this segment", 'green', bold=True) - - elif args.cloud_topic == 'test': - xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) - rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) - elif keypt_names[k] in ['left_hole', 'right_hole', 'stand', 'top_cut', 'mid_cut', 'bot_cut']: - xyz_tf, rgb_plot = get_kp_clouds(listener, 1) - kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) - - elif keypt_names[k] in ['needle_end', 'razor']: - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - kp_loc, pts = sc.find_needle_end(xyz_tfs, rgb_plots, window_name) - if pts > 0: break - else: print colorize("Couldn't find the keypoint! Trying again","red", True, True) - - elif keypt_names[k] == 'needle_tip': - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - kp_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') - if kp_loc[2] > 0.8: break - else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - - elif keypt_names[k] == 'tip_transform': # this is segment where robot looks for tip - demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) - - while True: - xyz_tfs, rgb_plots = get_kp_clouds(listener, 30) - exec_needle_tip_loc = sc.find_needle_tip(xyz_tfs, rgb_plots, window_name, 'execute') - if exec_needle_tip_loc[2] > 1: break - else: print colorize("Didn't find a high enough point! Trying again","red", True, True) - - kp_loc = ((0, 0, 0)) - - def grab_needle_tip(lr): - for demo in [False, True]: - if demo: - tip_loc = demo_needle_tip_loc - grabbing_robot = demo_robot - grabbed_needle_tip = demo_needle_tip - else: - tip_loc = exec_needle_tip_loc - grabbing_robot = robot - grabbed_needle_tip = needle_tip - grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) - grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) + print colorize("Key points from demo: %s"%keypt_names, 'green', bold=True) + time.sleep(1) #time.sleep or rospy.sleep?? + + #if args.cloud_topic == 'test': + #xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) + #rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) + #kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) - if "extra_info" in segment_info: - if "left_grab" in segment_info["extra_info"]: - grab_needle_tip('l') - elif "right_grab" in segment_info["extra_info"]: - grab_needle_tip('r') - - else: - print "Invalid keypoint name! Aborting..." - sys.exit(1) + if keypt_names[0] == 'tip_transform': # this is segment where robot looks for tip + demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) + exec_needle_tip_loc, _ = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) - else: # keypoint occluded - kp_loc, found_seg = find_last_kp_loc(exec_keypts, keypt_names[k], s) - print "keypoint %s found in seg %s at %s" %(keypt_names[k], found_seg, kp_loc) + exec_keypts[s]["locations"].append((0, 0, 0)) + + def grab_needle_tip(lr): + for demo in [False, True]: + if demo: + tip_loc = demo_needle_tip_loc + grabbing_robot = demo_robot + grabbed_needle_tip = demo_needle_tip + else: + tip_loc = exec_needle_tip_loc + grabbing_robot = robot + grabbed_needle_tip = needle_tip + grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) + grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) - - exec_keypts[s]["names"].append(keypt_names[k]) - exec_keypts[s]["locations"].append(kp_loc) - + if "extra_info" in segment_info: + if "left_grab" in segment_info["extra_info"]: + grab_needle_tip('l') + elif "right_grab" in segment_info["extra_info"]: + grab_needle_tip('r') + + else: + keypt_locs, keypt_pixels = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) + exec_keypts[s]["locations"] = keypt_locs + + for (n, name) in enumerate(keypt_names): exec_keypts[s]["names"].append(keypt_names[n]) + print 'exec_kp_names', exec_keypts[s]["names"] + demopoints_m3 = np.array(demo_keypts[s]) newpoints_m3 = np.array(exec_keypts[s]["locations"]) @@ -569,7 +534,6 @@ def grab_needle_tip(lr): print "residual", f.transform_points(demopoints_m3) - newpoints_m3 - for (i, mini_segment) in enumerate(mini_segments[s]): brett.update_rave() @@ -689,4 +653,4 @@ def remove_winding(arm_traj, current_arm_vals): else: print colorize("skipping right arm", 'yellow', bold=True, highlight=True) - trajectories.follow_body_traj2(brett, bodypart2traj, speed_factor=.5) + trajectories.follow_body_traj2(brett, bodypart2traj, speed_factor=.5) \ No newline at end of file diff --git a/iros/simple_clicker.py b/iros/simple_clicker.py index 6dba74b..c3fb6a9 100644 --- a/iros/simple_clicker.py +++ b/iros/simple_clicker.py @@ -2,28 +2,162 @@ import cv2 import numpy as np import sys +import rospy from jds_utils.colorize import colorize +import brett2.ros_utils as ru +import sensor_msgs.msg as sm -def show_pointclouds(clouds, window_name): +WIN_NAME = "Find Keypoints" + +def get_kp_clouds(listener, cloud_topic, num_clouds): + + class MessageGetter: + + def __init__(self, n_msgs): + self.n_msgs = n_msgs + self.msgs = [] + self.done = False + def callback(self,msg): + if self.done: + return + elif len(self.msgs) < self.n_msgs: + self.msgs.append(msg) + else: + self.done = True + + def get_msgs(n_msgs, topic, msgtype): + print "waiting for %i messages on topic %s"%(n_msgs, topic) + mg = MessageGetter(n_msgs) + sub = rospy.Subscriber(topic, msgtype, mg.callback) + while not mg.done: + rospy.sleep(.05) + sub.unregister() + return mg.msgs + + msgs = get_msgs(num_clouds, cloud_topic, sm.PointCloud2) + + if num_clouds == 1: + msg = msgs[0] + xyz, rgb = ru.pc2xyzrgb(msg) + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + rgb_plot = rgb.copy() + + return xyz_tf, rgb_plot + + else: + xyz_tfs = [] + rgb_plots = [] + for i in range(num_clouds): + msg = msgs[i] + xyz, rgb = ru.pc2xyzrgb(msg) + + if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") + + xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") + + xyz_tfs.append(xyz_tf) + rgb_plots.append(rgb) + + return xyz_tfs, rgb_plots + + +def get_last_kp_loc(exec_keypts, desired_keypt, current_seg): + + search_seg = current_seg - 1 + + while(True): + if search_seg < 0: + print "Reached beginning of execution and couldn't find desired keypoint! Aborting..." + sys.exit(1) + else: + search_seg_names = exec_keypts[search_seg]["names"] + search_seg_locs = exec_keypts[search_seg]["locations"] + + for k in range(len(search_seg_names)): + if search_seg_names[k] == desired_keypt: + kp_loc = search_seg_locs[k] + kp_found = True + + if kp_found: + return kp_loc, search_seg + else: + search_seg -= 1 + + +def show_pointclouds(clouds, WIN_NAME): nc = len(clouds) if nc == 2: rgb_plot = clouds[1].copy() - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(100) else: rgb_plot_multi = [] for i in range(nc): rgb_plot_multi.append(clouds[i][1].copy()) - cv2.imshow(window_name, rgb_plot_multi[i]) + cv2.imshow(WIN_NAME, rgb_plot_multi[i]) cv2.waitKey(100) +######################################### +### find all keypoints +######################################### +def get_kp_locations(kp_names, exec_keypts, current_seg, cloud_topic): + listener = ru.get_tf_listener() + kp_locations = [] + kp_xypixels = [] + + seg_kps = [] + if kp_names[0] == "tip_transform": + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, cloud_topic, 30) + needle_tip_loc = find_needle_tip(xyz_tfs, rgb_plots, WIN_NAME) + if needle_tip_loc[2] > 1: + return needle_tip_loc, kp_xypixels.append((0,0)) + else: + print colorize("Didn't find a high enough point! Trying again","red", True, True) + + elif kp_names[0] in ["needle_end", "razor"]: + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, cloud_topic, 30) + kp_loc, pts = find_red_block(xyz_tfs, rgb_plots, WIN_NAME) + if pts > 0: + seg_kps.append(kp_loc) + kp_xypixels.append((0,0)) + break + else: + print colorize("Couldn't find the keypoint! Trying again","red", True, True) + + elif kp_names[0] == "needle_tip": + while True: + xyz_tfs, rgb_plots = get_kp_clouds(listener, cloud_topic, 30) + kp_loc = find_needle_tip(xyz_tfs, rgb_plots, WIN_NAME) + if kp_loc[2] > 0.8: + seg_kps.append(kp_loc) + kp_xypixels.append((0,0)) + break + else: + print colorize("Didn't find a high enough point! Trying again","red", True, True) + + else: + xyz_tf, rgb_plot = get_kp_clouds(listener, cloud_topic, 1) + for k in range(len(kp_names)): + kp_loc, kp_xypix = find_kp(kp_names[k], xyz_tf, rgb_plot, WIN_NAME) + kp_xypixels.append(kp_xypix) + seg_kps.append(kp_loc) + + return seg_kps, kp_xypixels + + + ######################################### ### find a single keypoint ######################################### -def find_kp(kp, xyz_tf, rgb_plot, window_name): +def find_kp(kp, xyz_tf, rgb_plot, WIN_NAME): ### clicking set-up class GetClick: x = None @@ -39,15 +173,15 @@ def callback(self, event, x, y, flags, param): print colorize("click on the center of the " + kp, 'red', bold=True) gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) + cv2.setMouseCallback(WIN_NAME, gc.callback) while not gc.done: - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(10) row_kp = gc.x col_kp = gc.y cv2.circle(rgb_plot, (row_kp, col_kp), 5, (0, 0, 255), -1) - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(100) xyz_tf[np.isnan(xyz_tf)] = -2 @@ -55,90 +189,13 @@ def callback(self, event, x, y, flags, param): print kp, "3d location", x, y, z - return (x, y, z) - - -######################################### -### find cut -######################################### -def find_cut(xyz_tf, rgb_plot, window_name): - - ### clicking set-up - class GetClick: - x = None - y = None - xy = None - done = False - def callback(self, event, x, y, flags, param): - if self.done: - return - elif event == cv2.EVENT_LBUTTONDOWN: - self.x = x - self.y = y - self.xy = (x,y) - self.done = True - - xy_t = [] - xy_m = [] - xy_b = [] - - #print colorize("click at the top of the cut line", 'red', bold=True) - #gc = GetClick() - #cv2.setMouseCallback(window_name, gc.callback) - #while not gc.done: - #cv2.imshow(window_name, rgb_plot) - #cv2.waitKey(10) - #xy_t.append(gc.x) - #xy_t.append(gc.y) - - #x_tcut, y_tcut, z_tcut = xyz_tf[xy_t[1], xy_t[0]] - #tcut_loc = (x_tcut, y_tcut, z_tcut) - #cv2.circle(rgb_plot, (xy_t[0], xy_t[1]), 5, (0, 0, 255), -1) - #cv2.imshow(window_name, rgb_plot) - #cv2.waitKey(100) - - print colorize("click the cut line in between the holes", 'red', bold=True) - gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) - while not gc.done: - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(10) - xy_m.append(gc.x) - xy_m.append(gc.y) - - x_mcut, y_mcut, z_mcut = xyz_tf[xy_m[1], xy_m[0]] - mcut_loc = (x_mcut, y_mcut, z_mcut) - cv2.circle(rgb_plot, (xy_m[0], xy_m[1]), 5, (0,0, 255), -1) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) - - #print colorize("click the bottom of the cut line", 'red', bold=True) - #gc = GetClick() - #cv2.setMouseCallback(window_name, gc.callback) - #while not gc.done: - #cv2.imshow(window_name, rgb_plot) - #cv2.waitKey(10) - #xy_b.append(gc.x) - #xy_b.append(gc.y) - - #x_bcut, y_bcut, z_bcut = xyz_tf[xy_b[1], xy_b[0]] - #bcut_loc = (x_bcut, y_bcut, z_bcut) - - #cv2.circle(rgb_plot, (xy_b[0], xy_b[1]), 5, (0, 0, 255), -1) - #cv2.imshow(window_name, rgb_plot) - #cv2.waitKey(100) - - #print 'cut top 3d location', x_tcut, y_tcut, z_tcut - print 'cut middle cut 3d location', x_mcut, y_mcut, z_mcut - #print 'cut bottom 3d location', x_bcut, y_bcut, z_bcut - - return mcut_loc + return (x, y, z), (col_kp, row_kp) ######################################### ### find needle ######################################### -def find_needle_tip(xyz_tfs, rgb_plots, window_name, caller): +def find_needle_tip(xyz_tfs, rgb_plots, WIN_NAME): ### clicking set-up class GetClick: @@ -159,9 +216,9 @@ def callback(self, event, x, y, flags, param): for i in xrange(2): gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) + cv2.setMouseCallback(WIN_NAME, gc.callback) while not gc.done: - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(10) needle_rect_corners.append(gc.xy) @@ -169,7 +226,7 @@ def callback(self, event, x, y, flags, param): xy_br = np.array(needle_rect_corners).max(axis=0) cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(10) colmin, rowmin = xy_tl @@ -206,15 +263,14 @@ def callback(self, event, x, y, flags, param): max_needle.append(yneedle[ind]) max_needle.append(zneedle[ind]) - if caller == 'process': - cv2.circle(rgb_plots[ind], (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) - cv2.imshow(window_name, rgb_plots[ind]) - cv2.waitKey(100) + #cv2.circle(rgb_plots[ind], (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + #cv2.imshow(WIN_NAME, rgb_plots[ind]) + #cv2.waitKey(100) - else: - cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) - cv2.imshow(window_name, rgb_plot) - cv2.waitKey(100) + + cv2.circle(rgb_plot, (col_needle[ind], row_needle[ind]), 3, (255, 0, 0), 2) + cv2.imshow(WIN_NAME, rgb_plot) + cv2.waitKey(100) print 'needle tip 3d location', max_needle @@ -233,7 +289,7 @@ def callback(self, event, x, y, flags, param): ######################################### ### find needle ######################################### -def find_needle_end(xyz_tfs, rgbs, window_name): +def find_red_block(xyz_tfs, rgbs, WIN_NAME): ### clicking set-up class GetClick: @@ -253,9 +309,9 @@ def callback(self, event, x, y, flags, param): for i in xrange(2): gc = GetClick() - cv2.setMouseCallback(window_name, gc.callback) + cv2.setMouseCallback(WIN_NAME, gc.callback) while not gc.done: - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(10) needle_rect_corners.append(gc.xy) @@ -263,7 +319,7 @@ def callback(self, event, x, y, flags, param): xy_br = np.array(needle_rect_corners).max(axis=0) cv2.rectangle(rgb_plot, tuple(xy_tl), tuple(xy_br), (0, 255, 0)) - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(100) colmin, rowmin = xy_tl @@ -300,7 +356,7 @@ def callback(self, event, x, y, flags, param): row, col = xyz2uv(xyz_avg).astype('int')[0] cv2.circle(rgb_plot, (row, col), 3, (255, 0, 0), 2) - cv2.imshow(window_name, rgb_plot) + cv2.imshow(WIN_NAME, rgb_plot) cv2.waitKey(100) print 'Needle end location', xyz_avg From 7fe3dc4dead3c762ee0cd15e7a014a6217ecc890 Mon Sep 17 00:00:00 2001 From: Mallory Tayson Frederick Date: Wed, 13 Mar 2013 13:25:56 -0700 Subject: [PATCH 25/26] updates for getting data --- iros/execute_suture_traj.py | 243 ++++++++++++++---------------------- iros/simple_clicker.py | 36 ++++-- 2 files changed, 118 insertions(+), 161 deletions(-) diff --git a/iros/execute_suture_traj.py b/iros/execute_suture_traj.py index 67053f1..19b59aa 100644 --- a/iros/execute_suture_traj.py +++ b/iros/execute_suture_traj.py @@ -6,6 +6,7 @@ parser.add_argument("part_index",type=int) parser.add_argument("--segment_index", type=int, default=0) parser.add_argument("--interactive",action="store_true") +parser.add_argument("--no_movement",action="store_true") args = parser.parse_args() import numpy as np @@ -108,11 +109,6 @@ CLOSED_ANGLE = 0 -def call_and_print(cmd,color='green'): - print colorize(cmd, color, bold=True) - subprocess.check_call(cmd, shell=True) - - def transform_hmats(f, hmats): hmats = np.array(hmats) oldpts_md = hmats[:,:3,3] @@ -223,83 +219,6 @@ def binarize_gripper(angle): traj_segments.append(TrajSegment( larm[i_start:i_end+1], rarm[i_start:i_end+1], l_angle, r_angle )) return traj_segments - -#def get_kp_clouds(listener, num_clouds): - #xyz_tfs = [] - #rgb_plots = [] - - #class MessageGetter: - - #def __init__(self, n_msgs): - #self.n_msgs = n_msgs - #self.msgs = [] - #self.done = False - #def callback(self,msg): - #if self.done: - #return - #elif len(self.msgs) < self.n_msgs: - #self.msgs.append(msg) - #else: - #self.done = True - - #def get_msgs(n_msgs, topic, msgtype): - #print "waiting for %i messages on topic %s"%(n_msgs, topic) - #mg = MessageGetter(n_msgs) - #sub = rospy.Subscriber(topic, msgtype, mg.callback) - #while not mg.done: - #rospy.sleep(.05) - #sub.unregister() - #return mg.msgs - - #msgs = get_msgs(num_clouds, args.cloud_topic, sm.PointCloud2) - - #if num_clouds == 1: - #msg = msgs[0] - #xyz, rgb = ru.pc2xyzrgb(msg) - - #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - - #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - #rgb_plot = rgb.copy() - - #return xyz_tf, rgb_plot - - #else: - #for i in range(num_clouds): - #msg = msgs[i] - #xyz, rgb = ru.pc2xyzrgb(msg) - - #if (xyz.shape[0] == 1 or xyz.shape[1] == 1): raise Exception("needs to be an organized point cloud") - - #xyz_tf = ru.transform_points(xyz, listener, "base_footprint", "/camera_rgb_optical_frame") - - #xyz_tfs.append(xyz_tf) - #rgb_plots.append(rgb) - - #return xyz_tfs, rgb_plots - - -#def find_last_kp_loc(exec_keypts, desired_keypt, current_seg): - - #if search_seg < 1: - #print "Reached beginning of execution and couldn't find desired keypoint! Aborting..." - #sys.exit(1) - #else: - #search_seg = current_seg - 1 - - #while(True): - #search_seg_names = exec_keypts[search_seg]["names"] - #search_seg_locs = exec_keypts[search_seg]["locations"] - - #for k in range(len(search_seg_names)): - #if search_seg_names[k] == desired_keypt: - #kp_loc = search_seg_locs[k] - #kp_found = True - - #if kp_found: - #return kp_loc, search_seg - #else: - #search_seg -= 1 #def GetLinkMaybeAttached(robot,ee_link): @@ -441,77 +360,100 @@ def keyfunc(fname): demo_robot.Grab(demo_needle_tip) for s in range(args.segment_index, SEGNUM): + + snapshot_count = 0 + while True: + segment_info = task_info[args.task][args.part_index]["segments"][s] + keypt_names = segment_info["keypts_to_look_for"] + num_kps = len(keypt_names) + + print colorize("trajectory segment %i"%s, 'blue', bold=True, highlight=True) - segment_info = task_info[args.task][args.part_index]["segments"][s] - keypt_names = segment_info["keypts_to_look_for"] - num_kps = len(keypt_names) - - print colorize("trajectory segment %i"%s, 'blue', bold=True, highlight=True) - - # keep track of keypts seen during each segment - exec_keypts[s] = {} - exec_keypts[s]["names"] = [] - exec_keypts[s]["locations"] = [] - - # this is the frame whose trajectory we'll adapt to the new situation - # in some segments it's the needle tip - left_ee_linkname = segment_info.get("left_end_effector", "l_gripper_tool_frame") - right_ee_linkname = segment_info.get("right_end_effector", "r_gripper_tool_frame") - - if left_ee_linkname == "needle_tip": - left_ee_link = needle_tip.GetLinks()[0] - demo_left_ee_link = demo_needle_tip - else: - left_ee_link = robot.GetLink(left_ee_linkname) - demo_left_ee_link = demo_robot.GetLink(left_ee_linkname) - if right_ee_linkname == "needle_tip": - right_ee_link = needle_tip.GetLinks()[0] - demo_right_ee_link = demo_needle_tip - else: - right_ee_link = robot.GetLink(right_ee_linkname) - demo_right_ee_link = demo_robot.GetLink(right_ee_linkname) - - brett.update_rave() - - print colorize("Key points from demo: %s"%keypt_names, 'green', bold=True) - time.sleep(1) #time.sleep or rospy.sleep?? + # keep track of keypts seen during each segment + exec_keypts[s] = {} + exec_keypts[s]["names"] = [] + exec_keypts[s]["locations"] = [] + + # this is the frame whose trajectory we'll adapt to the new situation + # in some segments it's the needle tip + left_ee_linkname = segment_info.get("left_end_effector", "l_gripper_tool_frame") + right_ee_linkname = segment_info.get("right_end_effector", "r_gripper_tool_frame") + + if left_ee_linkname == "needle_tip": + left_ee_link = needle_tip.GetLinks()[0] + demo_left_ee_link = demo_needle_tip + else: + left_ee_link = robot.GetLink(left_ee_linkname) + demo_left_ee_link = demo_robot.GetLink(left_ee_linkname) + if right_ee_linkname == "needle_tip": + right_ee_link = needle_tip.GetLinks()[0] + demo_right_ee_link = demo_needle_tip + else: + right_ee_link = robot.GetLink(right_ee_linkname) + demo_right_ee_link = demo_robot.GetLink(right_ee_linkname) - #if args.cloud_topic == 'test': - #xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) - #rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) - #kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) + brett.update_rave() + + print colorize("Key points from demo: %s"%keypt_names, 'green', bold=True) + time.sleep(1) #time.sleep or rospy.sleep?? + + #if args.cloud_topic == 'test': + #xyz_tf = np.load(pcf + '/seg%s_' + keypt_names[k] + '_xyz_tf.npy'%s) + #rgb_plot = np.load(pcf + '/seg%s_' + keypt_names[k] + '_rgb_pl.npy'%s) + #kp_loc = sc.find_kp(keypt_names[k], xyz_tf, rgb_plot, window_name) + + if keypt_names[0] == 'tip_transform': # this is segment where robot looks for tip + demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) + exec_needle_tip_loc = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) - if keypt_names[0] == 'tip_transform': # this is segment where robot looks for tip - demo_needle_tip_loc = np.load(osp.join(IROS_DATA_DIR, kpf, "seg%s_needle_world_loc.npy"%s)) - exec_needle_tip_loc, _ = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) + exec_keypts[s]["locations"].append((0, 0, 0)) + + def grab_needle_tip(lr): + for demo in [False, True]: + if demo: + tip_loc = demo_needle_tip_loc + grabbing_robot = demo_robot + grabbed_needle_tip = demo_needle_tip + else: + tip_loc = exec_needle_tip_loc + grabbing_robot = robot + grabbed_needle_tip = needle_tip + grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) + grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) - exec_keypts[s]["locations"].append((0, 0, 0)) - - def grab_needle_tip(lr): - for demo in [False, True]: - if demo: - tip_loc = demo_needle_tip_loc - grabbing_robot = demo_robot - grabbed_needle_tip = demo_needle_tip - else: - tip_loc = exec_needle_tip_loc - grabbing_robot = robot - grabbed_needle_tip = needle_tip - grabbed_needle_tip.SetTransform(translation_matrix(tip_loc)) - grabbing_robot.Grab(grabbed_needle_tip, grabbing_robot.GetLink("%s_gripper_tool_frame"%lr)) + if "extra_info" in segment_info: + if "left_grab" in segment_info["extra_info"]: + grab_needle_tip('l') + elif "right_grab" in segment_info["extra_info"]: + grab_needle_tip('r') + + else: + keypt_locs = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) + exec_keypts[s]["locations"] = keypt_locs + + for (n, name) in enumerate(keypt_names): exec_keypts[s]["names"].append(keypt_names[n]) - if "extra_info" in segment_info: - if "left_grab" in segment_info["extra_info"]: - grab_needle_tip('l') - elif "right_grab" in segment_info["extra_info"]: - grab_needle_tip('r') - - else: - keypt_locs, keypt_pixels = sc.get_kp_locations(keypt_names, exec_keypts, s, args.cloud_topic) - exec_keypts[s]["locations"] = keypt_locs - - for (n, name) in enumerate(keypt_names): exec_keypts[s]["names"].append(keypt_names[n]) - print 'exec_kp_names', exec_keypts[s]["names"] + rgbfile = glob(osp.join(IROS_DATA_DIR, args.task, 'point_clouds', 'pt%i/seg%i_*_rgb_*.npy'%(PARTNUM, s)))[0] + xyzfile = glob(osp.join(IROS_DATA_DIR, args.task, 'point_clouds', 'pt%i/seg%i_*_xyz_tf*.npy'%(PARTNUM, s)))[0] + + if keypt_names[0] not in [ "needle_end", "needle_tip", "razor", "tip_transform"]: + np.savez(osp.join(IROS_DATA_DIR, "segment%.2i_snapshot%.2i_time%i"%(s,snapshot_count,int(time.time()))), + demo_rgb = np.load(rgbfile), + demo_xyz = np.load(xyzfile), + current_rgb = np.load("/tmp/rgb.npy"), + current_xyz = np.load("/tmp/xyz_tf.npy"), + keypts_names = keypt_names, + demo_keypts = demo_keypts[s], + exec_keypts = exec_keypts[s]["locations"] + ) + snapshot_count += 1 + if yes_or_no("done with snapshots?"): + print colorize("going on to next segment","red") + break + else: + print colorize("this segment doesn't have image keypoints. moving on","red") + break + print colorize("acquiring another snapshot", "blue") demopoints_m3 = np.array(demo_keypts[s]) newpoints_m3 = np.array(exec_keypts[s]["locations"]) @@ -653,4 +595,7 @@ def remove_winding(arm_traj, current_arm_vals): else: print colorize("skipping right arm", 'yellow', bold=True, highlight=True) - trajectories.follow_body_traj2(brett, bodypart2traj, speed_factor=.5) \ No newline at end of file + if args.no_movement: + print colorize("skipping arm movement","yellow",bold=True,highlight=True) + else: + trajectories.follow_body_traj2(brett, bodypart2traj, speed_factor=.5) \ No newline at end of file diff --git a/iros/simple_clicker.py b/iros/simple_clicker.py index c3fb6a9..7119728 100644 --- a/iros/simple_clicker.py +++ b/iros/simple_clicker.py @@ -109,7 +109,7 @@ def show_pointclouds(clouds, WIN_NAME): def get_kp_locations(kp_names, exec_keypts, current_seg, cloud_topic): listener = ru.get_tf_listener() kp_locations = [] - kp_xypixels = [] + #kp_xypixels = [] seg_kps = [] if kp_names[0] == "tip_transform": @@ -117,7 +117,7 @@ def get_kp_locations(kp_names, exec_keypts, current_seg, cloud_topic): xyz_tfs, rgb_plots = get_kp_clouds(listener, cloud_topic, 30) needle_tip_loc = find_needle_tip(xyz_tfs, rgb_plots, WIN_NAME) if needle_tip_loc[2] > 1: - return needle_tip_loc, kp_xypixels.append((0,0)) + return needle_tip_loc else: print colorize("Didn't find a high enough point! Trying again","red", True, True) @@ -127,7 +127,7 @@ def get_kp_locations(kp_names, exec_keypts, current_seg, cloud_topic): kp_loc, pts = find_red_block(xyz_tfs, rgb_plots, WIN_NAME) if pts > 0: seg_kps.append(kp_loc) - kp_xypixels.append((0,0)) + #kp_xypixels.append((0,0)) break else: print colorize("Couldn't find the keypoint! Trying again","red", True, True) @@ -138,26 +138,28 @@ def get_kp_locations(kp_names, exec_keypts, current_seg, cloud_topic): kp_loc = find_needle_tip(xyz_tfs, rgb_plots, WIN_NAME) if kp_loc[2] > 0.8: seg_kps.append(kp_loc) - kp_xypixels.append((0,0)) + #kp_xypixels.append((0,0)) break else: print colorize("Didn't find a high enough point! Trying again","red", True, True) else: xyz_tf, rgb_plot = get_kp_clouds(listener, cloud_topic, 1) + np.save("/tmp/xyz_tf.npy",xyz_tf) + np.save("/tmp/rgb.npy",rgb_plot) for k in range(len(kp_names)): - kp_loc, kp_xypix = find_kp(kp_names[k], xyz_tf, rgb_plot, WIN_NAME) - kp_xypixels.append(kp_xypix) + kp_loc = find_kp(kp_names[k], xyz_tf, rgb_plot, exec_keypts, current_seg, WIN_NAME) + #kp_xypixels.append(kp_xypix) seg_kps.append(kp_loc) - return seg_kps, kp_xypixels + return seg_kps ######################################### ### find a single keypoint ######################################### -def find_kp(kp, xyz_tf, rgb_plot, WIN_NAME): +def find_kp(kp, xyz_tf, rgb_plot, past_keypts, current_seg, WIN_NAME): ### clicking set-up class GetClick: x = None @@ -170,13 +172,22 @@ def callback(self, event, x, y, flags, param): self.x = x self.y = y self.done = True - - print colorize("click on the center of the " + kp, 'red', bold=True) + + print colorize("Click on the center of the %s."%kp, 'red', bold=True) + print colorize("If this keypont is occluded, select the image window and press any key", 'red', bold=True) + gc = GetClick() cv2.setMouseCallback(WIN_NAME, gc.callback) while not gc.done: cv2.imshow(WIN_NAME, rgb_plot) - cv2.waitKey(10) + k = cv2.waitKey(100) + if k == -1: + continue + else: + last_loc, found_seg = get_last_kp_loc(past_keypts, kp, current_seg) + print kp, "found in segment %s at location %s"%(found_seg, last_loc) + return last_loc + row_kp = gc.x col_kp = gc.y @@ -189,7 +200,8 @@ def callback(self, event, x, y, flags, param): print kp, "3d location", x, y, z - return (x, y, z), (col_kp, row_kp) + #return (x, y, z), (col_kp, row_kp) + return (x, y, z) ######################################### From 03d16f51d2a6de7f6b26002c782e394f098bf7ae Mon Sep 17 00:00:00 2001 From: John Schulman Date: Thu, 21 Mar 2013 09:56:54 -0700 Subject: [PATCH 26/26] various iros stuff --- iros/follow_pose_traj.py | 39 ++++++++---- iros/image_registration.py | 81 +++++++++++++++++++++++-- iros/iros_registration.py | 0 iros/iros_tps.py | 118 +++++++++++++++++++++++++++++++++++++ iros/test_tps_fitting.py | 61 +++++++++++++++++++ 5 files changed, 282 insertions(+), 17 deletions(-) create mode 100644 iros/iros_registration.py create mode 100644 iros/iros_tps.py create mode 100644 iros/test_tps_fitting.py diff --git a/iros/follow_pose_traj.py b/iros/follow_pose_traj.py index 07b46ac..3e6b3f8 100644 --- a/iros/follow_pose_traj.py +++ b/iros/follow_pose_traj.py @@ -5,6 +5,7 @@ import trajoptpy import openravepy +from openravepy import planningutils import numpy as np import json import trajoptpy.math_utils as mu @@ -50,8 +51,19 @@ env.Load(osp.join(osp.dirname(lfd.__file__), "data/table2.xml")) ####################### +def retime_traj(traj, robot): + traj_obj = openravepy.RaveCreateTrajectory(env,'') + traj_obj.Init(robot.GetActiveConfigurationSpecification()) + for row in traj: + traj_obj.Insert(0,row) + planningutils.RetimeActiveDOFTrajectory(traj_obj,robot,hastimestamps=False,maxvelmult=1,maxaccelmult=1,plannername='ParabolicTrajectoryRetimer') + new_traj = [] + durations = [] - + for i in xrange(traj_obj.GetNumWaypoints()): + new_traj.append(traj_obj.GetWaypoint(i)[:14]) + durations.append(traj_obj.GetWaypoint(i)[-1]) + return np.array(new_traj), np.cumsum(durations) def adaptive_resample(x, tol, max_change=None, min_steps=3): """ @@ -168,8 +180,7 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj): result = trajoptpy.OptimizeProblem(prob) # do optimization traj = result.GetTraj() - - + assert (robot.GetDOFLimits()[0][robot.GetManipulator(manip_name).GetArmIndices()] <= traj.min(axis=0)).all() return traj ################################### @@ -178,8 +189,10 @@ def plan_follow_traj(robot, manip_name, new_hmats, old_traj): IROS_DATA_DIR = os.getenv("IROS_DATA_DIR") -def keyfunc(fname): return int(osp.basename(fname).split("_")[0][2:]) # sort files with names like pt1_larm.npy -lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(osp.join(IROS_DATA_DIR, "InterruptedSutureTrajectories/pt*%s.npy"%partname)), +PARTNUM = 0 +SEGMENT_NUM = 0 +def keyfunc(fname): return int(osp.basename(fname).split("_")[0][3:]) # sort files with names like pt1_larm.npy +lgrip_files, rgrip_files, larm_files, rarm_files = [sorted(glob(osp.join(IROS_DATA_DIR, "InterruptedSuture0/joint_trajectories/pt%i/seg*_%s.npy"%(PARTNUM, partname))), key = keyfunc) for partname in ("lgrip", "rgrip", "larm", "rarm")] @@ -230,12 +243,11 @@ def binarize_gripper(angle): #IPython.embed() return traj_segments -PARTNUM = 0 segments = segment_trajectory( - np.load(larm_files[PARTNUM]), - np.load(rarm_files[PARTNUM]), - np.load(lgrip_files[PARTNUM]), - np.load(rgrip_files[PARTNUM])) + np.load(larm_files[SEGMENT_NUM]), + np.load(rarm_files[SEGMENT_NUM]), + np.load(lgrip_files[SEGMENT_NUM]), + np.load(rgrip_files[SEGMENT_NUM])) print "trajectory broken into %i segments by gripper transitions"%len(segments) @@ -248,7 +260,7 @@ def binarize_gripper(angle): full_traj = np.c_[segment.larm_traj, segment.rarm_traj] full_traj = mu.remove_duplicate_rows(full_traj) orig_times = np.arange(len(full_traj)) - ds_times, ds_traj = adaptive_resample(full_traj, tol=.025, max_change=.1) # about 2.5 degrees, 10 degrees + ds_times, ds_traj = adaptive_resample(full_traj, tol=.01, max_change=.1) # about 2.5 degrees, 10 degrees n_steps = len(ds_traj) @@ -280,7 +292,7 @@ def binarize_gripper(angle): trajoptpy.SetInteractive(False) - best_left_path = plan_follow_traj(robot, "rightarm", left_hmats, ds_traj[:,:7]) + best_left_path = plan_follow_traj(robot, "leftarm", left_hmats, ds_traj[:,:7]) best_right_path = plan_follow_traj(robot, "rightarm", right_hmats, ds_traj[:,7:]) @@ -292,11 +304,12 @@ def binarize_gripper(angle): ################################## #### Now view/execute the trajectory ################################## - + if args.mode == "openrave": robot.SetActiveDOFs(np.r_[robot.GetManipulator("leftarm").GetArmIndices(), robot.GetManipulator("rightarm").GetArmIndices()]) viewer = trajoptpy.GetViewer(env) joint_traj = np.c_[best_left_path, best_right_path] + joints, times = retime_traj(joint_traj,robot) # *5 factor is due to an openrave oddity robot.SetDOFValues([segment.lgrip_angle*5, segment.rgrip_angle*5], [robot.GetJoint("l_gripper_l_finger_joint").GetDOFIndex(), robot.GetJoint("r_gripper_l_finger_joint").GetDOFIndex()], False) for (i,row) in enumerate(joint_traj): diff --git a/iros/image_registration.py b/iros/image_registration.py index 4a51f10..061a615 100644 --- a/iros/image_registration.py +++ b/iros/image_registration.py @@ -3,7 +3,8 @@ import scipy.ndimage as ndi import itertools as it import scipy.spatial.distance as ssd -from jds_utils.shortest_paths import shortest_paths +import jds_utils.shortest_paths as sp +import jds_utils.math_utils as mu DEBUG_PLOTTING = False PLOT_COUNTER = 0 @@ -23,7 +24,8 @@ def register_images(src_img, targ_img, src_xys_n): vs_n.append(vs) rankvs_n.append(0*np.arange(len(vs))) - matchinds_n = dp_match(xys_n, rankvs_n, src_xys_n) + #matchinds_n = dp_match(xys_n, rankvs_n, src_xys_n) + matchinds_n = dp_match_ternary(xys_n, rankvs_n, src_xys_n) return [xys_n[i][m] for (i,m) in enumerate(matchinds_n)] @@ -47,13 +49,84 @@ def dp_match(xys_n, vs_n, src_xys_n): edgecosts_ab = np.sqrt((diffdiff_abd**2).sum(axis=2)) edgecosts.append(edgecosts_ab) - paths_mn, costs_m = shortest_paths(nodecosts, edgecosts) + paths_mn, costs_m = sp.shortest_paths(nodecosts, edgecosts) + + + bestpath_n = paths_mn[np.argmin(costs_m)] return bestpath_n +def dp_match_ternary(xys_n, vs_n, src_xys_n): + N = len(xys_n) + assert len(vs_n) == N + assert len(src_xys_n) == N + + nodecosts = vs_n + edgecosts = [] + tripcosts = [] + + + diff_d = (np.array(src_xys_n[0]) - np.array(src_xys_n[1]))[None,:] + diff_abd = xys_n[0][:,None,:] - xys_n[1][None,:,:] + lengths_ab = mu.norms(diff_abd, 2) + edge_coef = 10 + edgecosts.append(np.abs(np.log(lengths_ab / np.linalg.norm(diff_d)))*edge_coef) + + #edgecosts.append(np.zeros((xys_n[0].shape[0],xys_n[1].shape[0]))) + for n in xrange(2,N): + xys_ad = xys_n[n-2] + xys_bd = xys_n[n-1] + xys_cd = xys_n[n] + A = len(xys_ad) + B = len(xys_bd) + C = len(xys_cd) + tripcosts_abc = np.empty((A,B,C)) + oldtri = np.array([src_xys_n[n-2], src_xys_n[n-1], src_xys_n[n]]) + oldsides = np.array([oldtri[1]-oldtri[2], oldtri[2]-oldtri[0], oldtri[0]-oldtri[1]]) + oldcomplex = oldsides[:,0] + 1j*oldsides[:,1] + oldcomplexratios = np.array([oldcomplex[1]/oldcomplex[2],oldcomplex[2]/oldcomplex[0],oldcomplex[0]/oldcomplex[1]]) + oldsidelengths = mu.norms(oldsides, 1) + oldangles = np.arccos([oldsides[1].dot(oldsides[2])/np.linalg.norm(oldsides[1])/np.linalg.norm(oldsides[2]), + oldsides[2].dot(oldsides[0])/np.linalg.norm(oldsides[2])/np.linalg.norm(oldsides[0]), + oldsides[0].dot(oldsides[1])/np.linalg.norm(oldsides[0])/np.linalg.norm(oldsides[1])]) + for a in xrange(A): + for b in xrange(B): + for c in xrange(C): + + newtri = np.array([xys_ad[a], xys_bd[b], xys_cd[c]]) + newsides = np.array([newtri[1]-newtri[2],newtri[2]-newtri[0], newtri[0]-newtri[1]]) + #newsidelengths = mu.norms(newsides,1) + newcomplex = newsides[:,0] + 1j*newsides[:,1] + newcomplexratios = np.array([newcomplex[1]/newcomplex[2],newcomplex[2]/newcomplex[0],newcomplex[0]/newcomplex[1]]) + + #newangles = np.arccos([newsides[1].dot(newsides[2])/np.linalg.norm(newsides[1])/np.linalg.norm(newsides[2]), + #newsides[2].dot(newsides[0])/np.linalg.norm(newsides[2])/np.linalg.norm(newsides[0]), + #newsides[0].dot(newsides[1])/np.linalg.norm(newsides[0])/np.linalg.norm(newsides[1])]) + #tripcosts_abc[a,b,c] = np.linalg.norm(newsidelengths - oldsidelengths) + #tripcosts_abc[a,b,c] = np.linalg.norm(newangles - oldangles)*10 + tripcosts_abc[a,b,c] = (np.abs(newcomplexratios - oldcomplexratios)**2).sum() + tripcosts.append(tripcosts_abc) + + + diff_d = (np.array(src_xys_n[n-1]) - np.array(src_xys_n[n]))[None,:] + diff_bcd = xys_bd[:,None,:] - xys_cd[None,:,:] + lengths_bc = mu.norms(diff_bcd, 2) + edgecosts.append(np.abs(np.log(lengths_bc / np.linalg.norm(diff_d)))*edge_coef) + + + #diff_d = (np.array(src_xys_n[n]) - np.array(src_xys_n[n+1]))[None,:] + #diff_abd = xys_ad[:,None,:] - xys_bd[None,:,:] + #diffdiff_abd = diff_abd - diff_d + #edgecosts_ab = np.sqrt((diffdiff_abd**2).sum(axis=2)) + #edgecosts.append(edgecosts_ab) + + + bestpath,cost = sp.shortest_paths_ternary(nodecosts, edgecosts,tripcosts) + print "cost",cost + return bestpath -def get_matches(src_img, xy, targ_img, patch_size = 59, max_deficit = .3, min_match_distance = 10, max_num_matches = 20): +def get_matches(src_img, xy, targ_img, patch_size = 25, max_deficit = .3, min_match_distance = 10, max_num_matches = 20): assert patch_size % 2 == 1 patch_radius = patch_size // 2 assert src_img.ndim == 3 diff --git a/iros/iros_registration.py b/iros/iros_registration.py new file mode 100644 index 0000000..e69de29 diff --git a/iros/iros_tps.py b/iros/iros_tps.py new file mode 100644 index 0000000..b07d08d --- /dev/null +++ b/iros/iros_tps.py @@ -0,0 +1,118 @@ +import numpy as np +import os.path as osp +import os +from glob import glob +import lfd.tps as tps +from jds_utils.colorize import colorize +from lfd import fastmath, registration +import iros.image_registration as ir + + +PLOT = False + +def axisanglepart(m): + if np.linalg.det(m) < 0 or np.isnan(m).any(): raise Exception + u,s,vh = np.linalg.svd(m) + rotpart = u.dot(vh) + theta = np.arccos((np.trace(rotpart) - 1)/2) + axis = (1/(2*np.sin(theta))) * np.array([[rotpart[2,1] - rotpart[1,2], rotpart[0,2]-rotpart[2,0], rotpart[1,0]-rotpart[0,1]]]) + return theta, axis + + + +def fit(demo_keypts, current_keypts): + rot_coefs = .01*np.array((0.01,0.01,0.0025)) + scale_coef= .01*.01 + fastmath.set_coeffs(rot_coefs, scale_coef) + rfunc = fastmath.rot_reg + lin_ag, trans_g, w_ng = tps.tps_fit_regrot(demo_keypts, current_keypts, bend_coef = 1, rfunc=rfunc) + #spline.fit(demo_keypts, current_keypts,bend_coef=10,rot_coef=.1) + print "-----------------------------" + print "dataset %i"%i + centertrans_g = tps.tps_eval([demo_keypts.mean(axis=0)], lin_ag, trans_g, w_ng, demo_keypts)[0]-demo_keypts.mean(axis=0) + print "translation of center:\n", centertrans_g + print "linear:\n",lin_ag + print "axis-angle", axisanglepart(lin_ag.T) + print "singular vals", np.linalg.svd(lin_ag.T)[1] + print "nonlinear:\n",w_ng + print "residuals:\n",tps.tps_eval(demo_keypts, lin_ag, trans_g, w_ng, demo_keypts)-current_keypts + max_residual = (tps.tps_eval(demo_keypts, lin_ag, trans_g, w_ng, demo_keypts)-current_keypts).max() + print "max residual:%.3f"%max_residual + if max_residual > .015: + print colorize("warning: large residual (%.3f)"%max_residual,'red',highlight=True) + if np.linalg.norm(centertrans_g) > .4: + print colorize("warning: large translation (%.3f)"%np.linalg.norm(centertrans_g),'red',highlight=True) + + if PLOT: + import mayavi.mlab as mlab + mlab.clf() + x,y,z = demo_keypts.T + mlab.points3d(x,y,z,color=(0,1,0)) + x,y,z = current_keypts.T + mlab.points3d(x,y,z,color=(1,0,0)) + for (demopt, curpt) in zip(demo_keypts, current_keypts): + mlab.plot3d([demopt[0],curpt[0]], [demopt[1],curpt[1]], [demopt[2], curpt[2]],color=(1,1,0),tube_radius=.001) + mlab.show() + f = registration.ThinPlateSpline() + f.lin_ag = lin_ag + f.trans_g = trans_g + f.w_ng = w_ng + f.x_na = demo_keypts + + return f + +def xyz2rc(xyz, xyz_img): + diffs_rc = ((xyz_img - xyz)**2).sum(axis=2) + diffs_rc[np.isnan(diffs_rc)] = 1e100 + mindist = diffs_rc.min() + if mindist > 1e-4: + print "warning: nonzero minimum distance:",mindist + return np.unravel_index(diffs_rc.argmin(), diffs_rc.shape) + +def test_fitting(): + testdata_dir = osp.join(os.getenv("IROS_DATA_DIR"), "testdata") + fnames = glob(osp.join(testdata_dir,"segment*.npz")) + np.set_printoptions(precision=3) + + for (i,fname) in enumerate(fnames): + f = np.load(fname) + (current_xyz, current_rgb, current_keypts,demo_xyz, demo_rgb, demo_keypts) = \ + [f[key] for key in ["current_xyz", "current_rgb", "exec_keypts", "demo_xyz", "demo_rgb", "demo_keypts"]] + f = fit(demo_keypts, current_keypts) + +def test_keypoint_matching(): + iros_data_dir = osp.join(os.getenv("IROS_DATA_DIR")) + testdata_dir = osp.join(os.getenv("IROS_DATA_DIR"), "testdata") + fnames = glob(osp.join(testdata_dir,"segment*.npz")) + np.set_printoptions(precision=3) + for (i,fname) in enumerate(fnames): + + print "**** dataset %i ****"%i + f = np.load(fname) + (current_xyz, current_rgb, current_keypts,demo_xyz, demo_rgb, demo_keypts) = \ + [f[key] for key in ["current_xyz", "current_rgb", "exec_keypts", "demo_xyz", "demo_rgb", "demo_keypts"]] + + seg_num = int(osp.basename(fname)[7:9]) + demo_rgb = np.load(glob(osp.join(iros_data_dir, "InterruptedSuture0", 'point_clouds', 'pt%i/seg%i_*_rgb_*.npy'%(0, seg_num)))[0]) + current_xy = np.array([xyz2rc(xyz, current_xyz) for xyz in current_keypts])[:,::-1] + demo_xy = np.array([xyz2rc(xyz, demo_xyz) for xyz in demo_keypts])[:,::-1] + pred_current_xy = ir.register_images(demo_rgb, current_rgb, demo_xy) + for i in xrange(len(demo_xy)): + print "(%i, %i), (%i, %i), (%i, %i)"%tuple(current_xy[i].tolist() + pred_current_xy[i].tolist() + (current_xy[i] - pred_current_xy[i]).tolist()) + cur_plot_img = current_rgb.copy() + demo_plot_img = demo_rgb.copy() + plot_points_numbered(cur_plot_img, pred_current_xy, ir.Colors.GREEN) + plot_points_numbered(cur_plot_img, current_xy, ir.Colors.BLUE) + plot_points_numbered(demo_plot_img, demo_xy, ir.Colors.RED) + while cv2.waitKey(10)==-1: + cv2.imshow("current_rgb", cur_plot_img) + cv2.imshow("demo_rgb", demo_plot_img) + + +def plot_points_numbered(plot_img, xys, color=(255,255,255)): + for (i, (col, row)) in enumerate(xys): + cv2.putText(plot_img, str(i), (col, row), cv2.FONT_HERSHEY_PLAIN, 1.0, color, thickness = 1) + +if __name__ == "__main__": + import cv2 + test_keypoint_matching() \ No newline at end of file diff --git a/iros/test_tps_fitting.py b/iros/test_tps_fitting.py new file mode 100644 index 0000000..f939d67 --- /dev/null +++ b/iros/test_tps_fitting.py @@ -0,0 +1,61 @@ +import numpy as np +import os.path as osp +import os +from glob import glob +import lfd.tps as tps +from jds_utils.colorize import colorize +from lfd import fastmath +testdata_dir = osp.join(os.getenv("IROS_DATA_DIR"), "testdata") +fnames = glob(osp.join(testdata_dir,"segment*.npz")) +np.set_printoptions(precision=3) + +PLOT = False + +def axisanglepart(m): + if np.linalg.det(m) < 0 or np.isnan(m).any(): raise Exception + u,s,vh = np.linalg.svd(m) + rotpart = u.dot(vh) + theta = np.arccos((np.trace(rotpart) - 1)/2) + axis = (1/(2*np.sin(theta))) * np.array([[rotpart[2,1] - rotpart[1,2], rotpart[0,2]-rotpart[2,0], rotpart[1,0]-rotpart[0,1]]]) + return theta, axis + + +for (i,fname) in enumerate(fnames): + f = np.load(fname) + (current_xyz, current_rgb, current_keypts,demo_xyz, demo_rgb, demo_keypts) = \ + [f[key] for key in ["current_xyz", "current_rgb", "exec_keypts", "demo_xyz", "demo_rgb", "demo_keypts"]] + + + + rot_coefs = .01*np.array((0.01,0.01,0.0025)) + scale_coef= .01*.01 + fastmath.set_coeffs(rot_coefs, scale_coef) + rfunc = fastmath.rot_reg + lin_ag, trans_g, w_ng = tps.tps_fit_regrot(demo_keypts, current_keypts, bend_coef = 1, rfunc=rfunc) + #spline.fit(demo_keypts, current_keypts,bend_coef=10,rot_coef=.1) + print "-----------------------------" + print "dataset %i"%i + centertrans_g = tps.tps_eval([demo_keypts.mean(axis=0)], lin_ag, trans_g, w_ng, demo_keypts)[0]-demo_keypts.mean(axis=0) + print "translation of center:\n", centertrans_g + print "linear:\n",lin_ag + print "axis-angle", axisanglepart(lin_ag.T) + print "singular vals", np.linalg.svd(lin_ag.T)[1] + print "nonlinear:\n",w_ng + print "residuals:\n",tps.tps_eval(demo_keypts, lin_ag, trans_g, w_ng, demo_keypts)-current_keypts + max_residual = (tps.tps_eval(demo_keypts, lin_ag, trans_g, w_ng, demo_keypts)-current_keypts).max() + print "max residual:%.3f"%max_residual + if max_residual > .015: + print colorize("warning: large residual (%.3f)"%max_residual,'red',highlight=True) + if np.linalg.norm(centertrans_g) > .4: + print colorize("warning: large translation (%.3f)"%np.linalg.norm(centertrans_g),'red',highlight=True) + + if PLOT: + import mayavi.mlab as mlab + mlab.clf() + x,y,z = demo_keypts.T + mlab.points3d(x,y,z,color=(0,1,0)) + x,y,z = current_keypts.T + mlab.points3d(x,y,z,color=(1,0,0)) + for (demopt, curpt) in zip(demo_keypts, current_keypts): + mlab.plot3d([demopt[0],curpt[0]], [demopt[1],curpt[1]], [demopt[2], curpt[2]],color=(1,1,0),tube_radius=.001) + mlab.show()