From 52c49bf32b209bb1d8879c7256d20f2ef1614b32 Mon Sep 17 00:00:00 2001 From: Wenshan Date: Tue, 20 Oct 2020 03:20:22 -0400 Subject: [PATCH] tartanvo --- .gitignore | 3 + CMakeLists.txt | 209 ++++ Datasets/__init__.py | 0 Datasets/tartanTrajFlowDataset.py | 65 + Datasets/transformation.py | 218 ++++ Datasets/utils.py | 259 ++++ Network/PWC/PWCNet.py | 278 +++++ Network/PWC/__init__.py | 1 + Network/PWC/correlation.py | 397 ++++++ Network/VOFlowNet.py | 136 +++ Network/VONet.py | 53 + Network/__init__.py | 0 README.md | 172 ++- TartanVO.py | 110 ++ evaluator/__init__.py | 0 evaluator/evaluate_ate_scale.py | 133 ++ evaluator/evaluate_kitti.py | 129 ++ evaluator/evaluate_rpe.py | 219 ++++ evaluator/evaluator_base.py | 89 ++ evaluator/pose_est.txt | 734 +++++++++++ evaluator/pose_gt.txt | 734 +++++++++++ evaluator/tartanair_evaluator.py | 51 + evaluator/trajectory_transform.py | 162 +++ evaluator/transformation.py | 164 +++ package.xml | 77 ++ publish_image_from_folder.py | 123 ++ results/euroc_v102_tartanvo_1914.png | Bin 0 -> 74330 bytes results/euroc_v102_tartanvo_1914.txt | 1677 ++++++++++++++++++++++++++ results/kitti_10_tartanvo_1914.png | Bin 0 -> 28927 bytes results/kitti_10_tartanvo_1914.txt | 1201 ++++++++++++++++++ results/rviz.png | Bin 0 -> 263062 bytes tartanvo_node.py | 149 +++ vo_trajectory_from_folder.py | 105 ++ 33 files changed, 7646 insertions(+), 2 deletions(-) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 Datasets/__init__.py create mode 100644 Datasets/tartanTrajFlowDataset.py create mode 100644 Datasets/transformation.py create mode 100755 Datasets/utils.py create mode 100755 Network/PWC/PWCNet.py create mode 100755 Network/PWC/__init__.py create mode 100644 Network/PWC/correlation.py create mode 100644 Network/VOFlowNet.py create mode 100644 Network/VONet.py create mode 100644 Network/__init__.py create mode 100644 TartanVO.py create mode 100644 evaluator/__init__.py create mode 100644 evaluator/evaluate_ate_scale.py create mode 100644 evaluator/evaluate_kitti.py create mode 100644 evaluator/evaluate_rpe.py create mode 100644 evaluator/evaluator_base.py create mode 100644 evaluator/pose_est.txt create mode 100644 evaluator/pose_gt.txt create mode 100644 evaluator/tartanair_evaluator.py create mode 100644 evaluator/trajectory_transform.py create mode 100755 evaluator/transformation.py create mode 100644 package.xml create mode 100644 publish_image_from_folder.py create mode 100644 results/euroc_v102_tartanvo_1914.png create mode 100644 results/euroc_v102_tartanvo_1914.txt create mode 100644 results/kitti_10_tartanvo_1914.png create mode 100644 results/kitti_10_tartanvo_1914.txt create mode 100644 results/rviz.png create mode 100644 tartanvo_node.py create mode 100644 vo_trajectory_from_folder.py diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..59583923 --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +*.pyc +models/ +data/ \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 00000000..5b22373b --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,209 @@ +cmake_minimum_required(VERSION 2.8.3) +project(tartanvo) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + cv_bridge + geometry_msgs + nav_msgs + rospy + sensor_msgs + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# geometry_msgs# nav_msgs# sensor_msgs# std_msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES tartanvo +# CATKIN_DEPENDS cv_bridge geometry_msgs nav_msgs rospy sensor_msgs std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/tartanvo.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/tartanvo_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_tartanvo.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/Datasets/__init__.py b/Datasets/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/Datasets/tartanTrajFlowDataset.py b/Datasets/tartanTrajFlowDataset.py new file mode 100644 index 00000000..1373e580 --- /dev/null +++ b/Datasets/tartanTrajFlowDataset.py @@ -0,0 +1,65 @@ +import numpy as np +import cv2 +from torch.utils.data import Dataset, DataLoader +from os import listdir +from .transformation import pos_quats2SEs, pose2motion, SEs2ses +from .utils import make_intrinsics_layer + +class TrajFolderDataset(Dataset): + """scene flow synthetic dataset. """ + + def __init__(self, imgfolder , posefile = None, transform = None, + focalx = 320.0, focaly = 320.0, centerx = 320.0, centery = 240.0): + + files = listdir(imgfolder) + self.rgbfiles = [(imgfolder +'/'+ ff) for ff in files if (ff.endswith('.png') or ff.endswith('.jpg'))] + self.rgbfiles.sort() + self.imgfolder = imgfolder + + print('Find {} image files in {}'.format(len(self.rgbfiles), imgfolder)) + + if posefile is not None and posefile!="": + poselist = np.loadtxt(posefile).astype(np.float32) + assert(poselist.shape[1]==7) # position + quaternion + poses = pos_quats2SEs(poselist) + self.matrix = pose2motion(poses) + self.motions = SEs2ses(self.matrix).astype(np.float32) + # self.motions = self.motions / self.pose_std + assert(len(self.motions) == len(self.rgbfiles)) - 1 + else: + self.motions = None + + self.N = len(self.rgbfiles) - 1 + + # self.N = len(self.lines) + self.transform = transform + self.focalx = focalx + self.focaly = focaly + self.centerx = centerx + self.centery = centery + + def __len__(self): + return self.N + + def __getitem__(self, idx): + imgfile1 = self.rgbfiles[idx].strip() + imgfile2 = self.rgbfiles[idx+1].strip() + img1 = cv2.imread(imgfile1) + img2 = cv2.imread(imgfile2) + + res = {'img1': img1, 'img2': img2 } + + h, w, _ = img1.shape + intrinsicLayer = make_intrinsics_layer(w, h, self.focalx, self.focaly, self.centerx, self.centery) + res['intrinsic'] = intrinsicLayer + + if self.transform: + res = self.transform(res) + + if self.motions is None: + return res + else: + res['motion'] = self.motions[idx] + return res + + diff --git a/Datasets/transformation.py b/Datasets/transformation.py new file mode 100644 index 00000000..6f2ec156 --- /dev/null +++ b/Datasets/transformation.py @@ -0,0 +1,218 @@ +import numpy as np +#import cv2 +#import pyrr +from scipy.spatial.transform import Rotation as R + +def line2mat(line_data): + mat = np.eye(4) + mat[0:3,:] = line_data.reshape(3,4) + return np.matrix(mat) + +def motion2pose(data): + data_size = data.shape[0] + all_pose = np.zeros((data_size+1,12)) + temp = np.eye(4,4).reshape(1,16) + all_pose[0,:] = temp[0,0:12] + pose = np.matrix(np.eye(4,4)) + for i in range(0,data_size): + data_mat = line2mat(data[i,:]) + pose = pose*data_mat + pose_line = np.array(pose[0:3,:]).reshape(1,12) + all_pose[i+1,:] = pose_line + return all_pose + +def pose2motion(data, skip=0): + data_size = data.shape[0] + all_motion = np.zeros((data_size-1,12)) + for i in range(0,data_size-1-skip): + pose_curr = line2mat(data[i,:]) + pose_next = line2mat(data[i+1+skip,:]) + motion = pose_curr.I*pose_next + motion_line = np.array(motion[0:3,:]).reshape(1,12) + all_motion[i,:] = motion_line + return all_motion + +def SE2se(SE_data): + result = np.zeros((6)) + result[0:3] = np.array(SE_data[0:3,3].T) + result[3:6] = SO2so(SE_data[0:3,0:3]).T + return result +def SO2so(SO_data): + return R.from_dcm(SO_data).as_rotvec() + +def so2SO(so_data): + return R.from_rotvec(so_data).as_dcm() + +def se2SE(se_data): + result_mat = np.matrix(np.eye(4)) + result_mat[0:3,0:3] = so2SO(se_data[3:6]) + result_mat[0:3,3] = np.matrix(se_data[0:3]).T + return result_mat +### can get wrong result +def se_mean(se_datas): + all_SE = np.matrix(np.eye(4)) + for i in range(se_datas.shape[0]): + se = se_datas[i,:] + SE = se2SE(se) + all_SE = all_SE*SE + all_se = SE2se(all_SE) + mean_se = all_se/se_datas.shape[0] + return mean_se + +def ses_mean(se_datas): + se_datas = np.array(se_datas) + se_datas = np.transpose(se_datas.reshape(se_datas.shape[0],se_datas.shape[1],se_datas.shape[2]*se_datas.shape[3]),(0,2,1)) + se_result = np.zeros((se_datas.shape[0],se_datas.shape[2])) + for i in range(0,se_datas.shape[0]): + mean_se = se_mean(se_datas[i,:,:]) + se_result[i,:] = mean_se + return se_result + +def ses2poses(data): + data_size = data.shape[0] + all_pose = np.zeros((data_size+1,12)) + temp = np.eye(4,4).reshape(1,16) + all_pose[0,:] = temp[0,0:12] + pose = np.matrix(np.eye(4,4)) + for i in range(0,data_size): + data_mat = se2SE(data[i,:]) + pose = pose*data_mat + pose_line = np.array(pose[0:3,:]).reshape(1,12) + all_pose[i+1,:] = pose_line + return all_pose + +def ses2poses_quat(data): + ''' + ses: N x 6 + ''' + data_size = data.shape[0] + all_pose_quat = np.zeros((data_size+1,7)) + all_pose_quat[0,:] = np.array([0., 0., 0., 0., 0., 0., 1.]) + pose = np.matrix(np.eye(4,4)) + for i in range(0,data_size): + data_mat = se2SE(data[i,:]) + pose = pose*data_mat + quat = SO2quat(pose[0:3,0:3]) + all_pose_quat[i+1,:3] = np.array([pose[0,3], pose[1,3], pose[2,3]]) + all_pose_quat[i+1,3:] = quat + return all_pose_quat + +def SEs2ses(motion_data): + data_size = motion_data.shape[0] + ses = np.zeros((data_size,6)) + for i in range(0,data_size): + SE = np.matrix(np.eye(4)) + SE[0:3,:] = motion_data[i,:].reshape(3,4) + ses[i,:] = SE2se(SE) + return ses + +def so2quat(so_data): + so_data = np.array(so_data) + theta = np.sqrt(np.sum(so_data*so_data)) + axis = so_data/theta + quat=np.zeros(4) + quat[0:3] = np.sin(theta/2)*axis + quat[3] = np.cos(theta/2) + return quat + +def quat2so(quat_data): + quat_data = np.array(quat_data) + sin_half_theta = np.sqrt(np.sum(quat_data[0:3]*quat_data[0:3])) + axis = quat_data[0:3]/sin_half_theta + cos_half_theta = quat_data[3] + theta = 2*np.arctan2(sin_half_theta,cos_half_theta) + so = theta*axis + return so + +# input so_datas batch*channel*height*width +# return quat_datas batch*numner*channel +def sos2quats(so_datas,mean_std=[[1],[1]]): + so_datas = np.array(so_datas) + so_datas = so_datas.reshape(so_datas.shape[0],so_datas.shape[1],so_datas.shape[2]*so_datas.shape[3]) + so_datas = np.transpose(so_datas,(0,2,1)) + quat_datas = np.zeros((so_datas.shape[0],so_datas.shape[1],4)) + for i_b in range(0,so_datas.shape[0]): + for i_p in range(0,so_datas.shape[1]): + so_data = so_datas[i_b,i_p,:] + quat_data = so2quat(so_data) + quat_datas[i_b,i_p,:] = quat_data + return quat_datas + +def SO2quat(SO_data): + rr = R.from_dcm(SO_data) + return rr.as_quat() + +def quat2SO(quat_data): + return R.from_quat(quat_data).as_dcm() + + +def pos_quat2SE(quat_data): + SO = R.from_quat(quat_data[3:7]).as_dcm() + SE = np.matrix(np.eye(4)) + SE[0:3,0:3] = np.matrix(SO) + SE[0:3,3] = np.matrix(quat_data[0:3]).T + SE = np.array(SE[0:3,:]).reshape(1,12) + return SE + + +def pos_quats2SEs(quat_datas): + data_len = quat_datas.shape[0] + SEs = np.zeros((data_len,12)) + for i_data in range(0,data_len): + SE = pos_quat2SE(quat_datas[i_data,:]) + SEs[i_data,:] = SE + return SEs + + +def pos_quats2SE_matrices(quat_datas): + data_len = quat_datas.shape[0] + SEs = [] + for quat in quat_datas: + SO = R.from_quat(quat[3:7]).as_dcm() + SE = np.eye(4) + SE[0:3,0:3] = SO + SE[0:3,3] = quat[0:3] + SEs.append(SE) + return SEs + +def SE2pos_quat(SE_data): + pos_quat = np.zeros(7) + pos_quat[3:] = SO2quat(SE_data[0:3,0:3]) + pos_quat[:3] = SE_data[0:3,3].T + return pos_quat + +def kitti2tartan(traj): + ''' + traj: in kitti style, N x 12 numpy array, in camera frame + output: in TartanAir style, N x 7 numpy array, in NED frame + ''' + T = np.array([[0,0,1,0], + [1,0,0,0], + [0,1,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + + for pose in traj: + tt = np.eye(4) + tt[:3,:] = pose.reshape(3,4) + ttt=T.dot(tt).dot(T_inv) + new_traj.append(SE2pos_quat(ttt)) + + return np.array(new_traj) + +def tartan2kitti(traj): + T = np.array([[0,1,0,0], + [0,0,1,0], + [1,0,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + + for pose in traj: + tt = np.eye(4) + tt[:3,:] = pos_quat2SE(pose).reshape(3,4) + ttt=T.dot(tt).dot(T_inv) + new_traj.append(ttt[:3,:].reshape(12)) + + return np.array(new_traj) diff --git a/Datasets/utils.py b/Datasets/utils.py new file mode 100755 index 00000000..c064a26d --- /dev/null +++ b/Datasets/utils.py @@ -0,0 +1,259 @@ +from __future__ import division +import torch +import math +import random +import numpy as np +import numbers +import cv2 +import matplotlib.pyplot as plt + +import time +# ===== general functions ===== + +class Compose(object): + """Composes several transforms together. + + Args: + transforms (List[Transform]): list of transforms to compose. + + Example: + >>> transforms.Compose([ + >>> transforms.CenterCrop(10), + >>> transforms.ToTensor(), + >>> ]) + """ + + def __init__(self, transforms): + self.transforms = transforms + + def __call__(self, img): + for t in self.transforms: + img = t(img) + return img + + +class DownscaleFlow(object): + """ + Scale the flow and mask to a fixed size + + """ + def __init__(self, scale=4): + ''' + size: output frame size, this should be NO LARGER than the input frame size! + ''' + self.downscale = 1.0/scale + + def __call__(self, sample): + if self.downscale!=1 and sample.has_key('flow'): + sample['flow'] = cv2.resize(sample['flow'], + (0, 0), fx=self.downscale, fy=self.downscale, interpolation=cv2.INTER_LINEAR) + + if self.downscale!=1 and sample.has_key('intrinsic'): + sample['intrinsic'] = cv2.resize(sample['intrinsic'], + (0, 0), fx=self.downscale, fy=self.downscale, interpolation=cv2.INTER_LINEAR) + + if self.downscale!=1 and sample.has_key('fmask'): + sample['fmask'] = cv2.resize(sample['fmask'], + (0, 0), fx=self.downscale, fy=self.downscale, interpolation=cv2.INTER_LINEAR) + return sample + +class CropCenter(object): + """Crops the a sample of data (tuple) at center + if the image size is not large enough, it will be first resized with fixed ratio + """ + + def __init__(self, size): + if isinstance(size, numbers.Number): + self.size = (int(size), int(size)) + else: + self.size = size + + def __call__(self, sample): + kks = sample.keys() + th, tw = self.size + h, w = sample[kks[0]].shape[0], sample[kks[0]].shape[1] + if w == tw and h == th: + return sample + + # resize the image if the image size is smaller than the target size + scale_h, scale_w, scale = 1., 1., 1. + if th > h: + scale_h = float(th)/h + if tw > w: + scale_w = float(tw)/w + if scale_h>1 or scale_w>1: + scale = max(scale_h, scale_w) + w = int(round(w * scale)) # w after resize + h = int(round(h * scale)) # h after resize + + x1 = int((w-tw)/2) + y1 = int((h-th)/2) + + for kk in kks: + if sample[kk] is None: + continue + img = sample[kk] + if len(img.shape)==3: + if scale>1: + img = cv2.resize(img, (w,h), interpolation=cv2.INTER_LINEAR) + sample[kk] = img[y1:y1+th,x1:x1+tw,:] + elif len(img.shape)==2: + if scale>1: + img = cv2.resize(img, (w,h), interpolation=cv2.INTER_LINEAR) + sample[kk] = img[y1:y1+th,x1:x1+tw] + + return sample + +class ToTensor(object): + def __call__(self, sample): + sss = time.time() + + kks = list(sample) + + for kk in kks: + data = sample[kk] + data = data.astype(np.float32) + if len(data.shape) == 3: # transpose image-like data + data = data.transpose(2,0,1) + elif len(data.shape) == 2: + data = data.reshape((1,)+data.shape) + + if len(data.shape) == 3 and data.shape[0]==3: # normalization of rgb images + data = data/255.0 + + sample[kk] = torch.from_numpy(data.copy()) # copy to make memory continuous + + return sample + + +def tensor2img(tensImg,mean,std): + """ + convert a tensor a numpy array, for visualization + """ + # undo normalize + for t, m, s in zip(tensImg, mean, std): + t.mul_(s).add_(m) + tensImg = tensImg * float(255) + # undo transpose + tensImg = (tensImg.numpy().transpose(1,2,0)).astype(np.uint8) + return tensImg + +def bilinear_interpolate(img, h, w): + # assert round(h)>=0 and round(h)=0 and round(w)0] = 1 + + return output*mask + + + def forward(self,x): + im1 = x[0] + im2 = x[1] + + c11 = self.conv1b(self.conv1aa(self.conv1a(im1))) + c21 = self.conv1b(self.conv1aa(self.conv1a(im2))) + c12 = self.conv2b(self.conv2aa(self.conv2a(c11))) + c22 = self.conv2b(self.conv2aa(self.conv2a(c21))) + c13 = self.conv3b(self.conv3aa(self.conv3a(c12))) + c23 = self.conv3b(self.conv3aa(self.conv3a(c22))) + c14 = self.conv4b(self.conv4aa(self.conv4a(c13))) + c24 = self.conv4b(self.conv4aa(self.conv4a(c23))) + c15 = self.conv5b(self.conv5aa(self.conv5a(c14))) + c25 = self.conv5b(self.conv5aa(self.conv5a(c24))) + c16 = self.conv6b(self.conv6a(self.conv6aa(c15))) + c26 = self.conv6b(self.conv6a(self.conv6aa(c25))) + + + # corr6 = self.corr(c16, c26) + corr6 = FunctionCorrelation(tenFirst=c16, tenSecond=c26) + + corr6 = self.leakyRELU(corr6) + + + x = torch.cat((self.conv6_0(corr6), corr6),1) + x = torch.cat((self.conv6_1(x), x),1) + x = torch.cat((self.conv6_2(x), x),1) + x = torch.cat((self.conv6_3(x), x),1) + x = torch.cat((self.conv6_4(x), x),1) + flow6 = self.predict_flow6(x) + up_flow6 = self.deconv6(flow6) + up_feat6 = self.upfeat6(x) + + + warp5 = self.warp(c25, up_flow6*0.625) + # corr5 = self.corr(c15, warp5) + corr5 = FunctionCorrelation(tenFirst=c15, tenSecond=warp5) + corr5 = self.leakyRELU(corr5) + x = torch.cat((corr5, c15, up_flow6, up_feat6), 1) + x = torch.cat((self.conv5_0(x), x),1) + x = torch.cat((self.conv5_1(x), x),1) + x = torch.cat((self.conv5_2(x), x),1) + x = torch.cat((self.conv5_3(x), x),1) + x = torch.cat((self.conv5_4(x), x),1) + flow5 = self.predict_flow5(x) + up_flow5 = self.deconv5(flow5) + up_feat5 = self.upfeat5(x) + + + warp4 = self.warp(c24, up_flow5*1.25) #1.25 + # corr4 = self.corr(c14, warp4) + corr4 = FunctionCorrelation(tenFirst=c14, tenSecond=warp4) + corr4 = self.leakyRELU(corr4) + x = torch.cat((corr4, c14, up_flow5, up_feat5), 1) + x = torch.cat((self.conv4_0(x), x),1) + x = torch.cat((self.conv4_1(x), x),1) + x = torch.cat((self.conv4_2(x), x),1) + x = torch.cat((self.conv4_3(x), x),1) + x = torch.cat((self.conv4_4(x), x),1) + flow4 = self.predict_flow4(x) + up_flow4 = self.deconv4(flow4) + up_feat4 = self.upfeat4(x) + + + warp3 = self.warp(c23, up_flow4*2.5)#2.5 + # corr3 = self.corr(c13, warp3) + corr3 = FunctionCorrelation(tenFirst=c13, tenSecond=warp3) + corr3 = self.leakyRELU(corr3) + + + x = torch.cat((corr3, c13, up_flow4, up_feat4), 1) + x = torch.cat((self.conv3_0(x), x),1) + x = torch.cat((self.conv3_1(x), x),1) + x = torch.cat((self.conv3_2(x), x),1) + x = torch.cat((self.conv3_3(x), x),1) + x = torch.cat((self.conv3_4(x), x),1) + flow3 = self.predict_flow3(x) + up_flow3 = self.deconv3(flow3) + up_feat3 = self.upfeat3(x) + + + warp2 = self.warp(c22, up_flow3*5.0) + # corr2 = self.corr(c12, warp2) + corr2 = FunctionCorrelation(tenFirst=c12, tenSecond=warp2) + corr2 = self.leakyRELU(corr2) + x = torch.cat((corr2, c12, up_flow3, up_feat3), 1) + x = torch.cat((self.conv2_0(x), x),1) + x = torch.cat((self.conv2_1(x), x),1) + x = torch.cat((self.conv2_2(x), x),1) + x = torch.cat((self.conv2_3(x), x),1) + x = torch.cat((self.conv2_4(x), x),1) + flow2 = self.predict_flow2(x) + + x = self.dc_conv4(self.dc_conv3(self.dc_conv2(self.dc_conv1(x)))) + flow2 = flow2 + self.dc_conv7(self.dc_conv6(self.dc_conv5(x))) + + return flow2 + + +def pwc_dc_net(path=None): + + model = PWCDCNet() + if path is not None: + data = torch.load(path) + if 'state_dict' in data.keys(): + model.load_state_dict(data['state_dict']) + else: + model.load_state_dict(data) + return model + + + + diff --git a/Network/PWC/__init__.py b/Network/PWC/__init__.py new file mode 100755 index 00000000..cb471327 --- /dev/null +++ b/Network/PWC/__init__.py @@ -0,0 +1 @@ +from .PWCNet import * diff --git a/Network/PWC/correlation.py b/Network/PWC/correlation.py new file mode 100644 index 00000000..4039eb49 --- /dev/null +++ b/Network/PWC/correlation.py @@ -0,0 +1,397 @@ +#!/usr/bin/env python + +import torch + +import cupy +import re + +kernel_Correlation_rearrange = ''' + extern "C" __global__ void kernel_Correlation_rearrange( + const int n, + const float* input, + float* output + ) { + int intIndex = (blockIdx.x * blockDim.x) + threadIdx.x; + + if (intIndex >= n) { + return; + } + + int intSample = blockIdx.z; + int intChannel = blockIdx.y; + + float fltValue = input[(((intSample * SIZE_1(input)) + intChannel) * SIZE_2(input) * SIZE_3(input)) + intIndex]; + + __syncthreads(); + + int intPaddedY = (intIndex / SIZE_3(input)) + 4; + int intPaddedX = (intIndex % SIZE_3(input)) + 4; + int intRearrange = ((SIZE_3(input) + 8) * intPaddedY) + intPaddedX; + + output[(((intSample * SIZE_1(output) * SIZE_2(output)) + intRearrange) * SIZE_1(input)) + intChannel] = fltValue; + } +''' + +kernel_Correlation_updateOutput = ''' + extern "C" __global__ void kernel_Correlation_updateOutput( + const int n, + const float* rbot0, + const float* rbot1, + float* top + ) { + extern __shared__ char patch_data_char[]; + + float *patch_data = (float *)patch_data_char; + + // First (upper left) position of kernel upper-left corner in current center position of neighborhood in image 1 + int x1 = blockIdx.x + 4; + int y1 = blockIdx.y + 4; + int item = blockIdx.z; + int ch_off = threadIdx.x; + + // Load 3D patch into shared shared memory + for (int j = 0; j < 1; j++) { // HEIGHT + for (int i = 0; i < 1; i++) { // WIDTH + int ji_off = (j + i) * SIZE_3(rbot0); + for (int ch = ch_off; ch < SIZE_3(rbot0); ch += 32) { // CHANNELS + int idx1 = ((item * SIZE_1(rbot0) + y1+j) * SIZE_2(rbot0) + x1+i) * SIZE_3(rbot0) + ch; + int idxPatchData = ji_off + ch; + patch_data[idxPatchData] = rbot0[idx1]; + } + } + } + + __syncthreads(); + + __shared__ float sum[32]; + + // Compute correlation + for (int top_channel = 0; top_channel < SIZE_1(top); top_channel++) { + sum[ch_off] = 0; + + int s2o = top_channel % 9 - 4; + int s2p = top_channel / 9 - 4; + + for (int j = 0; j < 1; j++) { // HEIGHT + for (int i = 0; i < 1; i++) { // WIDTH + int ji_off = (j + i) * SIZE_3(rbot0); + for (int ch = ch_off; ch < SIZE_3(rbot0); ch += 32) { // CHANNELS + int x2 = x1 + s2o; + int y2 = y1 + s2p; + + int idxPatchData = ji_off + ch; + int idx2 = ((item * SIZE_1(rbot0) + y2+j) * SIZE_2(rbot0) + x2+i) * SIZE_3(rbot0) + ch; + + sum[ch_off] += patch_data[idxPatchData] * rbot1[idx2]; + } + } + } + + __syncthreads(); + + if (ch_off == 0) { + float total_sum = 0; + for (int idx = 0; idx < 32; idx++) { + total_sum += sum[idx]; + } + const int sumelems = SIZE_3(rbot0); + const int index = ((top_channel*SIZE_2(top) + blockIdx.y)*SIZE_3(top))+blockIdx.x; + top[index + item*SIZE_1(top)*SIZE_2(top)*SIZE_3(top)] = total_sum / (float)sumelems; + } + } + } +''' + +kernel_Correlation_updateGradFirst = ''' + #define ROUND_OFF 50000 + + extern "C" __global__ void kernel_Correlation_updateGradFirst( + const int n, + const int intSample, + const float* rbot0, + const float* rbot1, + const float* gradOutput, + float* gradFirst, + float* gradSecond + ) { for (int intIndex = (blockIdx.x * blockDim.x) + threadIdx.x; intIndex < n; intIndex += blockDim.x * gridDim.x) { + int n = intIndex % SIZE_1(gradFirst); // channels + int l = (intIndex / SIZE_1(gradFirst)) % SIZE_3(gradFirst) + 4; // w-pos + int m = (intIndex / SIZE_1(gradFirst) / SIZE_3(gradFirst)) % SIZE_2(gradFirst) + 4; // h-pos + + // round_off is a trick to enable integer division with ceil, even for negative numbers + // We use a large offset, for the inner part not to become negative. + const int round_off = ROUND_OFF; + const int round_off_s1 = round_off; + + // We add round_off before_s1 the int division and subtract round_off after it, to ensure the formula matches ceil behavior: + int xmin = (l - 4 + round_off_s1 - 1) + 1 - round_off; // ceil (l - 4) + int ymin = (m - 4 + round_off_s1 - 1) + 1 - round_off; // ceil (l - 4) + + // Same here: + int xmax = (l - 4 + round_off_s1) - round_off; // floor (l - 4) + int ymax = (m - 4 + round_off_s1) - round_off; // floor (m - 4) + + float sum = 0; + if (xmax>=0 && ymax>=0 && (xmin<=SIZE_3(gradOutput)-1) && (ymin<=SIZE_2(gradOutput)-1)) { + xmin = max(0,xmin); + xmax = min(SIZE_3(gradOutput)-1,xmax); + + ymin = max(0,ymin); + ymax = min(SIZE_2(gradOutput)-1,ymax); + + for (int p = -4; p <= 4; p++) { + for (int o = -4; o <= 4; o++) { + // Get rbot1 data: + int s2o = o; + int s2p = p; + int idxbot1 = ((intSample * SIZE_1(rbot0) + (m+s2p)) * SIZE_2(rbot0) + (l+s2o)) * SIZE_3(rbot0) + n; + float bot1tmp = rbot1[idxbot1]; // rbot1[l+s2o,m+s2p,n] + + // Index offset for gradOutput in following loops: + int op = (p+4) * 9 + (o+4); // index[o,p] + int idxopoffset = (intSample * SIZE_1(gradOutput) + op); + + for (int y = ymin; y <= ymax; y++) { + for (int x = xmin; x <= xmax; x++) { + int idxgradOutput = (idxopoffset * SIZE_2(gradOutput) + y) * SIZE_3(gradOutput) + x; // gradOutput[x,y,o,p] + sum += gradOutput[idxgradOutput] * bot1tmp; + } + } + } + } + } + const int sumelems = SIZE_1(gradFirst); + const int bot0index = ((n * SIZE_2(gradFirst)) + (m-4)) * SIZE_3(gradFirst) + (l-4); + gradFirst[bot0index + intSample*SIZE_1(gradFirst)*SIZE_2(gradFirst)*SIZE_3(gradFirst)] = sum / (float)sumelems; + } } +''' + +kernel_Correlation_updateGradSecond = ''' + #define ROUND_OFF 50000 + + extern "C" __global__ void kernel_Correlation_updateGradSecond( + const int n, + const int intSample, + const float* rbot0, + const float* rbot1, + const float* gradOutput, + float* gradFirst, + float* gradSecond + ) { for (int intIndex = (blockIdx.x * blockDim.x) + threadIdx.x; intIndex < n; intIndex += blockDim.x * gridDim.x) { + int n = intIndex % SIZE_1(gradSecond); // channels + int l = (intIndex / SIZE_1(gradSecond)) % SIZE_3(gradSecond) + 4; // w-pos + int m = (intIndex / SIZE_1(gradSecond) / SIZE_3(gradSecond)) % SIZE_2(gradSecond) + 4; // h-pos + + // round_off is a trick to enable integer division with ceil, even for negative numbers + // We use a large offset, for the inner part not to become negative. + const int round_off = ROUND_OFF; + const int round_off_s1 = round_off; + + float sum = 0; + for (int p = -4; p <= 4; p++) { + for (int o = -4; o <= 4; o++) { + int s2o = o; + int s2p = p; + + //Get X,Y ranges and clamp + // We add round_off before_s1 the int division and subtract round_off after it, to ensure the formula matches ceil behavior: + int xmin = (l - 4 - s2o + round_off_s1 - 1) + 1 - round_off; // ceil (l - 4 - s2o) + int ymin = (m - 4 - s2p + round_off_s1 - 1) + 1 - round_off; // ceil (l - 4 - s2o) + + // Same here: + int xmax = (l - 4 - s2o + round_off_s1) - round_off; // floor (l - 4 - s2o) + int ymax = (m - 4 - s2p + round_off_s1) - round_off; // floor (m - 4 - s2p) + + if (xmax>=0 && ymax>=0 && (xmin<=SIZE_3(gradOutput)-1) && (ymin<=SIZE_2(gradOutput)-1)) { + xmin = max(0,xmin); + xmax = min(SIZE_3(gradOutput)-1,xmax); + + ymin = max(0,ymin); + ymax = min(SIZE_2(gradOutput)-1,ymax); + + // Get rbot0 data: + int idxbot0 = ((intSample * SIZE_1(rbot0) + (m-s2p)) * SIZE_2(rbot0) + (l-s2o)) * SIZE_3(rbot0) + n; + float bot0tmp = rbot0[idxbot0]; // rbot1[l+s2o,m+s2p,n] + + // Index offset for gradOutput in following loops: + int op = (p+4) * 9 + (o+4); // index[o,p] + int idxopoffset = (intSample * SIZE_1(gradOutput) + op); + + for (int y = ymin; y <= ymax; y++) { + for (int x = xmin; x <= xmax; x++) { + int idxgradOutput = (idxopoffset * SIZE_2(gradOutput) + y) * SIZE_3(gradOutput) + x; // gradOutput[x,y,o,p] + sum += gradOutput[idxgradOutput] * bot0tmp; + } + } + } + } + } + const int sumelems = SIZE_1(gradSecond); + const int bot1index = ((n * SIZE_2(gradSecond)) + (m-4)) * SIZE_3(gradSecond) + (l-4); + gradSecond[bot1index + intSample*SIZE_1(gradSecond)*SIZE_2(gradSecond)*SIZE_3(gradSecond)] = sum / (float)sumelems; + } } +''' + +def cupy_kernel(strFunction, objVariables): + strKernel = globals()[strFunction] + + while True: + objMatch = re.search('(SIZE_)([0-4])(\()([^\)]*)(\))', strKernel) + + if objMatch is None: + break + # end + + intArg = int(objMatch.group(2)) + + strTensor = objMatch.group(4) + intSizes = objVariables[strTensor].size() + + strKernel = strKernel.replace(objMatch.group(), str(intSizes[intArg])) + # end + + while True: + objMatch = re.search('(VALUE_)([0-4])(\()([^\)]+)(\))', strKernel) + + if objMatch is None: + break + # end + + intArgs = int(objMatch.group(2)) + strArgs = objMatch.group(4).split(',') + + strTensor = strArgs[0] + intStrides = objVariables[strTensor].stride() + strIndex = [ '((' + strArgs[intArg + 1].replace('{', '(').replace('}', ')').strip() + ')*' + str(intStrides[intArg]) + ')' for intArg in range(intArgs) ] + + strKernel = strKernel.replace(objMatch.group(0), strTensor + '[' + str.join('+', strIndex) + ']') + # end + + return strKernel +# end + +@cupy.util.memoize(for_each_device=True) +def cupy_launch(strFunction, strKernel): + return cupy.cuda.compile_with_cache(strKernel).get_function(strFunction) +# end + +class _FunctionCorrelation(torch.autograd.Function): + @staticmethod + def forward(self, first, second): + rbot0 = first.new_zeros([ first.shape[0], first.shape[2] + 8, first.shape[3] + 8, first.shape[1] ]) + rbot1 = first.new_zeros([ first.shape[0], first.shape[2] + 8, first.shape[3] + 8, first.shape[1] ]) + + self.save_for_backward(first, second, rbot0, rbot1) + + assert(first.is_contiguous() == True) + assert(second.is_contiguous() == True) + + output = first.new_zeros([ first.shape[0], 81, first.shape[2], first.shape[3] ]) + + if first.is_cuda == True: + n = first.shape[2] * first.shape[3] + cupy_launch('kernel_Correlation_rearrange', cupy_kernel('kernel_Correlation_rearrange', { + 'input': first, + 'output': rbot0 + }))( + grid=tuple([ int((n + 16 - 1) / 16), first.shape[1], first.shape[0] ]), + block=tuple([ 16, 1, 1 ]), + args=[ n, first.data_ptr(), rbot0.data_ptr() ] + ) + + n = second.shape[2] * second.shape[3] + cupy_launch('kernel_Correlation_rearrange', cupy_kernel('kernel_Correlation_rearrange', { + 'input': second, + 'output': rbot1 + }))( + grid=tuple([ int((n + 16 - 1) / 16), second.shape[1], second.shape[0] ]), + block=tuple([ 16, 1, 1 ]), + args=[ n, second.data_ptr(), rbot1.data_ptr() ] + ) + + n = output.shape[1] * output.shape[2] * output.shape[3] + cupy_launch('kernel_Correlation_updateOutput', cupy_kernel('kernel_Correlation_updateOutput', { + 'rbot0': rbot0, + 'rbot1': rbot1, + 'top': output + }))( + grid=tuple([ output.shape[3], output.shape[2], output.shape[0] ]), + block=tuple([ 32, 1, 1 ]), + shared_mem=first.shape[1] * 4, + args=[ n, rbot0.data_ptr(), rbot1.data_ptr(), output.data_ptr() ] + ) + + elif first.is_cuda == False: + raise NotImplementedError() + + # end + + return output + # end + + @staticmethod + def backward(self, gradOutput): + first, second, rbot0, rbot1 = self.saved_tensors + + assert(gradOutput.is_contiguous() == True) + + gradFirst = first.new_zeros([ first.shape[0], first.shape[1], first.shape[2], first.shape[3] ]) if self.needs_input_grad[0] == True else None + gradSecond = first.new_zeros([ first.shape[0], first.shape[1], first.shape[2], first.shape[3] ]) if self.needs_input_grad[1] == True else None + + if first.is_cuda == True: + if gradFirst is not None: + for intSample in range(first.shape[0]): + n = first.shape[1] * first.shape[2] * first.shape[3] + cupy_launch('kernel_Correlation_updateGradFirst', cupy_kernel('kernel_Correlation_updateGradFirst', { + 'rbot0': rbot0, + 'rbot1': rbot1, + 'gradOutput': gradOutput, + 'gradFirst': gradFirst, + 'gradSecond': None + }))( + grid=tuple([ int((n + 512 - 1) / 512), 1, 1 ]), + block=tuple([ 512, 1, 1 ]), + args=[ n, intSample, rbot0.data_ptr(), rbot1.data_ptr(), gradOutput.data_ptr(), gradFirst.data_ptr(), None ] + ) + # end + # end + + if gradSecond is not None: + for intSample in range(first.shape[0]): + n = first.shape[1] * first.shape[2] * first.shape[3] + cupy_launch('kernel_Correlation_updateGradSecond', cupy_kernel('kernel_Correlation_updateGradSecond', { + 'rbot0': rbot0, + 'rbot1': rbot1, + 'gradOutput': gradOutput, + 'gradFirst': None, + 'gradSecond': gradSecond + }))( + grid=tuple([ int((n + 512 - 1) / 512), 1, 1 ]), + block=tuple([ 512, 1, 1 ]), + args=[ n, intSample, rbot0.data_ptr(), rbot1.data_ptr(), gradOutput.data_ptr(), None, gradSecond.data_ptr() ] + ) + # end + # end + + elif first.is_cuda == False: + raise NotImplementedError() + + # end + + return gradFirst, gradSecond + # end +# end + +def FunctionCorrelation(tenFirst, tenSecond): + return _FunctionCorrelation.apply(tenFirst, tenSecond) +# end + +class ModuleCorrelation(torch.nn.Module): + def __init__(self): + super(ModuleCorrelation, self).__init__() + # end + + def forward(self, tenFirst, tenSecond): + return _FunctionCorrelation.apply(tenFirst, tenSecond) + # end +# end \ No newline at end of file diff --git a/Network/VOFlowNet.py b/Network/VOFlowNet.py new file mode 100644 index 00000000..ecf35a02 --- /dev/null +++ b/Network/VOFlowNet.py @@ -0,0 +1,136 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2020, Wenshan Wang, CMU +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of CMU nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import torch +import torch.nn as nn +import torch.nn.functional as F +import math + +def conv(in_planes, out_planes, kernel_size=3, stride=2, padding=1, dilation=1, bn_layer=False, bias=True): + if bn_layer: + return nn.Sequential( + nn.Conv2d(in_planes, out_planes, kernel_size=kernel_size, padding=padding, stride=stride, dilation=dilation, bias=bias), + nn.BatchNorm2d(out_planes), + nn.ReLU(inplace=True) + ) + else: + return nn.Sequential( + nn.Conv2d(in_planes, out_planes, kernel_size=kernel_size, padding=padding, stride=stride, dilation=dilation), + nn.ReLU(inplace=True) + ) + +def linear(in_planes, out_planes): + return nn.Sequential( + nn.Linear(in_planes, out_planes), + nn.ReLU(inplace=True) + ) + +class BasicBlock(nn.Module): + expansion = 1 + def __init__(self, inplanes, planes, stride, downsample, pad, dilation): + super(BasicBlock, self).__init__() + + self.conv1 = conv(inplanes, planes, 3, stride, pad, dilation) + self.conv2 = nn.Conv2d(planes, planes, 3, 1, pad, dilation) + + self.downsample = downsample + self.stride = stride + + def forward(self, x): + out = self.conv1(x) + out = self.conv2(out) + + if self.downsample is not None: + x = self.downsample(x) + out += x + + return F.relu(out, inplace=True) + +class VOFlowRes(nn.Module): + def __init__(self): + super(VOFlowRes, self).__init__() + inputnum = 4 + blocknums = [2,2,3,4,6,7,3] + outputnums = [32,64,64,128,128,256,256] + + self.firstconv = nn.Sequential(conv(inputnum, 32, 3, 2, 1, 1, False), + conv(32, 32, 3, 1, 1, 1), + conv(32, 32, 3, 1, 1, 1)) + + self.inplanes = 32 + + self.layer1 = self._make_layer(BasicBlock, outputnums[2], blocknums[2], 2, 1, 1) # 40 x 28 + self.layer2 = self._make_layer(BasicBlock, outputnums[3], blocknums[3], 2, 1, 1) # 20 x 14 + self.layer3 = self._make_layer(BasicBlock, outputnums[4], blocknums[4], 2, 1, 1) # 10 x 7 + self.layer4 = self._make_layer(BasicBlock, outputnums[5], blocknums[5], 2, 1, 1) # 5 x 4 + self.layer5 = self._make_layer(BasicBlock, outputnums[6], blocknums[6], 2, 1, 1) # 3 x 2 + fcnum = outputnums[6] * 6 + + fc1_trans = linear(fcnum, 128) + fc2_trans = linear(128,32) + fc3_trans = nn.Linear(32,3) + + fc1_rot = linear(fcnum, 128) + fc2_rot = linear(128,32) + fc3_rot = nn.Linear(32,3) + + + self.voflow_trans = nn.Sequential(fc1_trans, fc2_trans, fc3_trans) + self.voflow_rot = nn.Sequential(fc1_rot, fc2_rot, fc3_rot) + + + def _make_layer(self, block, planes, blocks, stride, pad, dilation): + downsample = None + if stride != 1 or self.inplanes != planes * block.expansion: + downsample = nn.Conv2d(self.inplanes, planes * block.expansion, + kernel_size=1, stride=stride) + + layers = [] + layers.append(block(self.inplanes, planes, stride, downsample, pad, dilation)) + self.inplanes = planes * block.expansion + for i in range(1, blocks): + layers.append(block(self.inplanes, planes,1,None,pad,dilation)) + + return nn.Sequential(*layers) + + def forward(self, x): + x = self.firstconv(x) + x = self.layer1(x) + x = self.layer2(x) + x = self.layer3(x) + x = self.layer4(x) + x = self.layer5(x) + + x = x.view(x.shape[0], -1) + x_trans = self.voflow_trans(x) + x_rot = self.voflow_rot(x) + return torch.cat((x_trans, x_rot), dim=1) \ No newline at end of file diff --git a/Network/VONet.py b/Network/VONet.py new file mode 100644 index 00000000..85fe4ab7 --- /dev/null +++ b/Network/VONet.py @@ -0,0 +1,53 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2020, Wenshan Wang, Yaoyu Hu, CMU +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of CMU nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import torch +import torch.nn as nn +import torch.nn.functional as F +from .PWC import PWCDCNet as FlowNet +from .VOFlowNet import VOFlowRes as FlowPoseNet + +class VONet(nn.Module): + def __init__(self): + super(VONet, self).__init__() + + self.flowNet = FlowNet() + self.flowPoseNet = FlowPoseNet() + + def forward(self, x): + # import ipdb;ipdb.set_trace() + flow = self.flowNet(x[0:2]) + flow_input = torch.cat( ( flow, x[2] ), dim=1 ) + pose = self.flowPoseNet( flow_input ) + + return flow, pose + diff --git a/Network/__init__.py b/Network/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/README.md b/README.md index 25dbe79a..97ed11d9 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,170 @@ -# tartanvo -TartanVO: A Generalizable Learning-based VO +# TartanVO: A Generalizable Learning-based VO + +TartanVO is a learning-based visual odometry trained on [TartanAir](https://theairlab.org/tartanair-dataset) dataset. It generalizes to multiple datasets and real-world scenarios, and outperforms geometry-based methods in challenging scenes. + +TODO: add a paper link and author info + +## Example +Introduction video: [Youtube](https://www.youtube.com/watch?v=NQ1UEh3thbU) + +TODO: Add another video source + +Our model is trained purely on simulation data, but it generalizes well to real-world data. For example, this is the testing result on [KITTI](http://www.cvlibs.net/datasets/kitti/eval_odometry.php) 10 trajectory: + +![KITTI10](results/kitti_10_tartanvo_1914.png) + +This is the testing result on [EuRoC V102](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets): + +![EUROC_V102](results/euroc_v102_tartanvo_1914.png) + +## Requirments +* Python 2 / 3 +* numpy +* matplotlib +* scipy +* pytorch >= 1.3 +* torchvision +* opencv-python +* cupy == 6.7.0 +* visdom +* [WorkFlow](https://github.com/huyaoyu/WorkFlow): branch amigo + +You can install the above dependencies manually, or follow the following steps: +``` +$ pip install numpy matplotlib scipy torch==1.4.0 torchvision opencv-python cupy==6.7.0 visdom + +``` + +## Test with pretrained model +### Download the pretrained model + +``` +$ mkdir models + +$ wget https://cmu.box.com/shared/static/t1a5u4x6dxohl89104dyrsiz42mvq2sz.pkl -O models/tartanvo_1914.pkl + +``` + +### Download the testing data + +* Download KITTI-10 testing trajectory +``` +$ mkdir data + +$ wget https://cmu.box.com/shared/static/nw3bi7x5vng2xy296ndxt19uozpk64jq.zip -O data/KITTI_10.zip + +$ unzip -q data/KITTI_10.zip -d data/KITTI_10/ +``` + +* Download EuRoC-V102 testing trajectory +``` +$ mkdir data + +$ wget https://cmu.box.com/shared/static/1ctocidptdv1xev6pjxdj0b782mrstps.zip -O data/EuRoC_V102.zip + +$ unzip -q data/EuRoC_V102.zip -d data/EuRoC_V102/ +``` + + + +### Run the testing script +The `vo_trajectory_from_folder.py` script shows an example of running TartanVO on a sequence of images reading out from a folder. Because TartanVO outputs up-to-scale translation, it also reads a pose-file for adjusting the translation scale. If the pose-file is not provided, the default scale of 1.0 will be used. The results will be stored in the `results` folder. + +- Testing on KITTI +``` +$ python vo_trajectory_from_folder.py --model-name tartanvo_1914.pkl --kitti --test-dir data/KITTI_10/image_left --pose-file data/KITTI_10/pose_left.txt +``` +- Testing on EuRoC +``` + +$ python vo_trajectory_from_folder.py --model-name tartanvo_1914.pkl --euroc --test-dir data/EuRoC_V102/image_left --pose-file data/EuRoC_V102/pose_left.txt +``` + + + +Running the above commands with `--save-flow` tag, allows you to save intermediate optical flow outputs into the `results` folder. + +## Run the ROS node + +We provide a python ROS node in `tartanvo_node.py` for easy integration of the TartanVO to robotic systems. + +### How does TartanVONode work? +1. Subscribed topics + - rgb_image (sensor_msgs/Image): RGB image. + - cam_info (sensor_msgs/CameraInfo): camera parameters which are used to calculate intrinsics layer. + - vo_scale (std_msgs/Float32): scale of the translation (should be published at the same frequncy with the image). If this is not provided, default value of 1.0 will be used. + +2. Published topics + - tartanvo_pose (geometry_msgs/PoseStamped): position and orientation of the camera + - tartanvo_odom (nav_msgs/Odometry): position and orientation of the camera (same with the `tartanvo_pose`). + +3. Parameters: + We use the following parameters to calculate the initial intrinsics layer. If the `cam_info` topic is received, the intrinsics value will be over-written. + - image_width : image width + - image_height : image height + - focal_x : camera focal lengh + - focal_y : camera focal lengh + - center_x : camera optical center + - center_y : camera optical center + +### Run the ROS node +1. Open a ROS core: +``` +$ roscore +``` + +2. Run the TartanVONode +``` +$ python tartanvo_node.py +``` + +3. Publish the images and scales, e.g. run the following example +``` +$ python publish_image_from_folder.py +``` + +If you open the `rviz`, you can see the visualization as follows + +![RVIZ](results/rviz.png) + + +## Paper + +More technical details are available in the TartanVO paper. Please cite this as: + +``` +@article{tartanvo2020corl, + title = {TartanVO: A Generalizable Learning-based VO}, + author = {Wang, Wenshan and Hu, Yaoyu and Scherer, Sebastian}, + booktitle = {Conference on Robot Learning (CoRL)}, + year = {2020} +} +``` + +``` +@article{tartanair2020iros, + title = {TartanAir: A Dataset to Push the Limits of Visual SLAM}, + author = {Wang, Wenshan and Zhu, Delong and Wang, Xiangwei and Hu, Yaoyu and Qiu, Yuheng and Wang, Chen and Hu, Yafei and Kapoor, Ashish and Scherer, Sebastian}, + booktitle = {2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, + year = {2020} +} +``` + +## License +This software is BSD licensed. + +Copyright (c) 2020, Carnegie Mellon University All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/TartanVO.py b/TartanVO.py new file mode 100644 index 00000000..61ee4883 --- /dev/null +++ b/TartanVO.py @@ -0,0 +1,110 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2020, Wenshan Wang, Yaoyu Hu, CMU +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of CMU nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import torch +import numpy as np +import time + +np.set_printoptions(precision=4, suppress=True, threshold=10000) + +from Network.VONet import VONet + +class TartanVO(object): + def __init__(self, model_name): + # import ipdb;ipdb.set_trace() + self.vonet = VONet() + + # load the whole model + if model_name.endswith('.pkl'): + modelname = 'models/' + model_name + self.load_model(self.vonet, modelname) + + self.vonet.cuda() + + self.test_count = 0 + self.pose_std = np.array([ 0.13, 0.13, 0.13, 0.013 , 0.013, 0.013], dtype=np.float32) # the output scale factor + self.flow_norm = 20 # scale factor for flow + + def load_model(self, model, modelname): + preTrainDict = torch.load(modelname) + model_dict = model.state_dict() + preTrainDictTemp = {k:v for k,v in preTrainDict.items() if k in model_dict} + + if( 0 == len(preTrainDictTemp) ): + print("Does not find any module to load. Try DataParallel version.") + for k, v in preTrainDict.items(): + kk = k[7:] + if ( kk in model_dict ): + preTrainDictTemp[kk] = v + + if ( 0 == len(preTrainDictTemp) ): + raise Exception("Could not load model from %s." % (modelname), "load_model") + + model_dict.update(preTrainDictTemp) + model.load_state_dict(model_dict) + print('Model loaded...') + return model + + def test_batch(self, sample): + self.test_count += 1 + + # import ipdb;ipdb.set_trace() + img0 = sample['img1'].cuda() + img1 = sample['img2'].cuda() + intrinsic = sample['intrinsic'].cuda() + inputs = [img0, img1, intrinsic] + + self.vonet.eval() + + with torch.no_grad(): + starttime = time.time() + flow, pose = self.vonet(inputs) + inferencetime = time.time()-starttime + # import ipdb;ipdb.set_trace() + posenp = pose.data.cpu().numpy() + posenp = posenp * self.pose_std # The output is normalized during training, now scale it back + flownp = flow.data.cpu().numpy() + flownp = flownp * self.flow_norm + + # calculate scale from GT posefile + if 'motion' in sample: + motions_gt = sample['motion'] + scale = np.linalg.norm(motions_gt[:,:3], axis=1) + trans_est = posenp[:,:3] + trans_est = trans_est/np.linalg.norm(trans_est,axis=1).reshape(-1,1)*scale.reshape(-1,1) + posenp[:,:3] = trans_est + else: + print(' scale is not given, using 1 as the default scale value..') + + print("{} Pose inference using {}s: \n{}".format(self.test_count, inferencetime, posenp)) + return posenp, flownp + diff --git a/evaluator/__init__.py b/evaluator/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/evaluator/evaluate_ate_scale.py b/evaluator/evaluate_ate_scale.py new file mode 100644 index 00000000..cb568cb4 --- /dev/null +++ b/evaluator/evaluate_ate_scale.py @@ -0,0 +1,133 @@ +#!/usr/bin/python + +# Modified by Wenshan Wang +# Modified by Raul Mur-Artal +# Automatically compute the optimal scale factor for monocular VO/SLAM. + +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Juergen Sturm, TUM +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of TUM nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Requirements: +# sudo apt-get install python-argparse + +""" +This script computes the absolute trajectory error from the ground truth +trajectory and the estimated trajectory. +""" + +import numpy + +def align(model,data,calc_scale=False): + """Align two trajectories using the method of Horn (closed-form). + + Input: + model -- first trajectory (3xn) + data -- second trajectory (3xn) + + Output: + rot -- rotation matrix (3x3) + trans -- translation vector (3x1) + trans_error -- translational error per point (1xn) + + """ + numpy.set_printoptions(precision=3,suppress=True) + model_zerocentered = model - model.mean(1) + data_zerocentered = data - data.mean(1) + + W = numpy.zeros( (3,3) ) + for column in range(model.shape[1]): + W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column]) + U,d,Vh = numpy.linalg.linalg.svd(W.transpose()) + S = numpy.matrix(numpy.identity( 3 )) + if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0): + S[2,2] = -1 + rot = U*S*Vh + + if calc_scale: + rotmodel = rot*model_zerocentered + dots = 0.0 + norms = 0.0 + for column in range(data_zerocentered.shape[1]): + dots += numpy.dot(data_zerocentered[:,column].transpose(),rotmodel[:,column]) + normi = numpy.linalg.norm(model_zerocentered[:,column]) + norms += normi*normi + # s = float(dots/norms) + s = float(norms/dots) + else: + s = 1.0 + + # trans = data.mean(1) - s*rot * model.mean(1) + # model_aligned = s*rot * model + trans + # alignment_error = model_aligned - data + + # scale the est to the gt, otherwise the ATE could be very small if the est scale is small + trans = s*data.mean(1) - rot * model.mean(1) + model_aligned = rot * model + trans + data_alingned = s * data + alignment_error = model_aligned - data_alingned + + trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0] + + return rot,trans,trans_error, s + +def plot_traj(ax,stamps,traj,style,color,label): + """ + Plot a trajectory using matplotlib. + + Input: + ax -- the plot + stamps -- time stamps (1xn) + traj -- trajectory (3xn) + style -- line style + color -- line color + label -- plot legend + + """ + stamps.sort() + interval = numpy.median([s-t for s,t in zip(stamps[1:],stamps[:-1])]) + x = [] + y = [] + last = stamps[0] + for i in range(len(stamps)): + if stamps[i]-last < 2*interval: + x.append(traj[i][0]) + y.append(traj[i][1]) + elif len(x)>0: + ax.plot(x,y,style,color=color,label=label) + label="" + x=[] + y=[] + last= stamps[i] + if len(x)>0: + ax.plot(x,y,style,color=color,label=label) + + diff --git a/evaluator/evaluate_kitti.py b/evaluator/evaluate_kitti.py new file mode 100644 index 00000000..021297ec --- /dev/null +++ b/evaluator/evaluate_kitti.py @@ -0,0 +1,129 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. +# This is a python reinplementation of the KITTI metric: http://www.cvlibs.net/datasets/kitti/eval_odometry.php +# Cridit: Xiangwei Wang https://github.com/TimingSpace + +import numpy as np +import sys + +def trajectory_distances(poses): + distances = [] + distances.append(0) + for i in range(1,len(poses)): + p1 = poses[i-1] + p2 = poses[i] + delta = p1[0:3,3] - p2[0:3,3] + distances.append(distances[i-1]+np.linalg.norm(delta)) + return distances + +def last_frame_from_segment_length(dist,first_frame,length): + for i in range(first_frame,len(dist)): + if dist[i]>dist[first_frame]+length: + return i + return -1 + +def rotation_error(pose_error): + a = pose_error[0,0] + b = pose_error[1,1] + c = pose_error[2,2] + d = 0.5*(a+b+c-1) + rot_error = np.arccos(max(min(d,1.0),-1.0)) + return rot_error + +def translation_error(pose_error): + dx = pose_error[0,3] + dy = pose_error[1,3] + dz = pose_error[2,3] + return np.sqrt(dx*dx+dy*dy+dz*dz) + +# def line2matrix(pose_line): +# pose_line = np.array(pose_line) +# pose_m = np.matrix(np.eye(4)) +# pose_m[0:3,:] = pose_line.reshape(3,4) +# return pose_m + +def calculate_sequence_error(poses_gt,poses_result,lengths=[10,20,30,40,50,60,70,80]): + # error_vetor + errors = [] + + # paramet + step_size = 1 #10; # every second + num_lengths = len(lengths) + + # import ipdb;ipdb.set_trace() + # pre-compute distances (from ground truth as reference) + dist = trajectory_distances(poses_gt) + # for all start positions do + for first_frame in range(0, len(poses_gt), step_size): + # for all segment lengths do + for i in range(0,num_lengths): + # current length + length = lengths[i]; + + # compute last frame + last_frame = last_frame_from_segment_length(dist,first_frame,length); + # continue, if sequence not long enough + if (last_frame==-1): + continue; + + # compute rotational and translational errors + pose_delta_gt = np.linalg.inv(poses_gt[first_frame]).dot(poses_gt[last_frame]) + pose_delta_result = np.linalg.inv(poses_result[first_frame]).dot(poses_result[last_frame]) + pose_error = np.linalg.inv(pose_delta_result).dot(pose_delta_gt) + r_err = rotation_error(pose_error); + t_err = translation_error(pose_error); + + # compute speed + num_frames = (float)(last_frame-first_frame+1); + speed = length/(0.1*num_frames); + + # write to file + error = [first_frame,r_err/length,t_err/length,length,speed] + errors.append(error) + # return error vector + return errors + +def calculate_ave_errors(errors,lengths=[10,20,30,40,50,60,70,80]): + rot_errors=[] + tra_errors=[] + for length in lengths: + rot_error_each_length =[] + tra_error_each_length =[] + for error in errors: + if abs(error[3]-length)<0.1: + rot_error_each_length.append(error[1]) + tra_error_each_length.append(error[2]) + + if len(rot_error_each_length)==0: + # import ipdb;ipdb.set_trace() + continue + else: + rot_errors.append(sum(rot_error_each_length)/len(rot_error_each_length)) + tra_errors.append(sum(tra_error_each_length)/len(tra_error_each_length)) + return np.array(rot_errors)*180/np.pi, tra_errors + +def evaluate(gt, data,kittitype=True): + if kittitype: + lens = [100,200,300,400,500,600,700,800] # + else: + lens = [5,10,15,20,25,30,35,40] #[1,2,3,4,5,6] # + errors = calculate_sequence_error(gt, data, lengths=lens) + rot,tra = calculate_ave_errors(errors, lengths=lens) + return np.mean(rot), np.mean(tra) + +def main(): + # usage: python main.py path_to_ground_truth path_to_predict_pose + # load and preprocess data + ground_truth_data = np.loadtxt(sys.argv[1]) + predict_pose__data = np.loadtxt(sys.argv[2]) + errors = calculate_sequence_error(ground_truth_data,predict_pose__data) + rot,tra = calculate_ave_errors(errors) + print(rot,'\n',tra) + #print(error) + # evaluate the vo result + # save and visualization the evaluatation result + +if __name__ == "__main__": + main() + + diff --git a/evaluator/evaluate_rpe.py b/evaluator/evaluate_rpe.py new file mode 100644 index 00000000..b99dac47 --- /dev/null +++ b/evaluator/evaluate_rpe.py @@ -0,0 +1,219 @@ +#!/usr/bin/python +# Software License Agreement (BSD License) +# +# Modified by Wenshan Wang +# Copyright (c) 2013, Juergen Sturm, TUM +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of TUM nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +This script computes the relative pose error from the ground truth trajectory +and the estimated trajectory. +""" + +import random +import numpy as np +import sys + +def ominus(a,b): + """ + Compute the relative 3D transformation between a and b. + + Input: + a -- first pose (homogeneous 4x4 matrix) + b -- second pose (homogeneous 4x4 matrix) + + Output: + Relative 3D transformation from a to b. + """ + return np.dot(np.linalg.inv(a),b) + +def compute_distance(transform): + """ + Compute the distance of the translational component of a 4x4 homogeneous matrix. + """ + return np.linalg.norm(transform[0:3,3]) + +def compute_angle(transform): + """ + Compute the rotation angle from a 4x4 homogeneous matrix. + """ + # an invitation to 3-d vision, p 27 + return np.arccos( min(1,max(-1, (np.trace(transform[0:3,0:3]) - 1)/2) )) + +def distances_along_trajectory(traj): + """ + Compute the translational distances along a trajectory. + """ + motion = [ominus(traj[i+1],traj[i]) for i in range(len(traj)-1)] + distances = [0] + sum = 0 + for t in motion: + sum += compute_distance(t) + distances.append(sum) + return distances + + +def evaluate_trajectory(traj_gt, traj_est, param_max_pairs=10000, param_fixed_delta=False, + param_delta=1.00): + """ + Compute the relative pose error between two trajectories. + + Input: + traj_gt -- the first trajectory (ground truth) + traj_est -- the second trajectory (estimated trajectory) + param_max_pairs -- number of relative poses to be evaluated + param_fixed_delta -- false: evaluate over all possible pairs + true: only evaluate over pairs with a given distance (delta) + param_delta -- distance between the evaluated pairs + param_delta_unit -- unit for comparison: + "s": seconds + "m": meters + "rad": radians + "deg": degrees + "f": frames + param_offset -- time offset between two trajectories (to model the delay) + param_scale -- scale to be applied to the second trajectory + + Output: + list of compared poses and the resulting translation and rotation error + """ + + if not param_fixed_delta: + if(param_max_pairs==0 or len(traj_est)param_max_pairs): + pairs = random.sample(pairs,param_max_pairs) + + result = [] + for i,j in pairs: + + error44 = ominus( ominus( traj_est[j], traj_est[i] ), + ominus( traj_gt[j], traj_gt[i] ) ) + + trans = compute_distance(error44) + rot = compute_angle(error44) + + result.append([i,j,trans,rot]) + + if len(result)<2: + raise Exception("Couldn't find pairs between groundtruth and estimated trajectory!") + + return result + +# import argparse +# if __name__ == '__main__': +# random.seed(0) + +# parser = argparse.ArgumentParser(description=''' +# This script computes the relative pose error from the ground truth trajectory and the estimated trajectory. +# ''') +# parser.add_argument('groundtruth_file', help='ground-truth trajectory file (format: "timestamp tx ty tz qx qy qz qw")') +# parser.add_argument('estimated_file', help='estimated trajectory file (format: "timestamp tx ty tz qx qy qz qw")') +# parser.add_argument('--max_pairs', help='maximum number of pose comparisons (default: 10000, set to zero to disable downsampling)', default=10000) +# parser.add_argument('--fixed_delta', help='only consider pose pairs that have a distance of delta delta_unit (e.g., for evaluating the drift per second/meter/radian)', action='store_true') +# parser.add_argument('--delta', help='delta for evaluation (default: 1.0)',default=1.0) +# parser.add_argument('--delta_unit', help='unit of delta (options: \'s\' for seconds, \'m\' for meters, \'rad\' for radians, \'f\' for frames; default: \'s\')',default='s') +# parser.add_argument('--offset', help='time offset between ground-truth and estimated trajectory (default: 0.0)',default=0.0) +# parser.add_argument('--scale', help='scaling factor for the estimated trajectory (default: 1.0)',default=1.0) +# parser.add_argument('--save', help='text file to which the evaluation will be saved (format: stamp_est0 stamp_est1 stamp_gt0 stamp_gt1 trans_error rot_error)') +# parser.add_argument('--plot', help='plot the result to a file (requires --fixed_delta, output format: png)') +# parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the mean translational error measured in meters will be printed)', action='store_true') +# args = parser.parse_args() + +# if args.plot and not args.fixed_delta: +# sys.exit("The '--plot' option can only be used in combination with '--fixed_delta'") + +# traj_gt = np.loadtxt(args.groundtruth_file) +# traj_est = np.loadtxt(args.estimated_file) + +# from trajectory_transform import trajectory_transform +# traj_gt, traj_est = trajectory_transform(traj_gt, traj_est) + +# traj_gt = tf.pos_quats2SE_matrices(traj_gt) +# traj_est = tf.pos_quats2SE_matrices(traj_est) + +# result = evaluate_trajectory(traj_gt, +# traj_est, +# int(args.max_pairs), +# args.fixed_delta, +# float(args.delta), +# args.delta_unit) + +# trans_error = np.array(result)[:,2] +# rot_error = np.array(result)[:,3] + +# if args.save: +# f = open(args.save,"w") +# f.write("\n".join([" ".join(["%f"%v for v in line]) for line in result])) +# f.close() + +# if args.verbose: +# print "compared_pose_pairs %d pairs"%(len(trans_error)) + +# print "translational_error.rmse %f m"%np.sqrt(np.dot(trans_error,trans_error) / len(trans_error)) +# print "translational_error.mean %f m"%np.mean(trans_error) +# print "translational_error.median %f m"%np.median(trans_error) +# print "translational_error.std %f m"%np.std(trans_error) +# print "translational_error.min %f m"%np.min(trans_error) +# print "translational_error.max %f m"%np.max(trans_error) + +# print "rotational_error.rmse %f deg"%(np.sqrt(np.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / np.pi) +# print "rotational_error.mean %f deg"%(np.mean(rot_error) * 180.0 / np.pi) +# print "rotational_error.median %f deg"%(np.median(rot_error) * 180.0 / np.pi) +# print "rotational_error.std %f deg"%(np.std(rot_error) * 180.0 / np.pi) +# print "rotational_error.min %f deg"%(np.min(rot_error) * 180.0 / np.pi) +# print "rotational_error.max %f deg"%(np.max(rot_error) * 180.0 / np.pi) +# else: +# print np.mean(trans_error) + +# import ipdb;ipdb.set_trace() + +# if args.plot: +# import matplotlib +# matplotlib.use('Agg') +# import matplotlib.pyplot as plt +# import matplotlib.pylab as pylab +# fig = plt.figure() +# ax = fig.add_subplot(111) +# ax.plot(stamps - stamps[0],trans_error,'-',color="blue") +# #ax.plot([t for t,e in err_rot],[e for t,e in err_rot],'-',color="red") +# ax.set_xlabel('time [s]') +# ax.set_ylabel('translational error [m]') +# plt.savefig(args.plot,dpi=300) + + diff --git a/evaluator/evaluator_base.py b/evaluator/evaluator_base.py new file mode 100644 index 00000000..eaad3ad6 --- /dev/null +++ b/evaluator/evaluator_base.py @@ -0,0 +1,89 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +from trajectory_transform import trajectory_transform, rescale +from transformation import pos_quats2SE_matrices, SE2pos_quat + +np.set_printoptions(suppress=True, precision=2, threshold=100000) + +def transform_trajs(gt_traj, est_traj, cal_scale): + gt_traj, est_traj = trajectory_transform(gt_traj, est_traj) + if cal_scale : + est_traj, s = rescale(gt_traj, est_traj) + print(' Scale, {}'.format(s)) + else: + s = 1.0 + return gt_traj, est_traj, s + +def quats2SEs(gt_traj, est_traj): + gt_SEs = pos_quats2SE_matrices(gt_traj) + est_SEs = pos_quats2SE_matrices(est_traj) + return gt_SEs, est_SEs + +from evaluate_ate_scale import align, plot_traj + +class ATEEvaluator(object): + def __init__(self): + super(ATEEvaluator, self).__init__() + + + def evaluate(self, gt_traj, est_traj, scale): + gt_xyz = np.matrix(gt_traj[:,0:3].transpose()) + est_xyz = np.matrix(est_traj[:, 0:3].transpose()) + + rot, trans, trans_error, s = align(gt_xyz, est_xyz, scale) + print(' ATE scale: {}'.format(s)) + error = np.sqrt(np.dot(trans_error,trans_error) / len(trans_error)) + + # align two trajs + est_SEs = pos_quats2SE_matrices(est_traj) + T = np.eye(4) + T[:3,:3] = rot + T[:3,3:] = trans + T = np.linalg.inv(T) + est_traj_aligned = [] + for se in est_SEs: + se[:3,3] = se[:3,3] * s + se_new = T.dot(se) + se_new = SE2pos_quat(se_new) + est_traj_aligned.append(se_new) + + est_traj_aligned = np.array(est_traj_aligned) + return error, gt_traj, est_traj_aligned + +# ======================= + +from evaluate_rpe import evaluate_trajectory + +class RPEEvaluator(object): + def __init__(self): + super(RPEEvaluator, self).__init__() + + + def evaluate(self, gt_SEs, est_SEs): + result = evaluate_trajectory(gt_SEs, est_SEs) + + trans_error = np.array(result)[:,2] + rot_error = np.array(result)[:,3] + + trans_error_mean = np.mean(trans_error) + rot_error_mean = np.mean(rot_error) + + # import ipdb;ipdb.set_trace() + + return (rot_error_mean, trans_error_mean) + +# ======================= + +from evaluate_kitti import evaluate as kittievaluate + +class KittiEvaluator(object): + def __init__(self): + super(KittiEvaluator, self).__init__() + + # return rot_error, tra_error + def evaluate(self, gt_SEs, est_SEs, kittitype): + # trajectory_scale(est_SEs, 0.831984631412) + error = kittievaluate(gt_SEs, est_SEs, kittitype=kittitype) + return error diff --git a/evaluator/pose_est.txt b/evaluator/pose_est.txt new file mode 100644 index 00000000..bf1d957a --- /dev/null +++ b/evaluator/pose_est.txt @@ -0,0 +1,734 @@ +0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 1.000000000000000000e+00 +-7.763581722974777222e-02 8.129438757896423340e-02 8.294846117496490479e-02 1.040334086665092687e-02 1.041169190809397287e-05 2.011712313020339732e-02 9.997435032193935367e-01 +-1.614615394973635265e-01 1.753936329237417158e-01 1.824119399153587007e-01 2.189289735848180471e-02 3.260965583645257884e-04 4.095062368656528229e-02 9.989212336112042179e-01 +-2.483997135085643793e-01 2.510054263822752985e-01 2.833032081283895498e-01 3.369437576438091830e-02 8.340466259779691837e-04 6.266394019408838556e-02 9.974653986514492310e-01 +-3.529906697922169379e-01 3.595898575063656288e-01 3.870853431034880776e-01 4.637325208655862507e-02 1.227550561596514080e-03 8.501253099674151159e-02 9.952993929278292073e-01 +-4.535691853102751248e-01 4.568637710855560918e-01 4.845526710044738561e-01 5.965438091144881216e-02 1.521359706053023028e-03 1.078180747714191229e-01 9.923781052491449373e-01 +-5.581615826024445282e-01 5.510385940212652045e-01 5.734740478287805310e-01 7.331615232253894943e-02 1.618413853996865165e-03 1.308376388366791765e-01 9.886878357407519191e-01 +-6.897704174794190290e-01 6.581356249561387539e-01 6.748434631430831887e-01 8.658215377582006989e-02 1.708541625585218663e-03 1.538210618132044571e-01 9.842965445244924449e-01 +-8.455515829656050641e-01 7.827321154762114652e-01 7.665332346157245347e-01 9.995978770471897201e-02 1.513542442906467460e-03 1.765521462832924382e-01 9.792012504960488917e-01 +-1.005513256527982735e+00 9.027695237376163195e-01 8.540858013618440880e-01 1.130726715079791306e-01 1.288185412497112490e-03 1.989259590578820736e-01 9.734687286525551819e-01 +-1.185129075147004274e+00 1.021053229676384566e+00 9.391665916590067331e-01 1.257653451526082322e-01 1.150079331193483694e-03 2.206728462822609149e-01 9.672048514541641273e-01 +-1.374462012916290554e+00 1.141221578215573240e+00 1.015970865367560094e+00 1.376554687585733461e-01 1.061026809043993544e-03 2.417534712645754424e-01 9.605233365418593960e-01 +-1.588499030350069452e+00 1.266209135639860373e+00 1.086002959009900071e+00 1.485755038267222716e-01 9.605313046758917573e-04 2.622085642178698661e-01 9.535046055003959520e-01 +-1.818806502634098043e+00 1.383276731247666813e+00 1.140712190299622009e+00 1.584588407539465338e-01 8.681071444247497352e-04 2.817861214627339073e-01 9.463015368426513918e-01 +-2.045776265470826250e+00 1.492418481673508657e+00 1.184797250600713614e+00 1.670675346700424002e-01 8.257189692240109700e-04 3.001841140278199149e-01 9.391364327290262493e-01 +-2.276180491460872535e+00 1.596256008567038975e+00 1.221639715698451978e+00 1.742704915296339196e-01 9.591303608554155227e-04 3.170547184699983312e-01 9.322580994966139789e-01 +-2.506512307163954123e+00 1.697691124429126175e+00 1.253975000882568303e+00 1.801102943798766620e-01 1.308365573539137326e-03 3.320161931722179216e-01 9.259178078324850070e-01 +-2.730647291904825469e+00 1.791590510575493456e+00 1.278466289637631537e+00 1.840968232324677878e-01 1.578886214964081739e-03 3.451396192693618192e-01 9.203175983449257691e-01 +-2.923433144178567922e+00 1.870891735631864616e+00 1.292601088431287737e+00 1.849707697653387994e-01 1.386025599471512292e-03 3.562485413351011987e-01 9.158989209312665691e-01 +-3.077175452596739635e+00 1.933593849915830720e+00 1.299696969678707736e+00 1.854755639593988203e-01 1.868600603979128421e-03 3.650181587589055865e-01 9.123360260273387645e-01 +-3.193939947754621311e+00 1.981891317735233304e+00 1.303578995604927293e+00 1.855183673014065560e-01 3.083188543593773021e-03 3.715047670010525604e-01 9.097019288038555862e-01 +-3.315409474942201840e+00 2.030990137869406187e+00 1.311135170562608199e+00 1.812982113234903048e-01 3.879075462185585434e-03 3.754939783009084153e-01 9.089115129713721819e-01 +-3.457097195304501103e+00 2.079057742802964626e+00 1.323314158036400512e+00 1.751551006930524568e-01 4.849743914728919456e-03 3.771605153527103349e-01 9.094212882393348796e-01 +-3.607751299212842433e+00 2.125597561155946114e+00 1.328744742853992244e+00 1.669760035300219270e-01 5.862731875882476289e-03 3.762797830799659016e-01 9.113167052387843858e-01 +-3.741661109607048896e+00 2.166749128476885389e+00 1.330438836879045406e+00 1.569512452791514689e-01 6.669659372063521142e-03 3.735049313371923141e-01 9.142296515067259710e-01 +-3.860063450797174944e+00 2.199894961373179303e+00 1.333838814317130472e+00 1.454407120026545708e-01 7.241853549464966934e-03 3.691224647884061572e-01 9.179014869378113728e-01 +-3.965440417418732100e+00 2.226800631160249289e+00 1.343206933663203984e+00 1.325379926970463584e-01 7.844176604592478091e-03 3.633626870690228605e-01 9.221386473454279420e-01 +-4.066402862077570290e+00 2.255844838276743314e+00 1.355485145997750829e+00 1.183286632454299964e-01 8.219612003103273987e-03 3.562999831573637755e-01 9.268123073828324898e-01 +-4.169311459254840813e+00 2.289886648958757487e+00 1.371346518212128496e+00 1.032299517681223161e-01 8.406974670792977805e-03 3.479357009271835111e-01 9.317798054429122789e-01 +-4.274304728659573449e+00 2.326110416854968665e+00 1.388732450883825464e+00 8.741415828963333690e-02 8.379913478480226913e-03 3.384163034407642878e-01 9.368900192068824184e-01 +-4.371023610733479003e+00 2.361730196758660583e+00 1.403553973261158161e+00 7.102109638379625056e-02 8.057980014233599719e-03 3.279150071870076122e-01 9.419993613653473430e-01 +-4.459560418429068918e+00 2.395030322184842575e+00 1.416461243442338258e+00 5.420612473697292849e-02 7.365064650816518024e-03 3.164921687723831201e-01 9.470164409778689674e-01 +-4.540001823203836828e+00 2.425599654086818990e+00 1.426464306582395425e+00 3.715621844980641908e-02 6.231494058011067053e-03 3.043837172282954362e-01 9.518041337804227231e-01 +-4.612358115392317437e+00 2.452776723440271756e+00 1.433268633649291468e+00 2.011834412594883451e-02 4.716985069882587492e-03 2.919181785674783702e-01 9.562200316515701015e-01 +-4.676197707866614373e+00 2.476170399256655941e+00 1.437578832081728653e+00 3.272165197888430091e-03 2.840839541992785672e-03 2.793353264558116611e-01 9.601838140965953672e-01 +-4.729394004887086389e+00 2.494799783342323884e+00 1.440516646926108590e+00 -1.318569206037614912e-02 7.089819845754987337e-04 2.668435421441125444e-01 9.636493737582385588e-01 +-4.773843758590919251e+00 2.507891700440353144e+00 1.442752113368175770e+00 -2.903920539287624045e-02 -1.910930719998760402e-03 2.545928327167661376e-01 9.666103197388770107e-01 +-4.810216717409360854e+00 2.516280950884616008e+00 1.445033489495043622e+00 -4.413449361689851524e-02 -5.156598890310192841e-03 2.426934570333589558e-01 9.690848176630005861e-01 +-4.842444961040081708e+00 2.521851936853974241e+00 1.448018661613891700e+00 -5.830208152581990710e-02 -9.081029144956875507e-03 2.314251854411013276e-01 9.710616495485874244e-01 +-4.866759795781309350e+00 2.525786235783391565e+00 1.452406291993692200e+00 -7.126999092386157586e-02 -1.369779941037953253e-02 2.210570242580389144e-01 9.725567772416677803e-01 +-4.884401443052239777e+00 2.527892111796247843e+00 1.457189468992783343e+00 -8.289824316857601072e-02 -1.915495834478810055e-02 2.119194481674736563e-01 9.735764284800602075e-01 +-4.892039541818142823e+00 2.529953841039938478e+00 1.458850563230165820e+00 -9.301414318055745145e-02 -2.547372208527273404e-02 2.043313470160121326e-01 9.741396701707516481e-01 +-4.899106108043921104e+00 2.532639924374405549e+00 1.459694477163018700e+00 -1.016629322170821970e-01 -3.248648335372286700e-02 1.980939191208750672e-01 9.743551761291968649e-01 +-4.913951589168281231e+00 2.534521876501546256e+00 1.461731588944155558e+00 -1.089088070086514509e-01 -4.010769518544383266e-02 1.929507514486798747e-01 9.743203648503796499e-01 +-4.933610942602353333e+00 2.538586854819794958e+00 1.464692314854086463e+00 -1.147749002202129304e-01 -4.828628938072188070e-02 1.886497650383399949e-01 9.741182319926873223e-01 +-4.958440654878941700e+00 2.543277612007893929e+00 1.468203406428834512e+00 -1.194863089348542767e-01 -5.696299705392537938e-02 1.853303060451857998e-01 9.737200862826957959e-01 +-4.990954677322402944e+00 2.549407909844580988e+00 1.471203394844951884e+00 -1.231642486268289260e-01 -6.604007246099961870e-02 1.828656214855920725e-01 9.731543130891747717e-01 +-5.025047938541398196e+00 2.558715939396833505e+00 1.473825988547360355e+00 -1.259017917447793344e-01 -7.542633386954311625e-02 1.811794706028058144e-01 9.724368823910578552e-01 +-5.056480018462073289e+00 2.564807758629558343e+00 1.475891196155413532e+00 -1.278915055890489927e-01 -8.509363100646011313e-02 1.800907271765929685e-01 9.715812114247180942e-01 +-5.086104798580855402e+00 2.569691283527485659e+00 1.477163312790321648e+00 -1.292293462264915427e-01 -9.496559244675582823e-02 1.794984267144049683e-01 9.705985276768369641e-01 +-5.112606255918975329e+00 2.573412687699331514e+00 1.477477854537477153e+00 -1.299627604284677995e-01 -1.049854785309249916e-01 1.792703541166686954e-01 9.695100505118784406e-01 +-5.134905255077595321e+00 2.576288036269610782e+00 1.477239630484135979e+00 -1.302426546338418811e-01 -1.150711451979672811e-01 1.792885473078411618e-01 9.683237916200010398e-01 +-5.153893624298311771e+00 2.578483882124743776e+00 1.476620330702864026e+00 -1.302009236249876412e-01 -1.251474567794172432e-01 1.794546117522611839e-01 9.670479499330235651e-01 +-5.170387700900536565e+00 2.580064156137910292e+00 1.475659244919312441e+00 -1.299670410286786204e-01 -1.351584452176034790e-01 1.796414632746508588e-01 9.656964250670172500e-01 +-5.184181027452599899e+00 2.581160090942109075e+00 1.474565384211478536e+00 -1.296418604936777075e-01 -1.450448905082182272e-01 1.797323884557865681e-01 9.642878788901542153e-01 +-5.193670199816169841e+00 2.581753477051173640e+00 1.473764585350773926e+00 -1.293351330843586777e-01 -1.547441736237192833e-01 1.795981723139647712e-01 9.628452851806021950e-01 +-5.199333265867458032e+00 2.582035217643015024e+00 1.473379856620376183e+00 -1.291569717635498993e-01 -1.641813293619758807e-01 1.791096871363017651e-01 9.613961617381699964e-01 +-5.202331774675752030e+00 2.581664544006828432e+00 1.473864297841081417e+00 -1.292272888139313625e-01 -1.732843541244645513e-01 1.782025435959828374e-01 9.599565502006950357e-01 +-5.206241793394302597e+00 2.582221202370767354e+00 1.474536803626558035e+00 -1.297041040826846792e-01 -1.820029342402989803e-01 1.766310062204095588e-01 9.585682842352059030e-01 +-5.210985438789853319e+00 2.583094789759607490e+00 1.474966989504564285e+00 -1.307007029242959195e-01 -1.902369471614826779e-01 1.743631391815418374e-01 9.572484572619643917e-01 +-5.216251160117276520e+00 2.583977407180919617e+00 1.475366210935058264e+00 -1.323205068189602929e-01 -1.979592096899689679e-01 1.712833846211577193e-01 9.560153302771712269e-01 +-5.222946233934185223e+00 2.586808942321393801e+00 1.472278643001111886e+00 -1.310237157238480776e-01 -2.045421318352779183e-01 1.680589194756306470e-01 9.553802323633658888e-01 +-5.231628991463434630e+00 2.589857794226577248e+00 1.469924268626294328e+00 -1.299914791537154501e-01 -2.105017348685536416e-01 1.642104059553242124e-01 9.548958446152637780e-01 +-5.242168825144799982e+00 2.592841460080200999e+00 1.468451453680363228e+00 -1.292111837068332103e-01 -2.159394456534998452e-01 1.599379638273054072e-01 9.545126345911275623e-01 +-5.253286415437917078e+00 2.595970513784641387e+00 1.467826428868046262e+00 -1.286807950362075514e-01 -2.209464468219945743e-01 1.552757326655797021e-01 9.542081801217947579e-01 +-5.265486490643125350e+00 2.599432535416068557e+00 1.467152445892538015e+00 -1.283580449028720871e-01 -2.256078437309221862e-01 1.503256341714759581e-01 9.539535620795475124e-01 +-5.278931683231727234e+00 2.602917166318048814e+00 1.466546231382643173e+00 -1.282128746978846989e-01 -2.299556577100002053e-01 1.452586887261335946e-01 9.537198972899648686e-01 +-5.294180719114427447e+00 2.606445447497604206e+00 1.466469015635006201e+00 -1.281738649061152646e-01 -2.340465156471444597e-01 1.402375308412729671e-01 9.534815137992896927e-01 +-5.312463140471031409e+00 2.609762618928178846e+00 1.467229721920807917e+00 -1.281673290126850717e-01 -2.379196270513008749e-01 1.354483648227918224e-01 9.532161404201969779e-01 +-5.335824573770256762e+00 2.613782928396423788e+00 1.469043526066431404e+00 -1.281189173127078307e-01 -2.416006561296493993e-01 1.310745825024880462e-01 9.529081867508989445e-01 +-5.363259463899353818e+00 2.617851172109413760e+00 1.471131569469693146e+00 -1.280001689701116829e-01 -2.451563298382018197e-01 1.272199112235238294e-01 9.525383605911197371e-01 +-5.395411344443875379e+00 2.623212074403216576e+00 1.472248485541352014e+00 -1.277061673877437353e-01 -2.486749857660476848e-01 1.239774978389931309e-01 9.520931477990380865e-01 +-5.426128985633432933e+00 2.629509303787030738e+00 1.472886535222979631e+00 -1.272485630563925385e-01 -2.522551300913905559e-01 1.214382283999674711e-01 9.515396978379735415e-01 +-5.452652039613852253e+00 2.636104068030554970e+00 1.473580777471113379e+00 -1.265948281006319676e-01 -2.558473110227643121e-01 1.197640264486956596e-01 9.508797857273025844e-01 +-5.472306931796175888e+00 2.641829902721481105e+00 1.473873320383656482e+00 -1.256680327166950772e-01 -2.594724547148206106e-01 1.191192015543088567e-01 9.501010974737226222e-01 +-5.492777734979259918e+00 2.648747575407238042e+00 1.473959231064704500e+00 -1.244619490961244718e-01 -2.631815118648019314e-01 1.198660794814391944e-01 9.491452656899548312e-01 +-5.517309030986859320e+00 2.656660512910526073e+00 1.473909882633906099e+00 -1.229588360211476133e-01 -2.670171479008756621e-01 1.220429262392918324e-01 9.479917596835117921e-01 +-5.548501007034063015e+00 2.665854748006321273e+00 1.473972335360250963e+00 -1.210092705313811912e-01 -2.710428319108487139e-01 1.256652081050372294e-01 9.466259477090569474e-01 +-5.582659995289544597e+00 2.676549627306799017e+00 1.473410706142274762e+00 -1.184397636966367240e-01 -2.754753876080917596e-01 1.309016614379956145e-01 9.449603036347121732e-01 +-5.618542000812452919e+00 2.688346823076197545e+00 1.473815846312817035e+00 -1.152002555259703243e-01 -2.803413333399834562e-01 1.378292494260122403e-01 9.429425343495222434e-01 +-5.658800331255713800e+00 2.701072122771759787e+00 1.476535456259537193e+00 -1.111809696889956428e-01 -2.856535347335066866e-01 1.466344650116992443e-01 9.404993667055564499e-01 +-5.723162393434017226e+00 2.711850001969680513e+00 1.472010511799559440e+00 -9.645960069527406699e-02 -2.899736214586458583e-01 1.603600069216811475e-01 9.385602750540950057e-01 +-5.789886399037957432e+00 2.724914339993221191e+00 1.467559068109455245e+00 -7.961234498813223037e-02 -2.944040355605375137e-01 1.761043348999501434e-01 9.359355020986513951e-01 +-5.857801027110975056e+00 2.744695431095274696e+00 1.463945204565434421e+00 -6.075934553055403753e-02 -2.988044004969594991e-01 1.932606735103165330e-01 9.325633481775772449e-01 +-5.928718842828847535e+00 2.767996982110530357e+00 1.460667842684073348e+00 -4.041363023151172545e-02 -3.030217965527199353e-01 2.116615388665777919e-01 9.283015556563347648e-01 +-6.002894602593839224e+00 2.792273267216474952e+00 1.458903479340398990e+00 -1.906988129351004299e-02 -3.068992941963777921e-01 2.311642366215765632e-01 9.230450172788735586e-01 +-6.080423592056320103e+00 2.816755985211592872e+00 1.457840699040749088e+00 2.989901128715029190e-03 -3.103978479901604026e-01 2.515253384808229797e-01 9.167219268166566515e-01 +-6.159821503433136058e+00 2.842283901774936172e+00 1.456838883270557883e+00 2.555327984341005526e-02 -3.134828696451882335e-01 2.725158317531349850e-01 9.092911994515439078e-01 +-6.242220272728821406e+00 2.869195785452348435e+00 1.457031532612975910e+00 4.835426017865434439e-02 -3.160287452290629906e-01 2.938780975588026201e-01 9.007903192073739573e-01 +-6.328228979922918107e+00 2.897916089429688480e+00 1.459431885899282078e+00 7.112281369337754289e-02 -3.179164658780405661e-01 3.153813211739048272e-01 8.912940786818626115e-01 +-6.418319400752959147e+00 2.929363133766030192e+00 1.463556676178051852e+00 9.361902027674687266e-02 -3.191164931957644613e-01 3.367341951773196729e-01 8.809143376209914722e-01 +-6.512459485064193032e+00 2.961652060875547221e+00 1.469992759476173250e+00 1.154273123828760544e-01 -3.196110203343623946e-01 3.576625340537895603e-01 8.698291177469383850e-01 +-6.608705668912721265e+00 2.993374042313872163e+00 1.477422440200679254e+00 1.362564011417555232e-01 -3.194120827828730858e-01 3.779349820944927774e-01 8.582395397556208394e-01 +-6.708860129414741635e+00 3.029684950161678270e+00 1.483726567384882733e+00 1.557847355957741042e-01 -3.186315622378103063e-01 3.972704498662247841e-01 8.463929817961677315e-01 +-6.819298594650499368e+00 3.074051487095454505e+00 1.490085988826882257e+00 1.736994998816114855e-01 -3.172153833985199012e-01 4.153375084553274088e-01 8.346840542764281112e-01 +-6.937727501343463388e+00 3.123999412892846994e+00 1.495942713530356682e+00 1.897426385614484623e-01 -3.152290908872911745e-01 4.316833056047169603e-01 8.235761676614492544e-01 +-7.053690389257425863e+00 3.175431624220932392e+00 1.500371635520052482e+00 2.035718323494609405e-01 -3.128428333350659618e-01 4.460332176324769415e-01 8.134753052567540443e-01 +-7.160507266271090465e+00 3.219836099753031089e+00 1.503678186645701187e+00 2.147192789143497760e-01 -3.101588794608615141e-01 4.586560715210674100e-01 8.045691677036902467e-01 +-7.263857222743489217e+00 3.259420686638322184e+00 1.507104829137044577e+00 2.230030551458123678e-01 -3.071117296537569374e-01 4.694030734605031951e-01 7.972531801455003952e-01 +-7.379427554787534760e+00 3.303978953117806316e+00 1.512684161807263727e+00 2.285458026868785741e-01 -3.033655638342385719e-01 4.783511397594756853e-01 7.917803892531537491e-01 +-7.513956051602586506e+00 3.354457427853559270e+00 1.517813172094303109e+00 2.313569936374561264e-01 -2.988858572686310944e-01 4.853137690080703837e-01 7.884234824257249086e-01 +-7.647871124811962851e+00 3.403524157911047343e+00 1.519694781159322883e+00 2.307807859810244722e-01 -2.941287420864104329e-01 4.897210142813168132e-01 7.876558226717300659e-01 +-7.783024520160962467e+00 3.454887356183196978e+00 1.531881838661782735e+00 2.270182624484105294e-01 -2.889180509553187504e-01 4.918595901670846371e-01 7.893434444840518038e-01 +-7.932927031712694088e+00 3.515541344819415048e+00 1.544813960111571349e+00 2.209137782161527952e-01 -2.832097413707863054e-01 4.918438846262578878e-01 7.931448797570244125e-01 +-8.066793397270458854e+00 3.569413410737276582e+00 1.559274798339227663e+00 2.119618830049600222e-01 -2.773903912958500806e-01 4.906034406410121340e-01 7.983951694859114934e-01 +-8.192223267129946862e+00 3.619156454846514492e+00 1.574389835259532466e+00 2.007164604924963069e-01 -2.714268003444554322e-01 4.875667565567802231e-01 8.051825387388809041e-01 +-8.320078886071526014e+00 3.669773930832634701e+00 1.589713284153562167e+00 1.873456602548720096e-01 -2.654088840600973831e-01 4.830340534420075049e-01 8.131037354177889087e-01 +-8.445641803750774557e+00 3.718161069698102228e+00 1.602382435863983989e+00 1.722686950193424715e-01 -2.592978863788403254e-01 4.770453874402176830e-01 8.218976054209284898e-01 +-8.585898597663639720e+00 3.763842337255594028e+00 1.612724215029670782e+00 1.559540902868197521e-01 -2.529943279552718249e-01 4.697196254227078427e-01 8.312854751181643076e-01 +-8.744284886021782555e+00 3.810431377428940003e+00 1.623718323368587235e+00 1.385303921116263770e-01 -2.465440258096578408e-01 4.612076909196240471e-01 8.410188561040446986e-01 +-8.917256787043321253e+00 3.857984143852772885e+00 1.635529520697025729e+00 1.200997614827219034e-01 -2.400285635394314998e-01 4.518427327995526710e-01 8.507645647184876037e-01 +-9.104064759810293950e+00 3.909468736568438185e+00 1.647792240600521207e+00 1.010256813838104617e-01 -2.334802681253919932e-01 4.416485369603997957e-01 8.603645783314409767e-01 +-9.301241223158305260e+00 3.966133280590436350e+00 1.659879276563957395e+00 8.162298523277151940e-02 -2.270393438443374656e-01 4.308338925838269828e-01 8.695819940915584523e-01 +-9.506898456077562898e+00 4.033050506019718817e+00 1.671615796186202152e+00 6.232921915732245188e-02 -2.207809463892332902e-01 4.195279425445178068e-01 8.782750198852098400e-01 +-9.719084547238489691e+00 4.107758244306594975e+00 1.683041549236502066e+00 4.339485462197354565e-02 -2.147223909901595229e-01 4.081630697574083477e-01 8.862358301817121475e-01 +-9.937901626828326229e+00 4.184882732919266601e+00 1.691597128612665424e+00 2.514333870120135858e-02 -2.090149953532211835e-01 3.970576489093294303e-01 8.933228028578739099e-01 +-1.016759103732679392e+01 4.263001199913111883e+00 1.695061943809942129e+00 7.951056979035085390e-03 -2.037524638280196476e-01 3.863944356921051870e-01 8.995114907978111196e-01 +-1.040311776555026668e+01 4.342138223454597323e+00 1.694155376650493539e+00 -7.860991495868187989e-03 -1.991039859389698297e-01 3.761993446063320312e-01 9.048589492432858039e-01 +-1.062897301257094007e+01 4.421929781002599036e+00 1.690288951959063590e+00 -2.214107243025818447e-02 -1.953405400448643969e-01 3.664771572666042365e-01 9.094207967402290205e-01 +-1.083888411301165178e+01 4.502998187798571195e+00 1.686517435052399483e+00 -3.432563094326723102e-02 -1.924284141359653699e-01 3.578962584641444677e-01 9.130734760142072970e-01 +-1.102600989759129213e+01 4.574895040257780821e+00 1.683943445938448136e+00 -4.432764650310910826e-02 -1.905976866897620137e-01 3.511897429252484604e-01 9.156272141432794109e-01 +-1.119162909577845610e+01 4.637566012598074217e+00 1.683328669899319951e+00 -5.190637318312452120e-02 -1.897319204890198785e-01 3.464870459511551481e-01 9.171990500328939255e-01 +-1.138509586620138769e+01 4.700995911950154316e+00 1.682164000735672182e+00 -5.716773658474903069e-02 -1.900562658324461418e-01 3.437203900201822315e-01 9.178597923492943789e-01 +-1.158554687652896398e+01 4.773839985834662514e+00 1.684945256451874096e+00 -5.996103732729100855e-02 -1.911621616282371816e-01 3.424860699307142875e-01 9.179133040169402680e-01 +-1.177760597264674303e+01 4.855169503782111207e+00 1.688083280889883353e+00 -6.048066505920299957e-02 -1.931844251355316622e-01 3.427646024985401829e-01 9.173517037762234372e-01 +-1.196887591957389496e+01 4.947745171815075338e+00 1.686750522816761855e+00 -5.925859327901381729e-02 -1.960387045525514016e-01 3.442936519395072281e-01 9.162526822346890309e-01 +-1.216992391604054902e+01 5.054905297112563645e+00 1.685436264709414989e+00 -5.622420424806187644e-02 -1.994930407666681560e-01 3.469751204847852932e-01 9.146854551281152768e-01 +-1.236532759982683061e+01 5.162857071153237776e+00 1.682019361756213582e+00 -5.158909614579330200e-02 -2.035015282505595879e-01 3.506607040282821997e-01 9.126678623466392137e-01 +-1.256170608523899901e+01 5.273156950802071030e+00 1.679515879409670953e+00 -4.537404264791386477e-02 -2.079235185402558694e-01 3.553344735306013802e-01 9.101902459545322399e-01 +-1.276708765983067906e+01 5.389368126411258508e+00 1.681734725436552669e+00 -3.773606152303884964e-02 -2.125714885631528328e-01 3.607183884419826736e-01 9.073430853038946253e-01 +-1.297045639587896915e+01 5.502656323061654753e+00 1.684277003464522693e+00 -2.895915841600426449e-02 -2.175540603194260902e-01 3.667778982942412891e-01 9.040494676300264709e-01 +-1.316619284720094640e+01 5.616050585154817476e+00 1.685634018354128516e+00 -1.912370531618038869e-02 -2.226372597372509310e-01 3.730394864934088450e-01 9.005044928755971956e-01 +-1.337143560244176044e+01 5.735008513802350549e+00 1.690148906924720640e+00 -8.392904909194753849e-03 -2.277444471868876330e-01 3.796126924332511310e-01 8.966359897929240264e-01 +-1.356737765708902188e+01 5.849611986405886199e+00 1.694239201507259596e+00 3.188069272633895900e-03 -2.328242933347296761e-01 3.861322106115112618e-01 8.925718311500835389e-01 +-1.377000282528432784e+01 5.965616664818147896e+00 1.699851328706560638e+00 1.545742103295346184e-02 -2.377059136115166060e-01 3.925069498358597642e-01 8.883665491224195243e-01 +-1.398212489561399607e+01 6.084928747493433043e+00 1.708285859510020321e+00 2.820644182687547311e-02 -2.423252529499348162e-01 3.987638062806674322e-01 8.840080159246346270e-01 +-1.420648560532310078e+01 6.210423501976889860e+00 1.718109657231867038e+00 4.128077843900963134e-02 -2.466187100076117078e-01 4.048654964394661215e-01 8.795219754325778183e-01 +-1.443425241573653572e+01 6.334786491546755549e+00 1.725589570138854167e+00 5.455567918078327305e-02 -2.505771213294181732e-01 4.106165240693651630e-01 8.750021179724133402e-01 +-1.466078662471714722e+01 6.456107463720189621e+00 1.731439103688600323e+00 6.788851507020579601e-02 -2.541798207114213670e-01 4.158866153694868451e-01 8.705296904758311749e-01 +-1.488285297923898121e+01 6.573529320482816907e+00 1.737718214085419266e+00 8.109585000858207660e-02 -2.573371237995916716e-01 4.204963649265053838e-01 8.662469212230400339e-01 +-1.509735422230190238e+01 6.686039798413209390e+00 1.743139241988748367e+00 9.393535441045894330e-02 -2.599591505149226878e-01 4.243821918820579464e-01 8.622627143897424462e-01 +-1.530865095285013311e+01 6.796819388747013413e+00 1.746061735856029085e+00 1.063152694493233186e-01 -2.619316692924129608e-01 4.275231495756733335e-01 8.586691296852853039e-01 +-1.551262471361659934e+01 6.907480535836007185e+00 1.748239987247944383e+00 1.182349415536220888e-01 -2.632263886307654177e-01 4.300142524946435896e-01 8.554647568458139117e-01 +-1.570625846627583577e+01 7.013312466228680542e+00 1.750445888451903187e+00 1.298043062854738749e-01 -2.639090550059828288e-01 4.318805497222688583e-01 8.526323214820138441e-01 +-1.589019998778768716e+01 7.112664845566693650e+00 1.752781886349465967e+00 1.409289133858263876e-01 -2.641656477315370011e-01 4.330758048961919071e-01 8.501768791463034658e-01 +-1.606792120950874647e+01 7.208294803460730371e+00 1.754591869893346701e+00 1.517765163723192312e-01 -2.638692742451970163e-01 4.336451467018893058e-01 8.481088428129829326e-01 +-1.624434227101607320e+01 7.303142846534119492e+00 1.753898109638208691e+00 1.623957051178717692e-01 -2.630526253297322259e-01 4.335576118085632813e-01 8.464387588780707405e-01 +-1.641625602811456019e+01 7.395043159563359225e+00 1.751152354780340259e+00 1.726525697619735733e-01 -2.619629885775675571e-01 4.328739764729817585e-01 8.450955121849976770e-01 +-1.658587085178702480e+01 7.485826733257320953e+00 1.748231259560814044e+00 1.826036761368338701e-01 -2.606393656664650615e-01 4.315508758716597448e-01 8.440892646836253288e-01 +-1.675089644930930177e+01 7.575510349925608011e+00 1.745856667694209330e+00 1.922807357009022056e-01 -2.591184385917666422e-01 4.297045137176721541e-01 8.433502304484872258e-01 +-1.691506089922895484e+01 7.665309506093168856e+00 1.743384547774412763e+00 2.017770353694364749e-01 -2.575116521304156580e-01 4.273549743327898498e-01 8.428174999857650507e-01 +-1.708644637763754659e+01 7.758788866789966043e+00 1.742004140810507806e+00 2.111321666661664098e-01 -2.558397527854995857e-01 4.245088266948168765e-01 8.424733385149421050e-01 +-1.726784494652930135e+01 7.856822001082897522e+00 1.742654404360780562e+00 2.202197341042913814e-01 -2.541798948408322545e-01 4.211774153635236551e-01 8.423213530536949323e-01 +-1.746024801472902865e+01 7.960010265021137954e+00 1.745074856908168881e+00 2.289213759479810650e-01 -2.526004026647560297e-01 4.175357519182459343e-01 8.422895932772127559e-01 +-1.766654731231349373e+01 8.070327666174712533e+00 1.749793661338604478e+00 2.372063226794104418e-01 -2.511936926804049786e-01 4.136414953630123126e-01 8.423392565676695032e-01 +-1.787788669118211615e+01 8.183003558841669189e+00 1.755478918113403175e+00 2.450457413536536733e-01 -2.501033031262356321e-01 4.096916862187967578e-01 8.423499753459694483e-01 +-1.809178068879210954e+01 8.297254115051348577e+00 1.760518962209867366e+00 2.524429972134340505e-01 -2.493763715999471331e-01 4.056703627689585701e-01 8.423273410439073849e-01 +-1.829889634534535148e+01 8.414415868617682648e+00 1.763164725088491425e+00 2.592251936228366360e-01 -2.490581846075268502e-01 4.017012901080917464e-01 8.422637539869913814e-01 +-1.851064610958139767e+01 8.534587540429054542e+00 1.764080181755627086e+00 2.655126382578260613e-01 -2.491929627978202721e-01 3.976523144453786296e-01 8.421866733400295013e-01 +-1.872454699617393103e+01 8.657280115236002160e+00 1.765527871483244526e+00 2.713811710415635625e-01 -2.498018764759534494e-01 3.935295657386952417e-01 8.420722093215934345e-01 +-1.894476973094467809e+01 8.784598810057248741e+00 1.768893760754383537e+00 2.767423065037515340e-01 -2.509284107718010581e-01 3.893340918734590206e-01 8.419426592142716936e-01 +-1.916930753403601884e+01 8.909285765942943414e+00 1.783316449746438659e+00 2.754078127414572585e-01 -2.555650128083557515e-01 3.828539219274156302e-01 8.439548559210982015e-01 +-1.939833876380693667e+01 9.043023693463442925e+00 1.795814343152166925e+00 2.741002434342232896e-01 -2.604431742157352625e-01 3.764380432859956715e-01 8.457734172403018613e-01 +-1.963030247248972771e+01 9.185783372552252857e+00 1.806329673449146300e+00 2.727671470290222167e-01 -2.654510008092491047e-01 3.701835801397498904e-01 8.474065255370455407e-01 +-1.985929403658107972e+01 9.327231473640164694e+00 1.814036488740335740e+00 2.714815194294271095e-01 -2.705141545889362398e-01 3.640393622045553501e-01 8.488787256893001176e-01 +-2.008724920614000098e+01 9.470197801790330772e+00 1.819776077373240097e+00 2.702972236686065344e-01 -2.755438478847290207e-01 3.581381006992591653e-01 8.501481949323179688e-01 +-2.032193039518956112e+01 9.621574230777977021e+00 1.825137553906702736e+00 2.692228019766066960e-01 -2.804239749088110467e-01 3.526741685036900997e-01 8.511769884460007596e-01 +-2.055983410568753911e+01 9.794256163438852525e+00 1.827306526060864522e+00 2.682162956675854248e-01 -2.850021063575245428e-01 3.477638855419329378e-01 8.519941087514807387e-01 +-2.080293224004554631e+01 9.972464334757884075e+00 1.829046400636300307e+00 2.672929664477728950e-01 -2.892413510317480285e-01 3.434828989686284917e-01 8.525920906990737125e-01 +-2.104319455191703980e+01 1.015193624681640117e+01 1.830505407648819860e+00 2.665293772039856735e-01 -2.930953321927718958e-01 3.398652204467554339e-01 8.529646562564245915e-01 +-2.127315204145920546e+01 1.034196338290001549e+01 1.829235382877234306e+00 2.661559915932656395e-01 -2.962545926634149174e-01 3.368958021106880918e-01 8.531677962679651284e-01 +-2.149062860136037401e+01 1.053373496479204618e+01 1.827213082327507676e+00 2.661038993072872283e-01 -2.986506387292243714e-01 3.347622233780889744e-01 8.531885073889062809e-01 +-2.171292379071395828e+01 1.072679453505857339e+01 1.826920523683371211e+00 2.661970591574436273e-01 -3.001603278758976923e-01 3.337948908485642852e-01 8.530086441499495908e-01 +-2.189600021112985573e+01 1.091582039776040247e+01 1.831307815889416490e+00 2.661770342769272935e-01 -3.005621832023218087e-01 3.342485374222869399e-01 8.526957074314620577e-01 +-2.206506251410940322e+01 1.109854080964264256e+01 1.836749905245590231e+00 2.663409260383603483e-01 -2.999053713265300014e-01 3.355388451102992997e-01 8.523689739125704934e-01 +-2.221763032385653958e+01 1.127820034525780635e+01 1.843343858713348604e+00 2.667725878069750478e-01 -2.981830404836873227e-01 3.379075340574845820e-01 8.519023768153046738e-01 +-2.234894315407058230e+01 1.147270415594502246e+01 1.843866628129394725e+00 2.676971524061693697e-01 -2.950622061617062530e-01 3.413938183935630866e-01 8.513088127639103497e-01 +-2.247386418036266420e+01 1.168154878226672722e+01 1.838370263703727359e+00 2.688546026644202946e-01 -2.906278576088964782e-01 3.454956517088636492e-01 8.508144985039610697e-01 +-2.259389337586892665e+01 1.190418644415488103e+01 1.838890700189365734e+00 2.593184761901075053e-01 -2.888925775979807042e-01 3.457696129264617446e-01 8.542471993748459447e-01 +-2.267702201622588731e+01 1.216089715596706355e+01 1.843454210563671092e+00 2.478898442015371739e-01 -2.860717404439759859e-01 3.474433750659513542e-01 8.579024277992634007e-01 +-2.274279138435072767e+01 1.244641240095573664e+01 1.844891758709419571e+00 2.350113954258568061e-01 -2.820010737368858766e-01 3.503205816576961951e-01 8.616962368834414354e-01 +-2.278776095047748029e+01 1.274748733955873803e+01 1.835676297077167174e+00 2.202462408517593673e-01 -2.770604558117971128e-01 3.543508626105592030e-01 8.655428624579093455e-01 +-2.279386004297854740e+01 1.306813583639917020e+01 1.834061530233466852e+00 2.036987851021139495e-01 -2.712513536126683333e-01 3.588190722062826188e-01 8.695851084366361672e-01 +-2.278229110269767332e+01 1.337783685125774547e+01 1.836618388344035457e+00 1.856512666883281815e-01 -2.643068830537648739e-01 3.638748649299665128e-01 8.736535110686377559e-01 +-2.277482624181896043e+01 1.367788348151518818e+01 1.843272471041611071e+00 1.662779501905558566e-01 -2.563450872855653762e-01 3.691014452839521676e-01 8.777259605980322066e-01 +-2.277517771992877016e+01 1.396731596792628061e+01 1.848943435838783289e+00 1.459242359544663803e-01 -2.476261045319048115e-01 3.742100104701540642e-01 8.816769275250099236e-01 +-2.277891014895916655e+01 1.424863148173696814e+01 1.855507995309751523e+00 1.248368063514628812e-01 -2.381565662526234917e-01 3.797117746949031369e-01 8.851644458579459585e-01 +-2.278123831349811113e+01 1.452426181633606639e+01 1.868045646144445682e+00 1.032021173666537867e-01 -2.278694164594527172e-01 3.852498782419169210e-01 8.882608259442732468e-01 +-2.279374700624046923e+01 1.481405841726335737e+01 1.886702130759408291e+00 8.099637708244554479e-02 -2.170287580511503500e-01 3.911035793876907474e-01 8.907165682039777099e-01 +-2.281929122668881504e+01 1.511389860255536099e+01 1.909525084692540009e+00 5.810858941600706429e-02 -2.058242624457075065e-01 3.971769791025749341e-01 8.924741634270476620e-01 +-2.286619277585237953e+01 1.543078205055002883e+01 1.936867770270033873e+00 3.522591846294927803e-02 -1.941157524976541426e-01 4.032522840365893591e-01 8.935690979229948816e-01 +-2.292728992030420443e+01 1.575137801941480475e+01 1.967793013318889006e+00 1.274691221836536832e-02 -1.820988605748549427e-01 4.089524268852030020e-01 8.941114926427708998e-01 +-2.299970283838371543e+01 1.607013826214909002e+01 2.003532377978304080e+00 -9.192614801675663347e-03 -1.696025980915364106e-01 4.142256496517094932e-01 8.941853775339785315e-01 +-2.308401849355340474e+01 1.639451031089354416e+01 2.044617845076738050e+00 -3.079224063408317683e-02 -1.570274799098854701e-01 4.190687514791211488e-01 8.937424258576105451e-01 +-2.317791519790469579e+01 1.671692564319279484e+01 2.086556150440285418e+00 -5.170548063332913724e-02 -1.445299529190750831e-01 4.234558570874848993e-01 8.928172885769531941e-01 +-2.328381015351661532e+01 1.704096193805269266e+01 2.128948609238156653e+00 -7.189672916997863483e-02 -1.323312869182792229e-01 4.270045605427215119e-01 8.916200578594382087e-01 +-2.340427795004438138e+01 1.735701626761366967e+01 2.171373466696040477e+00 -9.112431622345168458e-02 -1.205138629086791729e-01 4.296235839130483902e-01 8.902787695180095495e-01 +-2.353721495216070636e+01 1.764163672899979218e+01 2.210276193991378424e+00 -1.088210540981210811e-01 -1.092261746711385290e-01 4.313071902192137652e-01 8.889328804280178797e-01 +-2.368482889535566827e+01 1.788736550815216830e+01 2.241025979305187654e+00 -1.249783686403358601e-01 -9.859504380821511316e-02 4.321472169235637262e-01 8.876418983541274343e-01 +-2.384607928896862816e+01 1.811242521096227520e+01 2.266084136725431186e+00 -1.394825025042187583e-01 -8.852640207265864702e-02 4.321040839500001618e-01 8.865628536497245360e-01 +-2.401887021275577538e+01 1.831890565421714356e+01 2.279919748837222038e+00 -1.522484236699693239e-01 -7.954755114421421802e-02 4.316803821504608396e-01 8.855193733080354290e-01 +-2.417563814101417563e+01 1.849465333577828829e+01 2.280101357735958345e+00 -1.568609837457968781e-01 -6.905650246495133315e-02 4.320591088014251735e-01 8.854098853287528659e-01 +-2.435465239258103409e+01 1.866788034911684591e+01 2.278833551147209313e+00 -1.607272140386094283e-01 -6.017316194805825968e-02 4.319610751780899593e-01 8.854126046456390897e-01 +-2.456409566518592769e+01 1.884827946901418727e+01 2.269796614147971958e+00 -1.636609697667866792e-01 -5.291919348364309411e-02 4.311929497177032777e-01 8.857128064040995508e-01 +-2.479778785919083361e+01 1.903629896227497653e+01 2.257981623479938804e+00 -1.659125060591743195e-01 -4.713767011932128853e-02 4.300026166831247831e-01 8.861990328509232739e-01 +-2.505276016903864189e+01 1.922914089322856057e+01 2.243173278804790449e+00 -1.677053219712714149e-01 -4.237869624486044484e-02 4.284738455514192079e-01 8.868421699997788288e-01 +-2.531606684592797407e+01 1.942574769930528333e+01 2.229085231275929058e+00 -1.691240220535058791e-01 -3.869162175143402160e-02 4.265967679199939577e-01 8.876458319017992427e-01 +-2.557257251407279952e+01 1.962250513150229736e+01 2.216540469105335198e+00 -1.700231185885573981e-01 -3.605937356402070387e-02 4.245757510827790626e-01 8.885534334973053117e-01 +-2.580221087760002874e+01 1.982022611720514860e+01 2.213541204118973926e+00 -1.706118174258889064e-01 -3.421548493935728380e-02 4.221743612690299075e-01 8.896570216912565998e-01 +-2.601146817578661441e+01 2.002178072754179183e+01 2.220440591652892426e+00 -1.708795840907891550e-01 -3.305780614654894867e-02 4.195332938165493575e-01 8.908979080478455215e-01 +-2.620146402382770745e+01 2.022263752058559660e+01 2.232834173233681163e+00 -1.707515192904049961e-01 -3.259258493898324616e-02 4.166296946298410631e-01 8.923011074035356316e-01 +-2.637627819712720978e+01 2.042627191949194554e+01 2.246709810052124556e+00 -1.704933168163576263e-01 -3.283554693023437582e-02 4.135249830121538461e-01 8.937845782005444661e-01 +-2.654141434367915409e+01 2.064312858172237952e+01 2.261016826810119174e+00 -1.699567631640833132e-01 -3.375044009679307316e-02 4.102752691268951035e-01 8.953489432173035167e-01 +-2.669147582367332916e+01 2.090214578367661247e+01 2.266700491683564245e+00 -1.690759921526795440e-01 -3.505602877705428499e-02 4.072087389723742512e-01 8.968641789317577384e-01 +-2.680711447038204653e+01 2.118769864213084730e+01 2.259189892130341271e+00 -1.681949656527562675e-01 -3.650877260619080772e-02 4.037426557047869569e-01 8.985373429708651827e-01 +-2.691264022015269930e+01 2.147122141299361786e+01 2.251254662706501097e+00 -1.673685360070890360e-01 -3.799697171692978381e-02 4.002503107457208720e-01 9.001908829296069170e-01 +-2.701700745394519387e+01 2.175605453038072312e+01 2.244111561578600700e+00 -1.666208604647388680e-01 -3.938839449346565741e-02 3.967915708431682953e-01 9.017995479560309002e-01 +-2.711597343636304203e+01 2.203754618878080151e+01 2.239399721771621277e+00 -1.660184516917547204e-01 -4.057493926753620583e-02 3.935196243600725396e-01 9.032905269722538710e-01 +-2.721313862380371518e+01 2.231502709860468059e+01 2.233579569352742045e+00 -1.655366737945723477e-01 -4.146849096221055797e-02 3.903769855378326770e-01 9.047008969436354242e-01 +-2.730451173334633808e+01 2.258723126943073822e+01 2.232524467267274826e+00 -1.652420270226250820e-01 -4.183748958383041311e-02 3.873398158884339693e-01 9.060422117107009843e-01 +-2.739618781129729186e+01 2.285659210566472765e+01 2.229679291440306965e+00 -1.651158750932687769e-01 -4.190338686780778477e-02 3.845494507040361776e-01 9.072499716299705641e-01 +-2.747385408025323983e+01 2.309855032345035397e+01 2.227974427794786827e+00 -1.632434010926707146e-01 -4.056829921507414810e-02 3.822183543045849508e-01 9.086335181036162556e-01 +-2.750097978566391532e+01 2.334479347695600993e+01 2.221391878575035950e+00 -1.621176179697699782e-01 -3.882819126368952656e-02 3.796792465634049041e-01 9.099746408228959194e-01 +-2.726825350965150818e+01 2.325151116060946777e+01 2.175983573215688693e+00 -1.613709937062294542e-01 -3.628260994147344126e-02 3.772982732247785465e-01 9.112019044525625500e-01 +-2.702456224413602115e+01 2.309912761978292295e+01 2.139766417121252040e+00 -1.613481927529301363e-01 -3.349904736413328310e-02 3.751107976647562459e-01 9.122151078617489750e-01 +-2.679101439840390597e+01 2.293399738099144969e+01 2.103119306761279450e+00 -1.616097877716584919e-01 -3.051899457695839493e-02 3.729867941334186754e-01 9.131438330849267482e-01 +-2.657740017191866500e+01 2.277437930122923149e+01 2.078001530922096940e+00 -1.620419907806670556e-01 -2.735605387094369040e-02 3.708395914350989253e-01 9.140415652853018935e-01 +-2.637159897173790313e+01 2.262100277940090010e+01 2.066049215829654173e+00 -1.627234156896967820e-01 -2.407343051419220947e-02 3.688004373214123222e-01 9.148375486076620877e-01 +-2.615837650587571872e+01 2.247488982876452113e+01 2.071833704459263625e+00 -1.635572428108897081e-01 -2.066514976553302310e-02 3.666721118914089139e-01 9.156273725873216307e-01 +-2.594072159916872522e+01 2.231161067952020360e+01 2.083107860750283979e+00 -1.646165804832455115e-01 -1.722983316112723304e-02 3.645091161472031605e-01 9.163719516309467572e-01 +-2.574886541918168348e+01 2.215301706047239350e+01 2.091090146796715121e+00 -1.658629634766780880e-01 -1.383545216156034825e-02 3.623977673111308251e-01 9.170419007802971256e-01 +-2.556440423704056997e+01 2.198430157723035450e+01 2.098127451992665815e+00 -1.672358011107535902e-01 -1.058012178033332536e-02 3.600494200502910580e-01 9.177606457015089481e-01 +-2.538037160207138498e+01 2.181392663014435840e+01 2.108677686882134417e+00 -1.686931897332309416e-01 -7.448179926461856101e-03 3.575327469053996565e-01 9.185082539839041216e-01 +-2.520276902143701037e+01 2.165310427306733487e+01 2.120402607732097877e+00 -1.703342537738301854e-01 -4.561949277056037005e-03 3.549010508834821720e-01 9.192445919532085119e-01 +-2.502419845774825191e+01 2.148206206072395119e+01 2.130397958085426868e+00 -1.720280497022145250e-01 -2.082080681697975888e-03 3.520872298862169902e-01 9.200198588567216618e-01 +-2.486219346498838689e+01 2.132068850602420795e+01 2.134670903847158741e+00 -1.734560119174085036e-01 -8.512613343039085239e-05 3.491701646239731005e-01 9.208654370189738314e-01 +-2.471280762926851438e+01 2.118007644514408483e+01 2.144139937175970179e+00 -1.750086373768262038e-01 1.603936758375859323e-03 3.463092364640772969e-01 9.216503036123622206e-01 +-2.456835475227538268e+01 2.103812656267921000e+01 2.152434445001956576e+00 -1.763108370000965319e-01 2.732061531323511702e-03 3.431077662199614187e-01 9.225963561061628626e-01 +-2.442264628234016399e+01 2.089420069466747876e+01 2.161781400049501922e+00 -1.774873368601994905e-01 3.238134741228041770e-03 3.396101015079875940e-01 9.236626433839272288e-01 +-2.427355990026089927e+01 2.073994110416465730e+01 2.170807444422401478e+00 -1.783772892155512380e-01 3.164213493379939256e-03 3.356419573651723276e-01 9.249410412238524559e-01 +-2.411143338788069457e+01 2.058005725822879839e+01 2.181711413896941121e+00 -1.789011116774514576e-01 2.533429513252270782e-03 3.312247041750007170e-01 9.264329941860981465e-01 +-2.395358374681939395e+01 2.043156042038951981e+01 2.193466375655354295e+00 -1.781820297642631445e-01 1.518440338007657478e-03 3.265133176735959819e-01 9.282444887438395797e-01 +-2.378137291698228850e+01 2.027731198521926004e+01 2.202544851885130051e+00 -1.772231022939589340e-01 -1.142698712680511951e-04 3.213388908752234374e-01 9.302328688441559024e-01 +-2.360820039485843225e+01 2.012826763343965908e+01 2.210462999475496293e+00 -1.760922286042515550e-01 -2.334194068303546785e-03 3.158412220681679483e-01 9.323252258603759168e-01 +-2.343254729893018506e+01 1.998287346412564602e+01 2.220826320731257297e+00 -1.747725618769842004e-01 -5.082887453721562400e-03 3.100518298367477832e-01 9.345033420507886657e-01 +-2.326255796617168414e+01 1.983837668300360235e+01 2.229804523609773437e+00 -1.733364359478628547e-01 -8.348776079163816588e-03 3.038379501885040690e-01 9.367855656332416681e-01 +-2.310235838765634142e+01 1.970584173074448131e+01 2.241947866511607490e+00 -1.717849912618561181e-01 -1.199786572547334104e-02 2.973837773282887453e-01 9.390999819259777670e-01 +-2.295028196114595787e+01 1.958286525374220943e+01 2.255424051517243456e+00 -1.701818409947707111e-01 -1.595036499586073228e-02 2.905897082064004544e-01 9.414569948030672153e-01 +-2.280736594859218513e+01 1.946862924924761273e+01 2.267797479466579169e+00 -1.685447598422293580e-01 -2.013834440397856140e-02 2.835267542321208145e-01 9.438218124474053727e-01 +-2.267118424034019597e+01 1.935690750043622543e+01 2.280219219544293185e+00 -1.669499012363294399e-01 -2.445635087061915486e-02 2.760323207101295639e-01 9.462217993880225331e-01 +-2.254359611888131099e+01 1.924570146442235341e+01 2.290289369338574854e+00 -1.653825843482539248e-01 -2.890006054022439819e-02 2.681149157090276236e-01 9.486451883395159435e-01 +-2.242508383706413611e+01 1.913420649682531760e+01 2.298669420917671236e+00 -1.638814594322881013e-01 -3.334227193822694724e-02 2.600662318870630707e-01 9.509977030939973375e-01 +-2.231183483397288114e+01 1.902501793763106264e+01 2.308454712118715335e+00 -1.625786648799470435e-01 -3.758926290786378938e-02 2.517783702289140835e-01 9.532905131090511075e-01 +-2.220400006045826657e+01 1.891547836354818202e+01 2.318149300855755879e+00 -1.613833449136288234e-01 -4.173159024063542027e-02 2.433500179162118027e-01 9.555075035627831337e-01 +-2.209845338351153643e+01 1.880975098162064896e+01 2.329158518475625161e+00 -1.603213535040028948e-01 -4.556253125266216536e-02 2.346356194645030369e-01 9.576884541883025070e-01 +-2.199799084197544730e+01 1.870655874788373296e+01 2.340223438454463789e+00 -1.594738115004466772e-01 -4.897948336942856834e-02 2.258455659957382677e-01 9.597722787657028132e-01 +-2.190095719256446216e+01 1.859784303157948671e+01 2.351705863539985231e+00 -1.587822881713953915e-01 -5.191858353588252317e-02 2.169134396992903335e-01 9.617905909233496198e-01 +-2.180016806990845168e+01 1.847877138637376504e+01 2.364258134753425278e+00 -1.583307346781289426e-01 -5.435581923632944873e-02 2.077876944491077460e-01 9.637432388082685097e-01 +-2.169832459632621635e+01 1.834041881565324061e+01 2.371908520050601155e+00 -1.580906530827755618e-01 -5.627824353758310166e-02 1.985031164445777430e-01 9.656275424787137407e-01 +-2.161548383546879748e+01 1.821752885545812362e+01 2.373340289822982285e+00 -1.580645006030164668e-01 -5.749209138725010215e-02 1.891466165768861118e-01 9.674367010008695367e-01 +-2.153422843287851407e+01 1.810552516173234494e+01 2.377717464229693878e+00 -1.582610487034898650e-01 -5.781615261480226725e-02 1.797060467473474143e-01 9.691833749751642690e-01 +-2.145644821540220448e+01 1.800209728838094847e+01 2.381849807874012903e+00 -1.587154231477732047e-01 -5.729026022789755757e-02 1.700788142442150874e-01 9.708760857212688222e-01 +-2.138004282181617910e+01 1.789385514207005556e+01 2.382619277185873408e+00 -1.592238091682391388e-01 -5.593437977958651275e-02 1.603099744843234087e-01 9.725326580684515720e-01 +-2.131597834516782441e+01 1.779451138764849105e+01 2.380707270552539612e+00 -1.597441991719376064e-01 -5.398242832653989132e-02 1.506953849547642277e-01 9.740936845584099446e-01 +-2.126265806665829672e+01 1.770139245316920551e+01 2.377305864217933884e+00 -1.602471603559134095e-01 -5.139311720526714561e-02 1.412382715028596691e-01 9.755671451721739107e-01 +-2.121685694350008689e+01 1.761415606179631865e+01 2.373554570508440431e+00 -1.607831530752041049e-01 -4.823766780015736194e-02 1.320171000100557046e-01 9.769305603099242008e-01 +-2.117367240235097370e+01 1.752188071591168139e+01 2.367590729108215442e+00 -1.612903379465737419e-01 -4.463757036160696801e-02 1.230275604278528445e-01 9.781907060963731526e-01 +-2.113100143682661169e+01 1.742278791756978151e+01 2.362691670404515332e+00 -1.618331352219359032e-01 -4.061698168306866752e-02 1.142921155128258093e-01 9.793352532705437152e-01 +-2.109492570797476318e+01 1.733146658600596979e+01 2.358713281992010025e+00 -1.623646253406837714e-01 -3.634335667160287081e-02 1.059958855915424519e-01 9.803477332634522590e-01 +-2.106526439786156502e+01 1.724624616177715808e+01 2.355980308482712449e+00 -1.628528046406527985e-01 -3.176630233078926724e-02 9.806486672466814547e-02 9.812507632677880398e-01 +-2.103936426292183626e+01 1.716172325856282654e+01 2.353005008951581267e+00 -1.632545499615026263e-01 -2.699483486846433744e-02 9.055017290930690577e-02 9.820487892613617431e-01 +-2.101316994183832421e+01 1.707674261872273291e+01 2.353074067198606567e+00 -1.636490478128985460e-01 -2.195947066909571810e-02 8.355952919697588743e-02 9.827280953470782787e-01 +-2.098479064496500612e+01 1.699431492942678545e+01 2.358596145165361868e+00 -1.639983383793207072e-01 -1.668269947733160008e-02 7.701321204686938093e-02 9.833082601240621390e-01 +-2.096163967115072779e+01 1.692453467350348362e+01 2.361175419977556977e+00 -1.642102349878315215e-01 -1.137705240406010516e-02 7.111908588094235928e-02 9.837924535274802373e-01 +-2.094336156452694908e+01 1.685937661067343285e+01 2.360740008996073946e+00 -1.644046833924985573e-01 -6.180734840807129878e-03 6.576125912326838407e-02 9.841790107169632318e-01 +-2.091996040243015997e+01 1.679113249666621854e+01 2.358775558375123094e+00 -1.645912914975021790e-01 -1.145647390666358926e-03 6.090789961009554498e-02 9.844788459438268413e-01 +-2.089543578595064233e+01 1.672696514289351555e+01 2.357740460916899483e+00 -1.648569860265175491e-01 3.843779565520111068e-03 5.679655997310179699e-02 9.846733111862938648e-01 +-2.087405016091337373e+01 1.666244969984196800e+01 2.352794701593329929e+00 -1.651557222290719329e-01 8.705447299667892769e-03 5.350871175046966605e-02 9.847764234466773736e-01 +-2.084682301696283702e+01 1.659373989436810604e+01 2.347284577116218962e+00 -1.653984696066861937e-01 1.343221752683440400e-02 5.098368829005908709e-02 9.848165100232305624e-01 +-2.082007325794588581e+01 1.651314920667093133e+01 2.338474942774067866e+00 -1.656639873016375331e-01 1.789091360014482060e-02 4.940161429136621929e-02 9.847816052548349353e-01 +-2.080010771656053237e+01 1.643467478336274468e+01 2.327420048648610518e+00 -1.658959161410687166e-01 2.207375510463954749e-02 4.874050405911737466e-02 9.846906230381583525e-01 +-2.077628596253444471e+01 1.633766415659650306e+01 2.311139872091339420e+00 -1.632495460536843579e-01 2.578267823255039892e-02 4.885143635650564947e-02 9.850372287332536114e-01 +-2.074269164923461872e+01 1.624306984938383636e+01 2.298012188524479971e+00 -1.599678110252953922e-01 2.918402575743999500e-02 4.992603871806279570e-02 9.854267835299000966e-01 +-2.071488868840863873e+01 1.616813284508246085e+01 2.287606128844659636e+00 -1.561182751816872494e-01 3.226338163908769319e-02 5.183087125454018812e-02 9.858497283236083986e-01 +-2.069429637576661563e+01 1.611479893213525827e+01 2.281165493657008714e+00 -1.517945123779943506e-01 3.510028329535292563e-02 5.447281094409707480e-02 9.862854932444228284e-01 +-2.067553701424431623e+01 1.606311297660372617e+01 2.278231674796024286e+00 -1.470623601140047809e-01 3.762818768044523532e-02 5.780810384592470486e-02 9.867192945718008534e-01 +-2.066005838233551373e+01 1.601730414076842379e+01 2.273252518070416617e+00 -1.419792709351021809e-01 3.989278958783632617e-02 6.172065692333886938e-02 9.871377693749885385e-01 +-2.064257134839859731e+01 1.597737853305197220e+01 2.269208534476636174e+00 -1.366602495681482621e-01 4.195775416104875061e-02 6.614564021603631938e-02 9.875162004661860449e-01 +-2.061997488949099022e+01 1.594087837935035168e+01 2.267951612735017886e+00 -1.312409524567876851e-01 4.379814446672567613e-02 7.104242182550495055e-02 9.878311914263957494e-01 +-2.059128170228992616e+01 1.589691802007559573e+01 2.268632761416656596e+00 -1.258040767870452492e-01 4.544670677981129531e-02 7.643959187395041321e-02 9.880611720875707160e-01 +-2.056995440351705540e+01 1.586070097046617988e+01 2.269894712831388439e+00 -1.203359303490808413e-01 4.699870185379919491e-02 8.214074553465268436e-02 9.882121447876437426e-01 +-2.055072368872220423e+01 1.582903563376351919e+01 2.271289033989540407e+00 -1.148204424327542300e-01 4.844133874280111274e-02 8.821176639260819297e-02 9.882754465886016693e-01 +-2.053411520233666110e+01 1.580249573892884030e+01 2.271322097049400579e+00 -1.092922895106014647e-01 4.977367090376329933e-02 9.463243089736995961e-02 9.882420982243942387e-01 +-2.052063436617159908e+01 1.578139047222228086e+01 2.269965081994594236e+00 -1.037949162151052540e-01 5.102594258875241262e-02 1.012866999303133758e-01 9.881112975901364948e-01 +-2.051109816762516047e+01 1.576614547502966701e+01 2.267769777918209773e+00 -9.840104008533895330e-02 5.227638024267977634e-02 1.081710706902907354e-01 9.878681065840148046e-01 +-2.050568321714575859e+01 1.575574744993795129e+01 2.265118931868119301e+00 -9.318094791277606315e-02 5.357389269048426494e-02 1.152212324396054838e-01 9.875075575476254253e-01 +-2.050166382423019229e+01 1.574690267938842325e+01 2.263077717368975339e+00 -8.821430977653496597e-02 5.492012921237273554e-02 1.223792101330696547e-01 9.870285202846668104e-01 +-2.049881720857412049e+01 1.574049373021817644e+01 2.261503709674841378e+00 -8.356314648832394165e-02 5.630909305222969730e-02 1.294914206530896894e-01 9.864473735640079122e-01 +-2.049634004631608164e+01 1.573664397208897192e+01 2.260506344301061787e+00 -7.936371613926523905e-02 5.776690852868199971e-02 1.364776028964898302e-01 9.857678233796330902e-01 +-2.049218710833437740e+01 1.572331693234137262e+01 2.258134984051995975e+00 -7.554488226594657796e-02 5.917387585839132408e-02 1.434541500898740829e-01 9.849935446105722026e-01 +-2.048657437881676557e+01 1.569756930055372379e+01 2.255590004990317254e+00 -7.234952555513138317e-02 6.067932273964941892e-02 1.500437064990849667e-01 9.841597448593090158e-01 +-2.047843582579944410e+01 1.566225449672118231e+01 2.252243725286425136e+00 -6.971624011045358948e-02 6.231747739621338461e-02 1.563830270621933693e-01 9.832601318403235702e-01 +-2.046442239506922434e+01 1.561154057414355201e+01 2.247412752498196831e+00 -6.753753647134667915e-02 6.408830427774044047e-02 1.625061682465696600e-01 9.823049831204545557e-01 +-2.044462728535043183e+01 1.553935775085130544e+01 2.239074167287379513e+00 -6.574968329266300815e-02 6.597160830403327181e-02 1.684161561215151981e-01 9.813056078961603923e-01 +-2.041817639042516319e+01 1.544780975665219280e+01 2.225232816334454355e+00 -6.428081985558835310e-02 6.796958880377335088e-02 1.743106238010578568e-01 9.802366497841802362e-01 +-2.037827970100034491e+01 1.535655819445656256e+01 2.215730549141833094e+00 -6.314394592599967271e-02 7.012749691860384327e-02 1.802301429577914393e-01 9.790873554259137412e-01 +-2.034304301221650135e+01 1.525750656497740110e+01 2.208270842005666257e+00 -6.228750850023884178e-02 7.234470415608308669e-02 1.860913730315238990e-01 9.778836844129077388e-01 +-2.030496317045575339e+01 1.515266078113735482e+01 2.201351717315796819e+00 -6.176481948095294966e-02 7.464613919449145096e-02 1.919754907470901106e-01 9.766055802156206056e-01 +-2.026302311912285603e+01 1.502794260271870108e+01 2.194500827666788556e+00 -6.150353105975184254e-02 7.689509711329897690e-02 1.977486174561704779e-01 9.752947917744485551e-01 +-2.020849726341433339e+01 1.490013804558936172e+01 2.179868191048701220e+00 -6.134829259082300729e-02 7.915527343069228561e-02 2.037013814230680120e-01 9.738976099600501479e-01 +-2.015865252051629852e+01 1.478943384765494073e+01 2.172600629379263903e+00 -6.130733305315389653e-02 8.150632296801041399e-02 2.099363517575650873e-01 9.723810155697343305e-01 +-2.010697506542285140e+01 1.469454277800677389e+01 2.169887108051629099e+00 -6.122343169573608856e-02 8.385772232222171718e-02 2.160867110524038737e-01 9.708378266261108447e-01 +-2.004333324686132300e+01 1.459155794196276901e+01 2.168254593386185203e+00 -6.121813631254290067e-02 8.620945953303266185e-02 2.221014920901688283e-01 9.692735309063055249e-01 +-1.995536522431518733e+01 1.449161916155743590e+01 2.176704636767818002e+00 -6.121831844503336506e-02 8.849909393654395440e-02 2.282178498163161540e-01 9.676449822251577126e-01 +-1.986852694734326619e+01 1.442672928122935261e+01 2.184905732446394300e+00 -6.079935440944351371e-02 9.076774558049814645e-02 2.348681532696405838e-01 9.658682934572044854e-01 +-1.977248391560454621e+01 1.435172719976702815e+01 2.195254625368472823e+00 -5.995056471532162617e-02 9.312418594182914067e-02 2.418719696773432015e-01 9.639666560933002337e-01 +-1.969067993194185107e+01 1.426944732331360122e+01 2.199145282308047289e+00 -5.868241001951993857e-02 9.537467557572931742e-02 2.493537768367389829e-01 9.619161504109252636e-01 +-1.960956707831019941e+01 1.417168327337953571e+01 2.203751693175549420e+00 -5.704751587468308988e-02 9.750129778798000135e-02 2.568054443738436721e-01 9.598385176861311541e-01 +-1.955079876767694813e+01 1.409388215135465394e+01 2.206114221758293858e+00 -5.500135549751854203e-02 9.950490433384594213e-02 2.647950310287480735e-01 9.575787960004964461e-01 +-1.949116912884880648e+01 1.402973278451732142e+01 2.205298159181333872e+00 -5.209322678538553381e-02 1.017655153258788803e-01 2.732479988458092479e-01 9.551259315684987872e-01 +-1.942543732676718093e+01 1.397021949839072974e+01 2.204714454798081924e+00 -4.870392115491865848e-02 1.040523361421392540e-01 2.825111603538412730e-01 9.523594029970722241e-01 +-1.929821494239357804e+01 1.378497043399655553e+01 2.205750938714737153e+00 -4.492083545822482538e-02 1.061211487241495860e-01 2.917518127459385879e-01 9.495268583346441194e-01 +-1.912665396715104649e+01 1.353795928427117978e+01 2.205938936536770090e+00 -4.050387523008284335e-02 1.083404317492605851e-01 3.015274564377538047e-01 9.464158367774282432e-01 +-1.890935921934523023e+01 1.327559809124179502e+01 2.224901666802643785e+00 -3.551371582259577053e-02 1.104073315128968891e-01 3.113157326726145313e-01 9.432027635009208044e-01 +-1.871895692483319706e+01 1.304034078023417109e+01 2.240376825580436826e+00 -3.059565958570060334e-02 1.122690636555179616e-01 3.210416825095556703e-01 9.398892217118648418e-01 +-1.858533960095937232e+01 1.285581032850718053e+01 2.239556104990208851e+00 -2.533638816897254217e-02 1.134705182592263134e-01 3.306192625627465409e-01 9.365753419114675182e-01 +-1.846637934944839188e+01 1.267245711276296838e+01 2.232190393417010199e+00 -1.996472408195707968e-02 1.142426246977342186e-01 3.400037153505683363e-01 9.332456640499179334e-01 +-1.834424743626685128e+01 1.248542095186074086e+01 2.224726272720475517e+00 -1.461782668039461608e-02 1.147569380941151490e-01 3.490302168913915204e-01 9.299435636087323154e-01 +-1.821656758056435876e+01 1.228891383911369317e+01 2.218094745620765806e+00 -9.473427686408660356e-03 1.150921517709838637e-01 3.575202265649736200e-01 9.267379901628109984e-01 +-1.808473947371998847e+01 1.208766941031786146e+01 2.211148295661107710e+00 -4.591869651937877973e-03 1.152099924134651621e-01 3.652709483137638879e-01 9.237330117737343471e-01 +-1.796212633515017743e+01 1.190028077422488195e+01 2.202906659710205606e+00 -2.268098271442152251e-04 1.150432754928166768e-01 3.721879461725837723e-01 9.210000560270295011e-01 +-1.785453028213330029e+01 1.173500074493014900e+01 2.196422447926726473e+00 3.584831690984122479e-03 1.146186967401746082e-01 3.781439587308655925e-01 9.186167999001022544e-01 +-1.776411908157643182e+01 1.159193336663456186e+01 2.188055005070835168e+00 6.860951809147601901e-03 1.138170436653504064e-01 3.829512423719652614e-01 9.167043907533920510e-01 +-1.769734221398674023e+01 1.147952232355739000e+01 2.179243348434104721e+00 9.447360004739294159e-03 1.127334212492174664e-01 3.865639640853909542e-01 9.152978760535983582e-01 +-1.763255751500428303e+01 1.137085906132285018e+01 2.171910293257880653e+00 1.110555655371989886e-02 1.114242542141882925e-01 3.885893432651385537e-01 9.145816551065322209e-01 +-1.757316524267253399e+01 1.127964602695488061e+01 2.166473754292252529e+00 1.185933542491708452e-02 1.098771284046711066e-01 3.892181435789570099e-01 9.144919826590290901e-01 +-1.752693756265603753e+01 1.120474242156642752e+01 2.162020643769047012e+00 1.173225842753999187e-02 1.079556522185817213e-01 3.881986992109021650e-01 9.151555493068490588e-01 +-1.749635054128563993e+01 1.114842258175177214e+01 2.159801109387699203e+00 1.068457498525992276e-02 1.054529732056452701e-01 3.853574005046796480e-01 9.166597900985391512e-01 +-1.746987484039617655e+01 1.109833512739065675e+01 2.160562514213641094e+00 8.361420198932255701e-03 1.023366124301905711e-01 3.807866783946503575e-01 9.189443942600107329e-01 +-1.743961018697540410e+01 1.103295869616226099e+01 2.160514159081406760e+00 4.759838570044848741e-03 9.862923242753426911e-02 3.740671675138654284e-01 9.221297941097912343e-01 +-1.738209358789312020e+01 1.092662162694817951e+01 2.159551026333672574e+00 -4.267478026647154540e-04 9.451641194703352955e-02 3.648909327282914838e-01 9.262402779090995741e-01 +-1.728429936725947869e+01 1.078156544320308186e+01 2.161188781995482699e+00 -7.344681234861672250e-03 8.979843880021999569e-02 3.532146170640036997e-01 9.311937065706878958e-01 +-1.717129514951847469e+01 1.060954244656145207e+01 2.161881636377004146e+00 -1.558728871856538897e-02 8.459577425049155663e-02 3.393465364544549501e-01 9.367200835681316340e-01 +-1.706168993742090123e+01 1.044539723171767776e+01 2.164013818496068442e+00 -2.499361266717898752e-02 7.909483822218456306e-02 3.234376213958564672e-01 9.426067187801692171e-01 +-1.696109414029760387e+01 1.029391974573971957e+01 2.167050192972648226e+00 -3.532126478746205889e-02 7.333142691594213280e-02 3.056241350394299783e-01 9.486668460192403396e-01 +-1.687467613593777571e+01 1.016347404306224256e+01 2.168212206345208504e+00 -4.622486579764858300e-02 6.725972925270648495e-02 2.862841285846667305e-01 9.546626484609582741e-01 +-1.679382067074978124e+01 1.004178731367571586e+01 2.169404071549860369e+00 -5.744366751608519228e-02 6.090054550451711596e-02 2.656675949095181899e-01 9.604228510589920553e-01 +-1.671502872125901007e+01 9.928769784441687563e+00 2.172637553329854754e+00 -6.892427977923976101e-02 5.424888258536680885e-02 2.438624215285866981e-01 9.658351854806833670e-01 +-1.663799007586359480e+01 9.817469086452909721e+00 2.178387655751162555e+00 -8.060115121284738837e-02 4.751327452176265509e-02 2.213335174097662561e-01 9.706994426515963559e-01 +-1.656408488197978457e+01 9.712851673770579453e+00 2.188949668821842831e+00 -9.216847508597671157e-02 4.077806440951327327e-02 1.983061332690445600e-01 9.749445003683047117e-01 +-1.649973487856637533e+01 9.614714016748605374e+00 2.200081186862143046e+00 -1.034956853282595624e-01 3.406593713696950271e-02 1.751033563911676694e-01 9.785024007734179907e-01 +-1.644145189377235994e+01 9.518645326628329073e+00 2.211673619938637980e+00 -1.143697992967085963e-01 2.747856742179980924e-02 1.520167501308666569e-01 9.813538443386329302e-01 +-1.639295111415408002e+01 9.438464491340159412e+00 2.223216243399236181e+00 -1.246647215866305419e-01 2.102622803237862506e-02 1.291460620602334630e-01 9.835333673742464589e-01 +-1.635229191864688758e+01 9.368127702486257036e+00 2.233562520519563499e+00 -1.342134310043322509e-01 1.479586287658969657e-02 1.068738640728450623e-01 9.850613124757330308e-01 +-1.631830051074468457e+01 9.307242259240959825e+00 2.244426700517038853e+00 -1.428014414319911107e-01 8.879592283973461453e-03 8.562554733092427039e-02 9.860005750991928108e-01 +-1.628619582107893038e+01 9.255500505683029289e+00 2.258414306512610548e+00 -1.503244219381807412e-01 3.270482471886472942e-03 6.561739121335170843e-02 9.864513117733360037e-01 +-1.625537509089395627e+01 9.209283319931946821e+00 2.273578104608310557e+00 -1.566462438607570395e-01 -2.030606906476295839e-03 4.723166892274411471e-02 9.865226583743368360e-01 +-1.622515917466837010e+01 9.168472316023480673e+00 2.287756380059410954e+00 -1.615980304750979923e-01 -6.849638316913116316e-03 3.080643644438940676e-02 9.863519073006619120e-01 +-1.619263194700837261e+01 9.132351626603893990e+00 2.302137466604272209e+00 -1.648971126317285152e-01 -1.098738770568819141e-02 1.663825802873680412e-02 9.861091961530722427e-01 +-1.615948541636274527e+01 9.105472748325324162e+00 2.317080591805684708e+00 -1.655842833399760461e-01 -1.447054216107828729e-02 5.040399209603840455e-03 9.860765656444495653e-01 +-1.613543561889148137e+01 9.089246719148793119e+00 2.330073713023355531e+00 -1.656461391315860177e-01 -1.718069026848557598e-02 -3.816953218732600274e-03 9.860281758057878321e-01 +-1.611969485803400559e+01 9.080030284385308903e+00 2.333121595778725244e+00 -1.630190628763794614e-01 -1.919318291760680265e-02 -9.716719758919092897e-03 9.863883371728771055e-01 +-1.611101792298105551e+01 9.077893633231999715e+00 2.332891359582450086e+00 -1.585215352822811896e-01 -2.029516156287563405e-02 -1.268769550646510827e-02 9.870653532020081666e-01 +-1.610786570749139557e+01 9.074754689125031248e+00 2.332373661696823586e+00 -1.522359735163119898e-01 -2.072530759265489228e-02 -1.317284282213836144e-02 9.880390140301673618e-01 +-1.610707111008888148e+01 9.074273188830556336e+00 2.330908070778615393e+00 -1.444230926660645953e-01 -2.059467730056086660e-02 -1.135002870264241633e-02 9.892365560008224978e-01 +-1.610051076023561123e+01 9.067454666629032545e+00 2.329856523599523221e+00 -1.354194888253757445e-01 -2.003183825100954274e-02 -7.444247601461353135e-03 9.905578304610710427e-01 +-1.608561065131056012e+01 9.055431567141054572e+00 2.333570903625997950e+00 -1.253950029047078696e-01 -1.897163984724062682e-02 -1.641236612165737933e-03 9.919241008659176462e-01 +-1.604942488873723505e+01 9.047208141752495436e+00 2.347260763556520580e+00 -1.144697698682805159e-01 -1.762930797492083534e-02 5.740325714956262711e-03 9.932536784984982159e-01 +-1.599780400830240801e+01 9.036078121086683623e+00 2.365797423118996434e+00 -1.028793770958119497e-01 -1.601182389409760293e-02 1.438189170857957951e-02 9.944609331068434699e-01 +-1.597493526484967674e+01 9.054104035289602948e+00 2.375230004990104948e+00 -9.116612313425521974e-02 -1.402592871805455159e-02 2.404947248203979926e-02 9.954464178891656578e-01 +-1.596623212574137796e+01 9.088837732746416265e+00 2.379756223421016781e+00 -7.920706450329700887e-02 -1.186981575955644609e-02 3.411035148029154668e-02 9.962036791399401237e-01 +-1.596954706205692354e+01 9.145630681692750841e+00 2.378335418541498658e+00 -6.713151095836895899e-02 -9.939073942417494395e-03 4.453442322185163782e-02 9.967001579566676650e-01 +-1.597713426819272442e+01 9.209867560630165428e+00 2.375847369721776126e+00 -5.513994028047861096e-02 -8.117924896497836357e-03 5.531919823089394977e-02 9.969119332950577839e-01 +-1.599726395083548702e+01 9.286978546016371183e+00 2.368917688079634765e+00 -4.346590881166189496e-02 -6.423142916541952317e-03 6.621660902030318541e-02 9.968373749311695287e-01 +-1.602325280615994174e+01 9.384730327165568653e+00 2.360474174448691898e+00 -3.231471166577935122e-02 -4.952948608179501104e-03 7.695102274079493321e-02 9.964987172343905408e-01 +-1.606731305965451639e+01 9.504301408337655133e+00 2.347623184502842797e+00 -2.189820861151870954e-02 -3.729460773636685943e-03 8.743663417366816237e-02 9.959223462074408006e-01 +-1.612083081086907654e+01 9.644930870353693564e+00 2.335521445274497676e+00 -1.240500041987740651e-02 -2.751275237990671516e-03 9.731352131216068624e-02 9.951726225457058206e-01 +-1.618099947206566469e+01 9.795013133979924902e+00 2.324490477150014112e+00 -4.103948224691608693e-03 -2.038100836592279547e-03 1.062099577466320416e-01 9.943331278112087501e-01 +-1.624217904165843152e+01 9.942615724029280955e+00 2.313414108981703077e+00 2.671543113858131438e-03 -1.817275572975684834e-03 1.139050986658751985e-01 9.934863396660439383e-01 +-1.629124780354753099e+01 1.006938740591245995e+01 2.303920311212641181e+00 7.578488459806609866e-03 -2.268273374107130595e-03 1.198967946776430676e-01 9.927548071932547069e-01 +-1.633472385079273792e+01 1.017595524124036643e+01 2.290903076987572895e+00 1.049449308106667478e-02 -3.410735886430148710e-03 1.241520308463849587e-01 9.922018096698036471e-01 +-1.637793268302061378e+01 1.028165325764400073e+01 2.274641803603773660e+00 1.135478531300459365e-02 -5.504453293259703277e-03 1.267870953564638192e-01 9.918496433009207358e-01 +-1.642822846916649837e+01 1.040742890945908350e+01 2.257948914225482273e+00 1.029881112775398767e-02 -8.313216204557929631e-03 1.277369548604467553e-01 9.917197144658432828e-01 +-1.647931254011575319e+01 1.052246117433054451e+01 2.243167421829907582e+00 7.634594890201421881e-03 -1.166218571425032755e-02 1.268715450056190353e-01 9.918211601256338161e-01 +-1.653516030257644331e+01 1.065070388833428439e+01 2.229596635922036718e+00 3.412057472295177384e-03 -1.565310569281696748e-02 1.246696696394519049e-01 9.920689093088246313e-01 +-1.659536502724029816e+01 1.079629368550196133e+01 2.219560690459061458e+00 -2.277955605083687059e-03 -2.008936474288094270e-02 1.213646936867543435e-01 9.924020086246534422e-01 +-1.666574160083146339e+01 1.095804922228458267e+01 2.206575003680418590e+00 -9.232634428867562970e-03 -2.485068396863391454e-02 1.169590881075668609e-01 9.927827994400153511e-01 +-1.674190989691862796e+01 1.113371931954566918e+01 2.190580694345738877e+00 -1.729123396301393556e-02 -2.983821393142610523e-02 1.116249497908161081e-01 9.931517888250256387e-01 +-1.682084807372992330e+01 1.131155062160362057e+01 2.171354591314961446e+00 -2.627781006345874734e-02 -3.505250642584061688e-02 1.055596444750812601e-01 9.934474642225414875e-01 +-1.690339518644142913e+01 1.149827905820425400e+01 2.151008411228464645e+00 -3.600895897540373758e-02 -4.038228984364392038e-02 9.883217843337271935e-02 9.936320924692395584e-01 +-1.699017092537654250e+01 1.169579789143146975e+01 2.131659798115800530e+00 -4.632514640753965934e-02 -4.565426019546325875e-02 9.170207545078250255e-02 9.936600517883820149e-01 +-1.709386783254561593e+01 1.190758659631958771e+01 2.114919487083909200e+00 -5.697037751959511953e-02 -5.086295538998143045e-02 8.444393908915696911e-02 9.934970847992861120e-01 +-1.721252576975277293e+01 1.212821192215514188e+01 2.102066421114354267e+00 -6.762684478981473291e-02 -5.597921324432133389e-02 7.717879162941922166e-02 9.931446415325295707e-01 +-1.734414723779302037e+01 1.234817916102151791e+01 2.094966851470915437e+00 -7.811016813160526207e-02 -6.091964018158538274e-02 7.004974020309484573e-02 9.926129889366381853e-01 +-1.749466391275494104e+01 1.255966252000725802e+01 2.090670235722457804e+00 -8.825476276087608485e-02 -6.557760250153599202e-02 6.300433027933761976e-02 9.919380279893152963e-01 +-1.766160084761688864e+01 1.275175773625625197e+01 2.088632206476979558e+00 -9.801771896044846055e-02 -6.981677485633164260e-02 5.643833537049062349e-02 9.911270216109892006e-01 +-1.784674088814451665e+01 1.293479071192559005e+01 2.084145789414349359e+00 -1.072340540274417386e-01 -7.358196782590170626e-02 5.072332308422956154e-02 9.902088707269739443e-01 +-1.804303659319181818e+01 1.312350271965192761e+01 2.086779122422094623e+00 -1.156308791144170789e-01 -7.684132591609062202e-02 4.584309259977438489e-02 9.892538760014278898e-01 +-1.823680545551879106e+01 1.330054306159428457e+01 2.100665654473128807e+00 -1.231424855552845504e-01 -7.936709817534590150e-02 4.193402412085699832e-02 9.883209154678385122e-01 +-1.841567601464123882e+01 1.346193909844716075e+01 2.134129752566813476e+00 -1.293208643605408825e-01 -8.103128912829450636e-02 3.909683664104095929e-02 9.875127227309660194e-01 +-1.858253985886641146e+01 1.360433933777828486e+01 2.168064371091896980e+00 -1.341300029799911697e-01 -8.204923167606985313e-02 3.767319669960150774e-02 9.868422817252924251e-01 +-1.872528555110619308e+01 1.371417458432784997e+01 2.190000764840207115e+00 -1.374762638688906968e-01 -8.210701065406829369e-02 3.764342635540047360e-02 9.863780127125750807e-01 +-1.886174992968339836e+01 1.381813799764337958e+01 2.202999472521771196e+00 -1.395160263736313910e-01 -8.129732852998228232e-02 3.901140679525193222e-02 9.861054839331668820e-01 +-1.900846804434779713e+01 1.392831097412183361e+01 2.206856974323029519e+00 -1.403293273126852980e-01 -7.988191194438465370e-02 4.150051939448869132e-02 9.860041399728640688e-01 +-1.916571367673935811e+01 1.403579048606478530e+01 2.207071381292480261e+00 -1.400379638015649963e-01 -7.790403469512195700e-02 4.501333120722775250e-02 9.860497042400393486e-01 +-1.932336268452755590e+01 1.413904396895380522e+01 2.204120642705144295e+00 -1.388513136416683336e-01 -7.536944635375898704e-02 4.938366621938568984e-02 9.862053041473500814e-01 +-1.948019051283263892e+01 1.423741841155265675e+01 2.200146855982614724e+00 -1.367630726654870954e-01 -7.234988442363499139e-02 5.469348488684781101e-02 9.864430411568382295e-01 +-1.964875955572989952e+01 1.433830687080092581e+01 2.194627629322277063e+00 -1.337558056365891479e-01 -6.896716357587492907e-02 6.103991920834043322e-02 9.867253612628513748e-01 +-1.982736775656775308e+01 1.443923626581344166e+01 2.187412016870568632e+00 -1.299336473950004622e-01 -6.540464313115372519e-02 6.827843064796437766e-02 9.870042669290723936e-01 +-2.003310344387709208e+01 1.455450267049625701e+01 2.188406739971098691e+00 -1.251762827996395766e-01 -6.150402563108019194e-02 7.655005314683840933e-02 9.872629464605172656e-01 +-2.020370104676618084e+01 1.463269892318620791e+01 2.183445481404470812e+00 -1.201726246628413569e-01 -5.755515563868281170e-02 8.478117842600900456e-02 9.874502375473758198e-01 +-2.039944575523385950e+01 1.473814869357466328e+01 2.171863244999892029e+00 -1.150452482359691914e-01 -5.377802125628649427e-02 9.345944491593065340e-02 9.874906169596617822e-01 +-2.058323154692209656e+01 1.482187808651007543e+01 2.162320377892114731e+00 -1.095851340567848969e-01 -5.021388268546568556e-02 1.027892628893974369e-01 9.873722237646116451e-01 +-2.077850243723293033e+01 1.491262548729414306e+01 2.155145278297261324e+00 -1.039155139600953515e-01 -4.681374706100800004e-02 1.126103102700283937e-01 9.870809676505636343e-01 +-2.097268377603544209e+01 1.499967083972508064e+01 2.144085471811068899e+00 -9.854660583477990732e-02 -4.354060165108766811e-02 1.221308656917521052e-01 9.866492309360290758e-01 +-2.117992613839238203e+01 1.510366820591486459e+01 2.131473250414687381e+00 -9.318340102928472646e-02 -4.053285809127053774e-02 1.316266821970481227e-01 9.860771868811744056e-01 +-2.134511741496542925e+01 1.527708983157364031e+01 2.103044743210867207e+00 -8.748968684153357600e-02 -3.735379189054816723e-02 1.413872393545844153e-01 9.853728963266293883e-01 +-2.111324512817924770e+01 1.530666291996512385e+01 2.083534390417496773e+00 -8.253825544210410814e-02 -3.501602564173068866e-02 1.505422105512969067e-01 9.845294345390187551e-01 +-2.087389369854814447e+01 1.529357879033045009e+01 2.075755340018088368e+00 -7.785113952916211666e-02 -3.342901890145941191e-02 1.591765119103717985e-01 9.836078446930101027e-01 +-2.064248619497521631e+01 1.526955410168450200e+01 2.074871614817053622e+00 -7.357602023898533738e-02 -3.232203097506882589e-02 1.671843552861336235e-01 9.826449531754252176e-01 +-2.043162307627387975e+01 1.524231419457743542e+01 2.074558946751290822e+00 -7.006468207152179162e-02 -3.194303482292529944e-02 1.745368820176589897e-01 9.816350169486763866e-01 +-2.023100473798250221e+01 1.520814818070421737e+01 2.068743045828157268e+00 -6.718428342995476366e-02 -3.238310953251236773e-02 1.810233746475911343e-01 9.806467197504810107e-01 +-2.003008189925847660e+01 1.517409903606462507e+01 2.070659101001316671e+00 -6.525167378786993211e-02 -3.344579123601653520e-02 1.870358849538260870e-01 9.796126902291274474e-01 +-1.982494515732422968e+01 1.513063637487507229e+01 2.074430086483830316e+00 -6.416746726491839858e-02 -3.519578605880979011e-02 1.918981645418474380e-01 9.786821423416809385e-01 +-1.965384943012049135e+01 1.508698024869777399e+01 2.076389137955708009e+00 -6.378019514722951810e-02 -3.763855786655878610e-02 1.957479091285511952e-01 9.778537888697909075e-01 +-1.948961096498404544e+01 1.505179097379046205e+01 2.072284817075018992e+00 -6.389437410566929654e-02 -4.044202187162802831e-02 1.987253473825571493e-01 9.771335832118609455e-01 +-1.933258911723182294e+01 1.502003635824399730e+01 2.070368887616188314e+00 -6.470998510553505056e-02 -4.345444887374317472e-02 2.009126418589243790e-01 9.765030957275405710e-01 +-1.917320681512573799e+01 1.499041699506302194e+01 2.072088841608691112e+00 -6.618339888423839523e-02 -4.693590890032925400e-02 2.019804236340539960e-01 9.760228275395445019e-01 +-1.902034381543474240e+01 1.496555965102183450e+01 2.075386078124768829e+00 -6.810809804166763348e-02 -5.054610197927305454e-02 2.020383533922505970e-01 9.756980827019108293e-01 +-1.887027065573176543e+01 1.494518788345334670e+01 2.078513958520793903e+00 -7.050182936655541299e-02 -5.418052228721418478e-02 2.010213896943786327e-01 9.755430435144810675e-01 +-1.874056917559722280e+01 1.492958187260158986e+01 2.082164290731034928e+00 -7.336861876315663167e-02 -5.773025156134082431e-02 1.988567967143820836e-01 9.755716779770967628e-01 +-1.863255263101379811e+01 1.491530607359389649e+01 2.085717404095332572e+00 -7.655764968775266577e-02 -6.113532483107075866e-02 1.956919154001892924e-01 9.757591584624414338e-01 +-1.853528160626419918e+01 1.490112845445516321e+01 2.088775495282948036e+00 -8.005915433033353179e-02 -6.435110930606666169e-02 1.914672314884831583e-01 9.761094407317428834e-01 +-1.844534103986456230e+01 1.488481591228454626e+01 2.092963753052159426e+00 -8.382208454099877859e-02 -6.742247592598546446e-02 1.861089373675393344e-01 9.766224457108689805e-01 +-1.836223704409640689e+01 1.486653652516606883e+01 2.096376783761374263e+00 -8.766101706523214687e-02 -7.022268758169866731e-02 1.796967982783925499e-01 9.772887180412758168e-01 +-1.828559200289143760e+01 1.484661298079097413e+01 2.097336750536834327e+00 -9.162121050648702747e-02 -7.262208661281341349e-02 1.722005733861409760e-01 9.780993763408689645e-01 +-1.821208011980237984e+01 1.482685568067020832e+01 2.095806705510431911e+00 -9.574690372886669743e-02 -7.452372176215169008e-02 1.634387164022577388e-01 9.790640306001334725e-01 +-1.813626085198079707e+01 1.480494398657802613e+01 2.095515815191007380e+00 -9.993557997899722711e-02 -7.582870961633583762e-02 1.535873062232560315e-01 9.801396184984921822e-01 +-1.806150641619427688e+01 1.478309008123216906e+01 2.096079684485329331e+00 -1.040516534877436727e-01 -7.641651660915249611e-02 1.425483410307718801e-01 9.813325570462070324e-01 +-1.798716727284493189e+01 1.476309320501279920e+01 2.097857943105324363e+00 -1.079974499821066969e-01 -7.626260043230576047e-02 1.302367427375733522e-01 9.826285163278722923e-01 +-1.792035828452866042e+01 1.474847287771143378e+01 2.099481093561671674e+00 -1.118371981574265428e-01 -7.520129091147600975e-02 1.168578180182255205e-01 9.839620417255634521e-01 +-1.786896633246229271e+01 1.473883459295010745e+01 2.100079897133919182e+00 -1.155498340418688458e-01 -7.296937675020730152e-02 1.024256137683263873e-01 9.853083491927672188e-01 +-1.782955813724623795e+01 1.473018792611420480e+01 2.101394596507172086e+00 -1.191334854201221288e-01 -6.976046563237510434e-02 8.680260521505843430e-02 9.866133172349799141e-01 +-1.780025780684731629e+01 1.472016275391155737e+01 2.106005668767443328e+00 -1.227530299644173234e-01 -6.568173737006395563e-02 7.021006128590007167e-02 9.877692035547255278e-01 +-1.778024323699494857e+01 1.471179777764218244e+01 2.111474266157935542e+00 -1.263361315597076040e-01 -6.082715310475720477e-02 5.267126556216187444e-02 9.887187798754073498e-01 +-1.776688363602180232e+01 1.470608652646782666e+01 2.114623548761825234e+00 -1.298361307518257068e-01 -5.531859876520795610e-02 3.432665932972633893e-02 9.893957596410226651e-01 +-1.776180378205032184e+01 1.470420970695452212e+01 2.115301687685079202e+00 -1.332139316602710677e-01 -4.932799815798065424e-02 1.516235116415115894e-02 9.897427758281290844e-01 +-1.776083762602299743e+01 1.470488575887673122e+01 2.115395313544910838e+00 -1.364343403737725557e-01 -4.288589963293847063e-02 -4.614807795886593025e-03 9.897095679667489154e-01 +-1.776346128225869947e+01 1.470799042157793757e+01 2.115089730487588859e+00 -1.394610445813741495e-01 -3.610019484816001656e-02 -2.484307627542065369e-02 9.892573303291761766e-01 +-1.776381347894344742e+01 1.471083074267056467e+01 2.115187686400317180e+00 -1.423418346008326618e-01 -2.899275916591693286e-02 -4.518123988528639778e-02 9.883606354666614191e-01 +-1.776124323303142205e+01 1.471304403810461281e+01 2.115470615317164960e+00 -1.450500884313442873e-01 -2.167426971983349437e-02 -6.550171346812502793e-02 9.870157493613137545e-01 +-1.775576822200288873e+01 1.471449152830182072e+01 2.116163165305680938e+00 -1.475710839897600157e-01 -1.423157851761065913e-02 -8.564796990829237622e-02 9.852332354915237511e-01 +-1.774671665487562322e+01 1.471525345178032396e+01 2.117798358331107966e+00 -1.498742727731608437e-01 -6.744801397174555319e-03 -1.054758811063421786e-01 9.830396339459467336e-01 +-1.773425008782144374e+01 1.471524935046138793e+01 2.120497156016112772e+00 -1.519542430216485329e-01 6.908105285363304055e-04 -1.248346645081095108e-01 9.804721340744722013e-01 +-1.771933772421600040e+01 1.471452123882868968e+01 2.124018873593796375e+00 -1.538148544917070648e-01 7.945132713633333565e-03 -1.435659849898861251e-01 9.775819838768001757e-01 +-1.770158892031110298e+01 1.471332367211089220e+01 2.128353228040870793e+00 -1.554512998809085833e-01 1.487580230637751237e-02 -1.615518430521011850e-01 9.744303333156587588e-01 +-1.768070659655806054e+01 1.471178483285920890e+01 2.133486153904172511e+00 -1.568672270639969446e-01 2.137023449095604155e-02 -1.786748408674451449e-01 9.710876148719804757e-01 +-1.765520583790828368e+01 1.470953312904325827e+01 2.139785298003943126e+00 -1.580715135408298500e-01 2.735972551992696747e-02 -1.948075342638374841e-01 9.676335654745908954e-01 +-1.763257909878102581e+01 1.470792589631183667e+01 2.145768696274809262e+00 -1.591307992913066627e-01 3.274421947091263330e-02 -2.098386170646575899e-01 9.641435573131417192e-01 +-1.761154506912698992e+01 1.470756849560478763e+01 2.150759440345031859e+00 -1.600752148866937674e-01 3.748578752557860799e-02 -2.237643708399396081e-01 9.606768854753626741e-01 +-1.759346871674128110e+01 1.470832716101988602e+01 2.153318594371060435e+00 -1.609509316239397247e-01 4.145880040599969618e-02 -2.363738737888267105e-01 9.573417213092957345e-01 +-1.757715898289109191e+01 1.470985754540407342e+01 2.156877113365502474e+00 -1.602667494947415394e-01 4.430118789341638830e-02 -2.476207932373343801e-01 9.544819165735920485e-01 +-1.756470525599414501e+01 1.471083080869373916e+01 2.160252285466500055e+00 -1.596877662244635121e-01 4.645445504920311941e-02 -2.575108597271836275e-01 9.518559635896126636e-01 +-1.755430864807247460e+01 1.471272029587783514e+01 2.164736519679076654e+00 -1.592736919425307984e-01 4.799229735555288201e-02 -2.661396745097128758e-01 9.494725491621541780e-01 +-1.754858573576068537e+01 1.471440250282627815e+01 2.166458189873719853e+00 -1.590557544306516191e-01 4.882832573250100311e-02 -2.734190187995648724e-01 9.473958580849505262e-01 +-1.754552770370608528e+01 1.471451448183227662e+01 2.167897316934680241e+00 -1.589529114605628402e-01 4.913746779228266720e-02 -2.794246577992133274e-01 9.456432448388171208e-01 +-1.754428721701840033e+01 1.471336620128529304e+01 2.168646122790431008e+00 -1.589759204067289211e-01 4.899210478298784976e-02 -2.843120574432076442e-01 9.441890061790466637e-01 +-1.754390638424300519e+01 1.471321537899052601e+01 2.168568871272051002e+00 -1.591757036192298358e-01 4.847914298886440293e-02 -2.882517089297858548e-01 9.429865401738088959e-01 +-1.753290603074790610e+01 1.471363162880962250e+01 2.169377446536030707e+00 -1.594643028330341994e-01 4.763583741186019904e-02 -2.911380238452138114e-01 9.420936299997494379e-01 +-1.751853244776126672e+01 1.471280485397276472e+01 2.169986494430891089e+00 -1.597935945782330835e-01 4.660807173512841045e-02 -2.931362906841420979e-01 9.414693874770819759e-01 +-1.749360712046400579e+01 1.470823595765781810e+01 2.168300470524465950e+00 -1.602048833166648811e-01 4.531525870765994862e-02 -2.941799139575875244e-01 9.411370248698095464e-01 +-1.745801525471232907e+01 1.470027967859899221e+01 2.166110862214427168e+00 -1.607828737305490308e-01 4.380865285503965367e-02 -2.943071296303092499e-01 9.410700126972115775e-01 +-1.741882322495211710e+01 1.469317200249942168e+01 2.163938381328017080e+00 -1.613279033958738840e-01 4.226787651504165105e-02 -2.936509542937228434e-01 9.412521680717634842e-01 +-1.737896885794033963e+01 1.468541492320332864e+01 2.164267197864405468e+00 -1.619048546725881388e-01 4.080061870030021742e-02 -2.923728871494927772e-01 9.416156437917089228e-01 +-1.732517095217490066e+01 1.467056184203279656e+01 2.166301326430514429e+00 -1.624501422565838293e-01 3.924979473063118507e-02 -2.905188307762270328e-01 9.421613522439444832e-01 +-1.726126185485400200e+01 1.465085560410666332e+01 2.171132953640088736e+00 -1.628620259007576287e-01 3.778866383611321350e-02 -2.880354133628819646e-01 9.429121825691334502e-01 +-1.719660886337743122e+01 1.463240272352795657e+01 2.175043059578144256e+00 -1.631772076012331096e-01 3.651314370467392822e-02 -2.850262011098593229e-01 9.438219432046217605e-01 +-1.712681734994837868e+01 1.461326579475347565e+01 2.179298359770279525e+00 -1.633524409900261043e-01 3.540889622928487107e-02 -2.816128215824896253e-01 9.448577738285589556e-01 +-1.704915580289160459e+01 1.459310383259100341e+01 2.183854887157135050e+00 -1.634045079515848709e-01 3.457048599237469433e-02 -2.778413567799292161e-01 9.459956815391612484e-01 +-1.696043605798555021e+01 1.457022790767244835e+01 2.188178644843842946e+00 -1.633968358729152026e-01 3.400307237291030210e-02 -2.737401073632363402e-01 9.472124447289032023e-01 +-1.686445452943246082e+01 1.454556340935098113e+01 2.192252050279553721e+00 -1.633193504788871819e-01 3.373760357456163234e-02 -2.693973164946810162e-01 9.484795406941164408e-01 +-1.676247652571894164e+01 1.451863900828790932e+01 2.195668851689526857e+00 -1.627230258886791237e-01 3.363081066303381245e-02 -2.648764450952924565e-01 9.498581159229988469e-01 +-1.665414071784867289e+01 1.448945165759921316e+01 2.199309790274477816e+00 -1.620861716074133430e-01 3.386812534102041222e-02 -2.601942143283090259e-01 9.512516870670147950e-01 +-1.654096545727008305e+01 1.445813648103237803e+01 2.201809227910159095e+00 -1.614146099625347330e-01 3.438326190478429439e-02 -2.554701948352409158e-01 9.526268243938107450e-01 +-1.642521524600244476e+01 1.442424229103463773e+01 2.204874207459998292e+00 -1.607356232978392752e-01 3.514888531803071064e-02 -2.508221460753407017e-01 9.539479241986402736e-01 +-1.630276064959747018e+01 1.438910735164141386e+01 2.207111311065022452e+00 -1.600734291322964964e-01 3.610716151405037738e-02 -2.463145030052167894e-01 9.551972140610355266e-01 +-1.617531324703833562e+01 1.435379086875449950e+01 2.208392404173166401e+00 -1.594634551745424123e-01 3.718634443121759947e-02 -2.420772117923132294e-01 9.563404116826896839e-01 +-1.604214904655785645e+01 1.431703333398411360e+01 2.210212697699383000e+00 -1.588795560143457797e-01 3.834523471075730605e-02 -2.382154889010023868e-01 9.573609992253030443e-01 +-1.590417679979208465e+01 1.427947412300661867e+01 2.210313007287423748e+00 -1.583865263573699944e-01 3.944165915495820990e-02 -2.348361943610171310e-01 9.582326377184082755e-01 +-1.576631978958427638e+01 1.424097358560167592e+01 2.207741055732447499e+00 -1.580269097823363833e-01 4.041997628330624287e-02 -2.320227947900415644e-01 9.589363356533610050e-01 +-1.562145330482072936e+01 1.420406578287582988e+01 2.203849486508297595e+00 -1.576936287658199654e-01 4.130167230877271334e-02 -2.297510513434703472e-01 9.595004439268123297e-01 +-1.546460777698472633e+01 1.416602655418754253e+01 2.202303482841406090e+00 -1.573713487654057608e-01 4.207713230364828333e-02 -2.282462273944179942e-01 9.598787356885335464e-01 +-1.530606226785305068e+01 1.413256628063003717e+01 2.199627038052340389e+00 -1.571426035282546818e-01 4.259567267890640441e-02 -2.278114988057656221e-01 9.599966085586523201e-01 +-1.514087565949761860e+01 1.409378848750856150e+01 2.199873242883951807e+00 -1.570254715378673060e-01 4.286541684680277020e-02 -2.283332991658232058e-01 9.598797937163758842e-01 +-1.498034452942751749e+01 1.405489914660284789e+01 2.200973272957193583e+00 -1.571775213891299372e-01 4.280269431575939310e-02 -2.299371452910466684e-01 9.594747592803697378e-01 +-1.482121006184025980e+01 1.401708694435837543e+01 2.197753955363283218e+00 -1.576473983988297967e-01 4.214352245069670488e-02 -2.325262432191075035e-01 9.588026482315483712e-01 +-1.466983996292526271e+01 1.397496022545172778e+01 2.194572255859627674e+00 -1.582920265446358388e-01 4.094213490888980872e-02 -2.361841713341422955e-01 9.578539371333814056e-01 +-1.453352887369791446e+01 1.393358679012593271e+01 2.190418074615139599e+00 -1.592016359939976422e-01 3.915596996180333716e-02 -2.409854874862833729e-01 9.565810926802701397e-01 +-1.439827424546816204e+01 1.388542956385763638e+01 2.183351167213614108e+00 -1.604243221444694723e-01 3.654193201848164596e-02 -2.472768717811687222e-01 9.548730884675132868e-01 +-1.425669761309909767e+01 1.383277627131903920e+01 2.173425473550271381e+00 -1.620682001990153831e-01 3.307854631736246998e-02 -2.551892415462925778e-01 9.526373409199061504e-01 +-1.412590162618181289e+01 1.377712114185407088e+01 2.167234427590452928e+00 -1.639446513721360132e-01 2.899553668503442386e-02 -2.648674162229788243e-01 9.498033491687686292e-01 +-1.399604943682839142e+01 1.372158914898174764e+01 2.163970265701970597e+00 -1.657858129734203489e-01 2.406582795187409488e-02 -2.762822044488303930e-01 9.463634454060370071e-01 +-1.384661139511829120e+01 1.365143058518259167e+01 2.161904520263594698e+00 -1.678233245218127556e-01 1.828506504258629178e-02 -2.893916232965937363e-01 9.422065621608289865e-01 +-1.368006921888726701e+01 1.356123087789077530e+01 2.166096155544508850e+00 -1.701283568415986325e-01 1.191197093043556629e-02 -3.039668466991156670e-01 9.372930924319964330e-01 +-1.350985440111793068e+01 1.345763383471481056e+01 2.175242283285886202e+00 -1.725710839785354611e-01 5.075239848615055449e-03 -3.194541419225832568e-01 9.317415178968395661e-01 +-1.333697703434933857e+01 1.334215600679860358e+01 2.185838791556650396e+00 -1.750679068924898552e-01 -2.337291607788242933e-03 -3.355921660815493479e-01 9.255935483312971446e-01 +-1.316622061469933058e+01 1.322387309937271560e+01 2.197136583342674587e+00 -1.775351457546254785e-01 -1.014724224601772258e-02 -3.520047064885605259e-01 9.189508931296438421e-01 +-1.299703565313839526e+01 1.310376719126060507e+01 2.215860596135141858e+00 -1.799735251964539040e-01 -1.806386358304223894e-02 -3.686207810301289078e-01 9.118123200612366919e-01 +-1.283168503003983929e+01 1.298131717868560742e+01 2.235696275939695443e+00 -1.824075464885830389e-01 -2.615885946035455267e-02 -3.851350973103248032e-01 9.042753526796357688e-01 +-1.267741113485115889e+01 1.286063583119418219e+01 2.260013652335474799e+00 -1.848076219677117216e-01 -3.410309760761479764e-02 -4.011888836470370312e-01 8.965100939703536387e-01 +-1.253201695949777950e+01 1.273853756466149889e+01 2.289854396520654589e+00 -1.871327884395841412e-01 -4.181670002319468060e-02 -4.167913561875874473e-01 8.885479215972782452e-01 +-1.239863978088368057e+01 1.262283651605162049e+01 2.320628911511395387e+00 -1.892500114284657031e-01 -4.925487165030190823e-02 -4.318127606038639765e-01 8.805088769975960572e-01 +-1.227396043270233683e+01 1.251183608098020805e+01 2.351509364719013728e+00 -1.912744275848471676e-01 -5.635579653835351421e-02 -4.460962716794354965e-01 8.724883850854173728e-01 +-1.216051823961005240e+01 1.240915076818466822e+01 2.382139946864808344e+00 -1.932260904940433788e-01 -6.292957144351564447e-02 -4.594119531511073329e-01 8.646640758342634125e-01 +-1.205266159099152823e+01 1.230780791279903319e+01 2.416061604298839871e+00 -1.949856614867817584e-01 -6.886831191208621361e-02 -4.715655968278623100e-01 8.572417331603260360e-01 +-1.194514238363695569e+01 1.220397806549690145e+01 2.455611748650547099e+00 -1.966094868358854442e-01 -7.416589001951345850e-02 -4.823695417288748066e-01 8.503902129255297426e-01 +-1.183827173554612244e+01 1.208747529584322855e+01 2.510145093144891426e+00 -1.982654813135747707e-01 -7.852441961796580161e-02 -4.916076360240347887e-01 8.443023175323814966e-01 +-1.173756014225560662e+01 1.196418221569341789e+01 2.581550381106281655e+00 -1.998543923968104929e-01 -8.183923493788647363e-02 -4.989418827405184831e-01 8.392957352908562152e-01 +-1.163732329880508054e+01 1.182568728239220590e+01 2.672790209931520167e+00 -2.011187590883487530e-01 -8.439271952813923172e-02 -5.044072222011399820e-01 8.354652951616321488e-01 +-1.153635173778608802e+01 1.166349977492017231e+01 2.788874222994223384e+00 -2.023787857096887022e-01 -8.622784410876796479e-02 -5.079827912772086895e-01 8.328030155242747146e-01 +-1.143950013689890000e+01 1.149166655351469402e+01 2.928524681772375349e+00 -2.035215056948520007e-01 -8.740878554344684581e-02 -5.095161711255729031e-01 8.314636210992372156e-01 +-1.135773304335328859e+01 1.133922297177344163e+01 3.075193507733003262e+00 -2.041824177583614619e-01 -8.757948540178962793e-02 -5.088236989862157111e-01 8.317076320332140726e-01 +-1.128699032941793767e+01 1.120075420766714025e+01 3.230513953070606181e+00 -2.047516830280953493e-01 -8.649289447884173088e-02 -5.060204106363749288e-01 8.333899617835321960e-01 +-1.122313447529674590e+01 1.107289294214347919e+01 3.385157011413508776e+00 -2.053711844052330260e-01 -8.408611022249672107e-02 -5.012543003408139741e-01 8.363588315347345592e-01 +-1.115248117688900820e+01 1.094133733651713491e+01 3.555691288090234714e+00 -2.056462033375179854e-01 -8.075730723813241696e-02 -4.951674025132455914e-01 8.402362303435323421e-01 +-1.108732048213619414e+01 1.081456404053830234e+01 3.717121101071051648e+00 -2.059910685309201961e-01 -7.650109225546963820e-02 -4.874224662550116771e-01 8.450647273734225307e-01 +-1.101494070912414713e+01 1.068284157588535521e+01 3.886119635478032297e+00 -2.061466384733158519e-01 -7.127643491142374166e-02 -4.784386800959306019e-01 8.505994696215272155e-01 +-1.093524173425383594e+01 1.054803923807605948e+01 4.058019727573429769e+00 -2.061099341383379191e-01 -6.507997307295336487e-02 -4.681790076260793354e-01 8.567914006080686873e-01 +-1.084763447487299537e+01 1.041268831336648404e+01 4.229629705735738376e+00 -2.057315387040039856e-01 -5.772430254235429853e-02 -4.568317663531050177e-01 8.635085207620848413e-01 +-1.074511561564592022e+01 1.027247535588492511e+01 4.400687582912439666e+00 -2.046454030423378867e-01 -4.918420410341037274e-02 -4.446273787415646606e-01 8.706362310051629638e-01 +-1.062932761967035589e+01 1.012820442647781150e+01 4.553728133787957155e+00 -2.029565690760325170e-01 -3.949167088139289572e-02 -4.311415380845254330e-01 8.782743283105247656e-01 +-1.049700918522519721e+01 9.987838589611772733e+00 4.669379209295867028e+00 -2.008189702976947155e-01 -2.903101795731325221e-02 -4.166969991530746209e-01 8.861107850649578843e-01 +-1.035518267560249939e+01 9.861969085908372179e+00 4.751070819784137811e+00 -1.958454252688869301e-01 -1.868715204652300274e-02 -4.016501144514015298e-01 8.944117098230366381e-01 +-1.020832808150564475e+01 9.749660002455138752e+00 4.807984829444467145e+00 -1.903070630035642863e-01 -7.593968791745912307e-03 -3.861295325734883654e-01 9.025681642910160507e-01 +-1.006462358990678396e+01 9.652235384479599389e+00 4.846173601572889567e+00 -1.847445601796558479e-01 4.365578917755052676e-03 -3.701214127740822257e-01 9.104176421348203485e-01 +-9.928657381585725972e+00 9.568888013689392125e+00 4.867075191618293495e+00 -1.792362421215590584e-01 1.718675473453972966e-02 -3.538081418758112218e-01 9.178227182108023019e-01 +-9.795577920659157556e+00 9.494090355712675233e+00 4.878113693445429888e+00 -1.737343257625819093e-01 3.081909256437668707e-02 -3.375861476186318155e-01 9.246090618534862360e-01 +-9.661176967701988971e+00 9.423962946457072221e+00 4.882171328813533329e+00 -1.681756565410551796e-01 4.502750568400982339e-02 -3.216238190481252035e-01 9.307240917155382709e-01 +-9.526235813569117639e+00 9.358046157154838340e+00 4.879546246116782449e+00 -1.627319079534192414e-01 5.965657446638202022e-02 -3.062229051444254613e-01 9.360484561081945376e-01 +-9.390715066920950704e+00 9.294511340234727470e+00 4.872074737937317046e+00 -1.575600456324180998e-01 7.452147882480016083e-02 -2.916078133009603612e-01 9.405243241610005134e-01 +-9.255741124676109877e+00 9.233168477068076641e+00 4.862719929474887515e+00 -1.526083636231672647e-01 8.970028692292388028e-02 -2.779558671478457588e-01 9.441423766854085686e-01 +-9.110115748703927707e+00 9.160656321856599504e+00 4.853119718596683008e+00 -1.448805444527668240e-01 1.042704447501368176e-01 -2.654940920189678422e-01 9.474438960705133805e-01 +-8.960508298635936342e+00 9.086392725294514250e+00 4.844143091669125489e+00 -1.368322183912593359e-01 1.191111185464089617e-01 -2.543805445511533869e-01 9.499367212115463754e-01 +-8.802053506879710554e+00 9.010855401599721759e+00 4.832301039463605896e+00 -1.284837162166377333e-01 1.338807568014935556e-01 -2.445762298229477716e-01 9.517090363254917529e-01 +-8.636209778905397982e+00 8.932626204285671889e+00 4.818409796669749667e+00 -1.199414029479377447e-01 1.484064460215570591e-01 -2.359549264073556307e-01 9.528455386988187170e-01 +-8.464140448895715707e+00 8.850351050039439116e+00 4.803352734674167124e+00 -1.112792292450228149e-01 1.626455393506967828e-01 -2.284682760107906996e-01 9.533967514881616090e-01 +-8.285842459073196054e+00 8.773383956707331066e+00 4.782369279912356497e+00 -1.025146313610508786e-01 1.764788996614772842e-01 -2.221124353490130932e-01 9.534210932004744121e-01 +-8.114133289484326994e+00 8.705543691922068561e+00 4.757856858937089761e+00 -9.388423022029269982e-02 1.897102117440097879e-01 -2.167248350967028725e-01 9.530088667976455152e-01 +-7.966413532293470823e+00 8.649262174225476940e+00 4.732697675124038383e+00 -8.546786416506156614e-02 2.021958267635559636e-01 -2.122202162550722582e-01 9.522470547132205754e-01 +-7.838296370121983436e+00 8.602142342702320477e+00 4.706681049907486702e+00 -7.722082121429661716e-02 2.138807004510542842e-01 -2.086132058058942085e-01 9.511951941279739309e-01 +-7.722460607913379960e+00 8.555961850315631168e+00 4.682140683149526694e+00 -6.926594664978155680e-02 2.246589746999888837e-01 -2.057724656928235640e-01 9.499410831019948764e-01 +-7.623831137275054459e+00 8.512771062322395110e+00 4.657138786462549085e+00 -6.168996695748747705e-02 2.343784833952097801e-01 -2.037189628972736477e-01 9.485565157627455779e-01 +-7.546843188356539223e+00 8.472208031328831268e+00 4.633192190619449313e+00 -5.450375163225126135e-02 2.430585373033365970e-01 -2.024227503969243946e-01 9.470885500355606945e-01 +-7.486476728816337634e+00 8.440815148072747576e+00 4.610710309118721817e+00 -4.770571378634198140e-02 2.506317554601256714e-01 -2.020770809235940546e-01 9.455540866581557680e-01 +-7.440299964705224589e+00 8.416958122596488678e+00 4.593164121767197905e+00 -4.140588616186403198e-02 2.570514082178247950e-01 -2.025012668505896951e-01 9.440355657182665228e-01 +-7.396345226618334046e+00 8.397243593556252605e+00 4.580928575928226998e+00 -3.559464193890889833e-02 2.619480351332992840e-01 -2.040529019416751078e-01 9.425913457587361544e-01 +-7.359082997625071343e+00 8.384106685373392764e+00 4.568838528947360977e+00 -3.082171805157595326e-02 2.643322252904545810e-01 -2.069175931235628374e-01 9.414687456203280069e-01 +-7.302026356289392339e+00 8.357480387139352374e+00 4.544941278909785609e+00 -2.705147037784246672e-02 2.635474766097758992e-01 -2.108188989966877647e-01 9.409389584548618624e-01 +-7.249194796845570998e+00 8.332448662081926472e+00 4.522177037968137192e+00 -2.348931618740522642e-02 2.629461495568421459e-01 -2.151934143954868928e-01 9.402122886374607580e-01 +-7.192574988222773413e+00 8.304052243351245366e+00 4.498606689260705949e+00 -2.019453168423964579e-02 2.624139011815839195e-01 -2.200437222374501678e-01 9.393144602230939499e-01 +-7.134046519940341113e+00 8.271338824996039563e+00 4.475103494481515121e+00 -1.720243089105051582e-02 2.619425976925379151e-01 -2.252009680059845753e-01 9.382827111412271881e-01 +-7.101496752580978011e+00 8.256352049370411450e+00 4.464792718273583816e+00 -1.608926579076124311e-02 2.563946365376729153e-01 -2.316767545295572439e-01 9.382582764825715405e-01 +-7.066311361565515980e+00 8.229456314921264948e+00 4.452957677367096245e+00 -1.588172072373412666e-02 2.486992594060363493e-01 -2.384370209333511736e-01 9.386394576744967466e-01 +-7.023231946952388505e+00 8.189605347353088760e+00 4.440963527834605351e+00 -1.649931232245117549e-02 2.391868458650006912e-01 -2.455518537738545781e-01 9.392664750276934482e-01 +-6.979041839034425543e+00 8.143272453791784216e+00 4.430181111014941386e+00 -1.786565177166500942e-02 2.279937541361085895e-01 -2.529972316317633529e-01 9.400488617876656683e-01 +-6.935183589108718571e+00 8.089564188639213782e+00 4.422930206766563899e+00 -1.998480485305475368e-02 2.154290072454379257e-01 -2.606377633159859819e-01 9.408818707293717942e-01 +-6.888868303451047836e+00 8.030702240266915481e+00 4.417015406419602996e+00 -2.287103566259705151e-02 2.016401886372044816e-01 -2.684141293202135237e-01 9.416856130777121470e-01 +-6.840674241225232599e+00 7.967394404473957081e+00 4.412340650852007329e+00 -2.640110625360386071e-02 1.867330320427368351e-01 -2.761348269065626027e-01 9.424346671394686625e-01 +-6.783646706868969645e+00 7.893077095892037320e+00 4.406745275081826563e+00 -3.049310860789122488e-02 1.707747820104351943e-01 -2.838466760501241470e-01 9.430466609513866727e-01 +-6.706675553581081139e+00 7.805858116523429757e+00 4.399698552885772607e+00 -3.517078950191957626e-02 1.539407376304821329e-01 -2.915211517472718339e-01 9.434407566295304193e-01 +-6.608358311218235137e+00 7.714939868202249862e+00 4.390607292666790507e+00 -4.032984107040732402e-02 1.362637847355430420e-01 -2.991954937832328465e-01 9.435504829919811876e-01 +-6.496344793411751084e+00 7.635577509875125735e+00 4.374959519035974687e+00 -4.606334997161197486e-02 1.176713080147281237e-01 -3.069104571995260322e-01 9.433119127938537352e-01 +-6.377487104502294279e+00 7.559796599687431673e+00 4.357834903699150608e+00 -5.216803244863016387e-02 9.851820270137630342e-02 -3.145480621841146851e-01 9.426727619600988595e-01 +-6.253332481168209611e+00 7.486272953676961883e+00 4.337973343863350983e+00 -5.869621212591501908e-02 7.896475123581589428e-02 -3.220200705284214648e-01 9.416061618763930108e-01 +-6.125955660049786644e+00 7.416734456754976890e+00 4.318464720724177752e+00 -6.561700398737782547e-02 5.905604672987263548e-02 -3.295377877320313509e-01 9.400060645074467258e-01 +-6.003543153951099498e+00 7.348223801923311704e+00 4.300963972352018772e+00 -7.299305252052640247e-02 3.916334266508965378e-02 -3.366025357079139857e-01 9.379961291790802624e-01 +-5.880512867404823041e+00 7.277274617380643740e+00 4.282508140535700392e+00 -8.085000752411357350e-02 1.931657739625739292e-02 -3.431589170379617526e-01 9.355917188810530805e-01 +-5.752199727943890117e+00 7.205898979355740863e+00 4.264124981893480104e+00 -8.880612838383861174e-02 -1.839939236060274318e-04 -3.490965591188769923e-01 9.328691180592872945e-01 +-5.620867968844497575e+00 7.133680648589026951e+00 4.248143531305163201e+00 -9.684880036799936587e-02 -1.922477257833903747e-02 -3.542156685044489661e-01 9.299364131219416407e-01 +-5.487357874667395663e+00 7.063942181732535630e+00 4.235131167686096987e+00 -1.048774302590843588e-01 -3.769935494056864816e-02 -3.586219151837029551e-01 9.268061084962051499e-01 +-5.351468054219385984e+00 7.001415512029576682e+00 4.221427222353877795e+00 -1.129437658115804433e-01 -5.559397401524718285e-02 -3.623312765097851940e-01 9.235089714721697041e-01 +-5.215343083461586815e+00 6.942455538290364991e+00 4.209360461916056728e+00 -1.210502069832659344e-01 -7.255572553426346827e-02 -3.652346965790361222e-01 9.201553656388268276e-01 +-5.077978219438366914e+00 6.884623083408889066e+00 4.199271436486815112e+00 -1.293062233471359845e-01 -8.853527020957462079e-02 -3.674283988327597394e-01 9.167538155023878810e-01 +-4.936981366718767639e+00 6.825944957851960204e+00 4.184431251317998424e+00 -1.377268663162275475e-01 -1.038090277746670370e-01 -3.689458283477936029e-01 9.133092345837549031e-01 +-4.799067951959267830e+00 6.767530718028485381e+00 4.167587916588884056e+00 -1.462227977877073315e-01 -1.183681824697107587e-01 -3.697480938739740042e-01 9.098868043232711811e-01 +-4.659851106914774554e+00 6.708264457925801061e+00 4.146864561326532694e+00 -1.546790427632031839e-01 -1.322488951593409623e-01 -3.700943353112481904e-01 9.064295818552727813e-01 +-4.522188911375335962e+00 6.649766699923481461e+00 4.125261756970721727e+00 -1.630881252217175059e-01 -1.453561096703797351e-01 -3.699021021501966988e-01 9.030205405840713295e-01 +-4.384336257272807735e+00 6.592750756864155015e+00 4.104585628073848191e+00 -1.713861896820074171e-01 -1.577184267005262430e-01 -3.692641992798849082e-01 8.996640653209384553e-01 +-4.250973995207671052e+00 6.537395187942486530e+00 4.087722524472261476e+00 -1.795708065933855901e-01 -1.692032476285243170e-01 -3.683439904464128056e-01 8.963521108677855453e-01 +-4.119881159089879397e+00 6.483124114210427891e+00 4.074099790579315261e+00 -1.875247269533678318e-01 -1.798487727683729109e-01 -3.671948340929857002e-01 8.931162726885953917e-01 +-3.986719846703399739e+00 6.430081682505231377e+00 4.063457033507956950e+00 -1.950501282673557935e-01 -1.897321176069262927e-01 -3.657920878694423394e-01 8.900298624484728194e-01 +-3.857806398098146961e+00 6.376368202825703158e+00 4.050154850419703578e+00 -2.025033880086890281e-01 -1.989905774586621656e-01 -3.640499842730823832e-01 8.870527416890000572e-01 +-3.733261705384908868e+00 6.323539375167103849e+00 4.034584292157113339e+00 -2.097529231168790420e-01 -2.076064800471262295e-01 -3.621125463825130009e-01 8.841818827288916438e-01 +-3.608895954391719840e+00 6.268594256964607148e+00 4.018608938499705019e+00 -2.167298606279331741e-01 -2.157054293662292455e-01 -3.599471943344783043e-01 8.814404110978438789e-01 +-3.484578877128846841e+00 6.211247339903801290e+00 4.002878100488556967e+00 -2.233355575556960071e-01 -2.232795469326028792e-01 -3.575758573962185549e-01 8.788667835228113345e-01 +-3.361961781382274861e+00 6.152604211490512398e+00 3.987491560176556593e+00 -2.296326114300094590e-01 -2.303731593773752084e-01 -3.550985408290596168e-01 8.764142549027159612e-01 +-3.232963224561080207e+00 6.092362024818040567e+00 3.971946792803201731e+00 -2.355387531475781060e-01 -2.370476390156331381e-01 -3.525263185246546027e-01 8.741023728411995153e-01 +-3.096806288696448473e+00 6.032428544600991316e+00 3.957059679993236934e+00 -2.409063130901048233e-01 -2.432742862646420090e-01 -3.499663749929467493e-01 8.719547870850730131e-01 +-2.947835898989248804e+00 5.971301466077779452e+00 3.941377327530580121e+00 -2.457396268570619657e-01 -2.491844071049651721e-01 -3.474969933653390686e-01 8.699223264919266896e-01 +-2.785655452816519606e+00 5.908597375916054162e+00 3.925311168851185695e+00 -2.499514306323248614e-01 -2.546738318261297929e-01 -3.451455502244761275e-01 8.680667693277970276e-01 +-2.612704489809447139e+00 5.843342742627270603e+00 3.908542328851709158e+00 -2.535515842518141771e-01 -2.598313598438937166e-01 -3.429015539914031518e-01 8.663819208033343156e-01 +-2.455399236820277942e+00 5.785151754944600100e+00 3.892242304149701848e+00 -2.539072761237607390e-01 -2.659010252763311377e-01 -3.403582355159561201e-01 8.654385333501263267e-01 +-2.293190962984199999e+00 5.723915231927273695e+00 3.876423312901263962e+00 -2.542894226008700631e-01 -2.714890557432704798e-01 -3.381377392628824308e-01 8.644612780053019252e-01 +-2.132373455540924390e+00 5.660935038304082845e+00 3.860920394488562835e+00 -2.547217607893528246e-01 -2.766660536020267291e-01 -3.362315999067881922e-01 8.634355157012689741e-01 +-1.971021436458088694e+00 5.595174079862699656e+00 3.846183329849794941e+00 -2.551964250719007121e-01 -2.814446574914436505e-01 -3.345882303122783008e-01 8.623887001362717797e-01 +-1.807598528662877957e+00 5.524880524458068543e+00 3.830543208442553027e+00 -2.557911745855398489e-01 -2.858331761697825990e-01 -3.331920886003421067e-01 8.613089869330943227e-01 +-1.636396750634920849e+00 5.449308591653828415e+00 3.814179987336483002e+00 -2.564356646716348109e-01 -2.898095296325224335e-01 -3.320076105548865342e-01 8.602453154731618534e-01 +-1.462849563296797939e+00 5.371808452666209099e+00 3.797672266084052506e+00 -2.570846326308839913e-01 -2.934042790718436877e-01 -3.310843152500332343e-01 8.591882670241032249e-01 +-1.288959287414961796e+00 5.292917677155276834e+00 3.781545168563773984e+00 -2.577150435771182191e-01 -2.966579214383787133e-01 -3.303889811051302083e-01 8.581491827892056001e-01 +-1.110384294059284738e+00 5.211388943277480479e+00 3.765021413855301535e+00 -2.582909199352131369e-01 -2.996411462888850519e-01 -3.299194320397960123e-01 8.571196094334919691e-01 +-9.306947922898101133e-01 5.129943480558734947e+00 3.748700907305206886e+00 -2.588553676685850791e-01 -3.023829077184999603e-01 -3.296466100733500548e-01 8.560908006544866167e-01 +-7.494490685971613164e-01 5.049509158624354122e+00 3.732439212189940125e+00 -2.593950529272124883e-01 -3.049098097719332712e-01 -3.295787314463892170e-01 8.550566825203730348e-01 +-5.667012248128854290e-01 4.970188515249279071e+00 3.716356193768302063e+00 -2.599189540195596115e-01 -3.071948295083041791e-01 -3.296747320403945469e-01 8.540421010068511842e-01 +-3.860252854679036005e-01 4.892396188679936309e+00 3.700342768031741336e+00 -2.604240794617456167e-01 -3.092307619911773275e-01 -3.299333368873552663e-01 8.530530468325369098e-01 +-2.072054335978287809e-01 4.816065056247569309e+00 3.683928818633339208e+00 -2.608932064002745799e-01 -3.110089615292314091e-01 -3.303045370677028525e-01 8.521190897992432234e-01 +-2.447975579075292729e-02 4.740467106325708890e+00 3.665415456885624312e+00 -2.613135702090207402e-01 -3.126000364908323448e-01 -3.308125963372271494e-01 8.512105144502563059e-01 +1.595740249002560729e-01 4.665596905702058095e+00 3.644972489376070879e+00 -2.616471515267254078e-01 -3.140208114602017209e-01 -3.314132164393753244e-01 8.503510167153639498e-01 +3.471288447045393077e-01 4.592472284345312517e+00 3.621866047608115924e+00 -2.619265891786012879e-01 -3.153883736017398798e-01 -3.320535384187794925e-01 8.495086451738068645e-01 +5.396921092991235902e-01 4.519869961037433548e+00 3.596445246442431909e+00 -2.621150676509559907e-01 -3.167384979479005991e-01 -3.326630847997775198e-01 8.487093440523550969e-01 +7.346148540931147775e-01 4.446154606730820191e+00 3.569251401890256137e+00 -2.622470510724456694e-01 -3.180828556285650865e-01 -3.331491282575469448e-01 8.479748298607119317e-01 +9.277145905395938197e-01 4.371409091765972477e+00 3.540091949644653901e+00 -2.626230253190023900e-01 -3.193624715034126260e-01 -3.335856134824063957e-01 8.472055639799496163e-01 +1.147408349023798069e+00 4.281853873535411026e+00 3.511632800095275897e+00 -2.628203931086945389e-01 -3.193106846024571510e-01 -3.337710710169577433e-01 8.470908282256689459e-01 +1.371228197384347425e+00 4.190689634470587954e+00 3.482504849926784107e+00 -2.630578164411414566e-01 -3.193105176189386385e-01 -3.338745359760006415e-01 8.469764171327285318e-01 +1.602631115346870860e+00 4.097610571536848489e+00 3.453718898542426530e+00 -2.632061328141644396e-01 -3.193060045923379331e-01 -3.339019271168552905e-01 8.469212385752546979e-01 +1.842365399673236093e+00 4.002317572365756249e+00 3.425523951207936957e+00 -2.633080283766072172e-01 -3.192899564009949454e-01 -3.338950352034970037e-01 8.468983398369697158e-01 +2.094720218907040632e+00 3.903878329413128512e+00 3.398803037233063318e+00 -2.633433159475628282e-01 -3.192180823322913752e-01 -3.338741291112674592e-01 8.469227088957377303e-01 +2.354262591754949341e+00 3.802152009202809158e+00 3.371593096554410085e+00 -2.633424979717358116e-01 -3.191920957378263646e-01 -3.337663848244893927e-01 8.469752245128163715e-01 +2.604197411746636881e+00 3.703220435939146959e+00 3.344303562073439817e+00 -2.633523283509775492e-01 -3.191927118787689643e-01 -3.336429326564991360e-01 8.470205656605683808e-01 +2.849775638970309721e+00 3.605343351638679028e+00 3.316527186966311547e+00 -2.633916373959189206e-01 -3.191995139476732080e-01 -3.334907466265020770e-01 8.470657089718527377e-01 +3.097269574732867792e+00 3.506807682250299152e+00 3.289455236294969609e+00 -2.634189178173160228e-01 -3.191981926378932299e-01 -3.333384052945241316e-01 8.471176831536757490e-01 +3.342667446625483318e+00 3.406404482585304372e+00 3.262533902487871007e+00 -2.635555257933511752e-01 -3.191790282508754628e-01 -3.331869385297593911e-01 8.471420100346495063e-01 +3.593692424357135540e+00 3.301117941430975478e+00 3.236380047578341745e+00 -2.637593801182107622e-01 -3.191393166883175203e-01 -3.330730963503033548e-01 8.471382904737906339e-01 +3.852259093578912719e+00 3.192793752004558172e+00 3.213368726070757742e+00 -2.640442641389767475e-01 -3.189400741266654737e-01 -3.330624427466959414e-01 8.471287691376589990e-01 +4.113682057355155131e+00 3.082963511105495158e+00 3.191243107632094844e+00 -2.643981242925143027e-01 -3.187506099625990741e-01 -3.331401395710793523e-01 8.470591522750866575e-01 +4.370650574498331942e+00 2.977905077017091617e+00 3.169436135804180488e+00 -2.645646206709125758e-01 -3.185704737972833156e-01 -3.334163189360682122e-01 8.469662612022570425e-01 +4.620010054486803242e+00 2.871391553607040237e+00 3.146975411462293870e+00 -2.647681049364830619e-01 -3.183207930799472063e-01 -3.337982696995875909e-01 8.468461048975165495e-01 +4.863105136758973934e+00 2.762516502334317892e+00 3.123525705996005097e+00 -2.651349630960089243e-01 -3.180136252111560591e-01 -3.342822003727763946e-01 8.466558281521140428e-01 +5.106965073624266438e+00 2.652677746937647907e+00 3.098733993142643417e+00 -2.655768091290671706e-01 -3.176437851507328269e-01 -3.348761857328731439e-01 8.464214163404696345e-01 +5.354525067790735449e+00 2.541683752404830798e+00 3.074547760560428333e+00 -2.659806296365726519e-01 -3.173161632991127190e-01 -3.356035998930727571e-01 8.461293501372315617e-01 +5.597027485204747244e+00 2.429894493447691151e+00 3.050253510475960272e+00 -2.664232896895293301e-01 -3.169067121365465312e-01 -3.365219601688203555e-01 8.457787065808948235e-01 +5.836457741611654981e+00 2.315672829549108691e+00 3.025680323846295483e+00 -2.668654645992337149e-01 -3.164087699659623443e-01 -3.375767531686643674e-01 8.454053050542151837e-01 +6.117179288033596229e+00 2.190876188079310172e+00 3.010688665963426658e+00 -2.625925915965534596e-01 -3.144352311098035924e-01 -3.373157174925847657e-01 8.475810285781371078e-01 +6.392460556058090049e+00 2.067228880174349470e+00 2.996010438678178733e+00 -2.575668981622772358e-01 -3.123728920230591788e-01 -3.369449988173235377e-01 8.500296443946259162e-01 +6.658490381244710044e+00 1.939125647571039002e+00 2.981245968920347877e+00 -2.517209370236194732e-01 -3.102719220936205891e-01 -3.366281794051740883e-01 8.526718178173181562e-01 +6.912966313485639169e+00 1.809531368391803952e+00 2.966588253924220098e+00 -2.453541443386767218e-01 -3.081337647487315534e-01 -3.361372045666425334e-01 8.554919993791344490e-01 +7.166081066372939290e+00 1.678144150695186188e+00 2.953539738913553148e+00 -2.383598649625162380e-01 -3.059262103830030499e-01 -3.355485534593488084e-01 8.584874814499373619e-01 +7.407934894783917201e+00 1.540454532724790937e+00 2.940250316007217535e+00 -2.308189700194129834e-01 -3.039631380850821296e-01 -3.349167410328621752e-01 8.614868743738993695e-01 +7.645869190725107956e+00 1.402894482678236576e+00 2.927984272082231776e+00 -2.226982507458010185e-01 -3.019744150717587616e-01 -3.342011298824619780e-01 8.645960845077699242e-01 +7.879217222833892365e+00 1.263399767335893875e+00 2.916618247588234958e+00 -2.140442592818645184e-01 -3.000658136006504884e-01 -3.333421032048318744e-01 8.677721226945004362e-01 +8.101334182756193769e+00 1.114780728356713269e+00 2.903659326891121051e+00 -2.054042949094037063e-01 -2.983662472546353972e-01 -3.324355015884601916e-01 8.707888081023515969e-01 +8.316225389912437649e+00 9.739550368439301442e-01 2.890432379311826061e+00 -1.964004584317672053e-01 -2.967803379525187912e-01 -3.314081403746222954e-01 8.737944784908888707e-01 +8.518734735201679342e+00 8.313422478980142527e-01 2.874659751083602721e+00 -1.873391067637601437e-01 -2.954759115789979962e-01 -3.305242338919597844e-01 8.765566865973857258e-01 +8.714223449303062807e+00 6.901135551082709929e-01 2.853743022883866498e+00 -1.783814212996334136e-01 -2.947715811138956754e-01 -3.296676214527598514e-01 8.789817337026891719e-01 +8.901441703891322277e+00 5.477546585134192014e-01 2.829696535221562392e+00 -1.695609075824687784e-01 -2.944237726621946050e-01 -3.287275382093225451e-01 8.811933876497437534e-01 +9.078252217730501172e+00 4.047536081228386706e-01 2.802179636631398463e+00 -1.607081968684333506e-01 -2.945056761842785309e-01 -3.277574482865859284e-01 8.831841102795328080e-01 +9.256796672624741262e+00 2.524054102349223561e-01 2.773384531365481021e+00 -1.521706827702955511e-01 -2.949674485666893275e-01 -3.268486962327947776e-01 8.848774271648428558e-01 +9.437211480952583997e+00 1.019943370345930134e-01 2.740277687602983736e+00 -1.435440180017515943e-01 -2.962383808567644605e-01 -3.259722865758864496e-01 8.862165957787457859e-01 +9.614766413691938851e+00 -4.729431208288253918e-02 2.704138251970213069e+00 -1.351058412327545422e-01 -2.977652060887240881e-01 -3.255769416052359810e-01 8.871763062267944422e-01 +9.770680202075253007e+00 -2.137748156193516880e-01 2.660377981225994670e+00 -1.277980964958311261e-01 -2.994357142642493641e-01 -3.253508338443577008e-01 8.877795700325497030e-01 +9.895132899960527695e+00 -3.858343836036971508e-01 2.598976673030808371e+00 -1.209923776176651394e-01 -3.012916446279859106e-01 -3.253564029833109772e-01 8.881031691856229315e-01 +1.000784447976543312e+01 -5.542553917153727472e-01 2.539350212476968682e+00 -1.150348663748838318e-01 -3.041427652656003011e-01 -3.249411924668446083e-01 8.880750053336999850e-01 +1.011265858691146668e+01 -7.179240050332311718e-01 2.470303229771022568e+00 -1.093006246538966303e-01 -3.081398019909077357e-01 -3.242624791160269027e-01 8.876693710704502971e-01 +1.022179692454391642e+01 -8.938462439381638092e-01 2.398513353490872024e+00 -1.035879986039058426e-01 -3.130950296430229929e-01 -3.240235413764137040e-01 8.867071670131574379e-01 +1.031148418984229131e+01 -1.040490301961203068e+00 2.307379810975608070e+00 -9.895497979985456993e-02 -3.183025159083416877e-01 -3.241619410384071198e-01 8.853305944841912689e-01 +1.037458622336226632e+01 -1.199648378737218524e+00 2.155572717082807621e+00 -9.703088203751170093e-02 -3.235862015959237725e-01 -3.236099439488839824e-01 8.838288200747589363e-01 +1.033318031932382652e+01 -1.293788436612981485e+00 1.905604072331350318e+00 -9.583695922994829586e-02 -3.271036389910402797e-01 -3.223569286728097949e-01 8.831218936305078593e-01 +1.023160183727370587e+01 -1.297948238006191302e+00 1.686275207041092905e+00 -9.387844954349483517e-02 -3.285142537315361988e-01 -3.222070139403097611e-01 8.828633200513485990e-01 +1.013119133191871235e+01 -1.261453794927615002e+00 1.542548847588035343e+00 -9.191333695847365981e-02 -3.317726228408854894e-01 -3.209426832334480451e-01 8.823119792264556560e-01 +9.993068328826669955e+00 -1.199750050880664665e+00 1.419193056000999986e+00 -8.955600720068797316e-02 -3.350458152737550988e-01 -3.208571001218437635e-01 8.813481293069412859e-01 +9.839563844464670694e+00 -1.128046972397543257e+00 1.338773818802253768e+00 -8.716823732184753037e-02 -3.382973192498133219e-01 -3.202054633799073513e-01 8.805821249443431809e-01 +9.728775802832204889e+00 -1.067105695522975850e+00 1.317468721063768111e+00 -8.511297273402342045e-02 -3.411115703857309223e-01 -3.203872894876689248e-01 8.796308638173925276e-01 +9.592023064321383075e+00 -9.725138047100572170e-01 1.308323457140910140e+00 -8.324578925318551481e-02 -3.431697891317079252e-01 -3.206000584852718993e-01 8.789311876194231266e-01 +9.442514675688185477e+00 -8.865337403329596189e-01 1.309883048538571071e+00 -8.166234106319285313e-02 -3.443225012511207939e-01 -3.203618421632400404e-01 8.787157501268997306e-01 +9.243589006673698094e+00 -7.912641982220930403e-01 1.325250630842437660e+00 -8.058690716438521306e-02 -3.443962014632983015e-01 -3.198974240769477673e-01 8.789553095603842570e-01 +9.018713194484710982e+00 -6.973293621360053818e-01 1.349168903506297035e+00 -7.925052868461171518e-02 -3.430578774573275203e-01 -3.191651674739566236e-01 8.798659243559093790e-01 +8.794012934437590800e+00 -6.187998979776567765e-01 1.382093492347846064e+00 -7.754037262700048949e-02 -3.400949725598375606e-01 -3.182367278169105362e-01 8.815033030004451042e-01 +8.581093571463386027e+00 -5.678327707402348601e-01 1.432173235376540177e+00 -7.591787169801128554e-02 -3.351992479099216160e-01 -3.175150776307634204e-01 8.837770662728448023e-01 +8.356264859884369400e+00 -5.286084301729339074e-01 1.484533567428590217e+00 -7.475072075718444675e-02 -3.282424444301498823e-01 -3.172419918661169014e-01 8.865813747828040770e-01 +8.118141635712989412e+00 -4.533118041249175612e-01 1.546988785181073300e+00 -7.313787077684372195e-02 -3.184073158508980428e-01 -3.174481306661658953e-01 8.902213780012463440e-01 +7.885570979441841821e+00 -3.983022579506699801e-01 1.601614041429946012e+00 -7.222139811872199666e-02 -3.061747143521878489e-01 -3.167312789249355776e-01 8.948308206659270070e-01 +7.682280939427666766e+00 -3.426629948067420051e-01 1.660634392982965668e+00 -7.179067418860048122e-02 -2.919527620693291858e-01 -3.160240699340598480e-01 8.998545718211709010e-01 +7.483608420427465546e+00 -2.961222204354244103e-01 1.719483263801687478e+00 -7.238493429684997316e-02 -2.753927756205827304e-01 -3.125801758836983524e-01 9.062078343684074611e-01 +7.309593075800011164e+00 -2.491927950743856868e-01 1.762921616388872792e+00 -7.432672740303010450e-02 -2.591273842264239513e-01 -3.102336817168699912e-01 9.116377394746917329e-01 +7.186201407452266210e+00 -1.870181783399862685e-01 1.766995228434814047e+00 -7.570759026599568897e-02 -2.432403940302289014e-01 -3.089772647673496020e-01 9.163161567725046641e-01 +7.040016477131526784e+00 -1.254953908139266883e-01 1.774089566325022238e+00 -7.670085028303229302e-02 -2.236201011955259443e-01 -3.070589235930023531e-01 9.218598784147321590e-01 +6.883667222996407986e+00 -6.709789548504513368e-02 1.768740016452765795e+00 -7.695912179331232394e-02 -2.017136002352660218e-01 -3.033548059118340579e-01 9.280972875644398767e-01 +6.722489697222223448e+00 -7.132980592086404781e-03 1.773727667361867155e+00 -7.704205922201358414e-02 -1.771477949789016793e-01 -2.990543712304484791e-01 9.344781770924713848e-01 +6.553664031184613492e+00 4.363647910078472664e-02 1.788075056764896420e+00 -7.705471421229488638e-02 -1.507743054792893000e-01 -2.944771267846891249e-01 9.405385123347719256e-01 +6.399744872508970950e+00 9.213386090419793673e-02 1.804570210033077604e+00 -7.626469955704046066e-02 -1.232300052429474158e-01 -2.889706227736842936e-01 9.463053576260282984e-01 +6.283577945003052889e+00 1.409379348652331776e-01 1.817695696466347099e+00 -7.497477266826389763e-02 -9.556048504081869621e-02 -2.839805537480736830e-01 9.511055689135718971e-01 +6.165654234236661146e+00 1.886136316691612858e-01 1.828152981630380758e+00 -7.364911608445168234e-02 -6.751080611787575736e-02 -2.786812776149009130e-01 9.551725629693529340e-01 +6.006019668023494518e+00 2.544104705378745779e-01 1.826357011983414491e+00 -7.209285452247593540e-02 -3.768186370331205043e-02 -2.730092473174886014e-01 9.585658163086976380e-01 +5.851285669886095775e+00 3.135814254923192101e-01 1.831344793058397036e+00 -7.008086715476420647e-02 -7.712049288828025199e-03 -2.676113689847374744e-01 9.609438667054630567e-01 +5.687481187047801257e+00 3.753294979574372525e-01 1.826613185591021926e+00 -6.757506981026646653e-02 2.210565334137030991e-02 -2.620294546172630690e-01 9.624371524220843854e-01 +5.572482549207586899e+00 4.318711072780065385e-01 1.824131582377623184e+00 -6.455514472084453170e-02 5.101699181857401871e-02 -2.566402477532203075e-01 9.629981458207059752e-01 +5.463498683954522761e+00 4.789541105287173361e-01 1.817043558246825841e+00 -6.089649783964248136e-02 7.818583888336987087e-02 -2.515926628039379387e-01 9.627457985270306828e-01 +5.373660904996192755e+00 5.170222625909541847e-01 1.821363672678161016e+00 -5.648860974444370325e-02 1.046954015972235003e-01 -2.467684888537582666e-01 9.617447518947903617e-01 +5.292031383098232844e+00 5.478507349686534411e-01 1.826529350585744726e+00 -5.207748258217679421e-02 1.296791723418434794e-01 -2.422735039362444998e-01 9.600908974973291210e-01 +5.195276546738191392e+00 5.905541172720901733e-01 1.826909895560539621e+00 -4.731428839170495615e-02 1.533120260154208769e-01 -2.386195653872892619e-01 9.577667865653205492e-01 +5.092197376701467881e+00 6.452614676134084126e-01 1.829453752892473695e+00 -4.220872745835693024e-02 1.750102993576923560e-01 -2.355782546923148313e-01 9.550353076768015592e-01 +4.999395722764114147e+00 6.867274119595971893e-01 1.829890949949061207e+00 -3.705983355028762138e-02 1.937000885286660201e-01 -2.327405117138519886e-01 9.523331489764216284e-01 +4.904188612785413071e+00 7.230854418774752546e-01 1.825964567083782963e+00 -3.180907193893355023e-02 2.089741586944637297e-01 -2.299984308363392516e-01 9.499570750882178061e-01 +4.836359910417331598e+00 7.418748113249656884e-01 1.821516767781382384e+00 -2.630853752681055688e-02 2.213746912648067722e-01 -2.275513831475613480e-01 9.479035899050954894e-01 +4.774702623194593265e+00 7.594512672561393174e-01 1.823385491238055156e+00 -2.038097436678299595e-02 2.317929447355764339e-01 -2.254099005143083423e-01 9.460691130506385660e-01 +4.711944631315355458e+00 7.833726412195742839e-01 1.833813714964690034e+00 -1.423762970859515295e-02 2.407079291359719986e-01 -2.235820730232180864e-01 9.443875096112156475e-01 +4.657523108621798080e+00 8.003853495378130400e-01 1.840671087893041236e+00 -8.219002226126889341e-03 2.476918705681500910e-01 -2.220298698167657014e-01 9.430183694484783885e-01 +4.596358931879579224e+00 8.077105411340720353e-01 1.840197358001297578e+00 -2.252653806068338673e-03 2.528540218873879253e-01 -2.201001484410734788e-01 9.421334441070958743e-01 +4.513729575748419265e+00 8.234347702564530636e-01 1.845918812490166871e+00 2.441912602580241422e-03 2.517728788032461140e-01 -2.181656276710544906e-01 9.428721816207311646e-01 +4.446834005879682472e+00 8.332576422366795299e-01 1.848173300475050240e+00 7.337880936797516913e-03 2.507708835141969073e-01 -2.157774837802976520e-01 9.436630473104179462e-01 +4.367832664500934214e+00 8.495117597821696398e-01 1.847862784825574423e+00 1.255189815650801198e-02 2.498591285665464901e-01 -2.130857943807204780e-01 9.444612557364822081e-01 +4.278047546831988512e+00 8.726757823392047309e-01 1.852963461240989318e+00 1.783265084550779075e-02 2.490205004779956488e-01 -2.100835157820606092e-01 9.452700485000359309e-01 +4.187759666223808352e+00 8.966909365192722303e-01 1.861003620416938009e+00 2.304002229000207819e-02 2.483107479673281881e-01 -2.064868752841157451e-01 9.461362815581543240e-01 +4.100515627667462581e+00 9.191911665850622803e-01 1.871205763894083107e+00 2.811443648596686357e-02 2.476812695549159282e-01 -2.021626360448621762e-01 9.470974643019459682e-01 +4.017590127056370974e+00 9.457163438563104263e-01 1.882360796148873749e+00 3.310663952318108894e-02 2.472080442372935616e-01 -1.971543544096434342e-01 9.481150086226399765e-01 +3.935537952426522601e+00 9.747118430788668242e-01 1.888131497135645986e+00 3.778238227017630124e-02 2.469453856496486299e-01 -1.913063301364711921e-01 9.492060512382806126e-01 +3.844863648313443072e+00 1.006040667570216041e+00 1.891954198035363133e+00 4.200956620979449940e-02 2.469007605187059640e-01 -1.846575290367432620e-01 9.503560332466997052e-01 +3.752119776379838623e+00 1.030921014336568131e+00 1.895160540559985618e+00 4.572982454506694522e-02 2.471328095683613391e-01 -1.767601364033251354e-01 9.516248252162111676e-01 +3.655449276242216605e+00 1.047527968549495148e+00 1.896577398359254651e+00 4.889846738913333768e-02 2.476125954583918709e-01 -1.673065434560853382e-01 9.530505022535807891e-01 +3.551634402061322415e+00 1.052695227407163925e+00 1.897153145950726927e+00 5.158017875574462396e-02 2.484179267617634135e-01 -1.563113387765038831e-01 9.545651179835072941e-01 +3.433367344687048295e+00 1.057388574327681185e+00 1.893019431761171711e+00 5.351107157230604316e-02 2.495089121239796870e-01 -1.437991192074766500e-01 9.561398703838684954e-01 +3.304394071475590611e+00 1.063090447397548655e+00 1.885639777352333457e+00 5.468254737695817103e-02 2.508713596432330384e-01 -1.297737954647030512e-01 9.577222524999897679e-01 +3.174884511557202860e+00 1.057595977742291415e+00 1.871923674892396861e+00 5.512959625100254807e-02 2.515747685992416049e-01 -1.138548032405743704e-01 9.595351525592590303e-01 +3.042828940095391399e+00 1.054878158578969272e+00 1.859796949775027519e+00 5.502964306928410931e-02 2.531697064694624077e-01 -9.643531647962980125e-02 9.610290470209132963e-01 +2.886904068324312789e+00 1.051820898911627999e+00 1.850082813414826610e+00 5.445278744204544441e-02 2.554650968723521931e-01 -7.775334808345839288e-02 9.621468976568758880e-01 +2.737246884887406750e+00 1.044871013432058682e+00 1.843313201603032025e+00 5.342934757180003297e-02 2.584251323516172372e-01 -5.798309113619418143e-02 9.628081215938619764e-01 +2.595539215649875331e+00 1.036570209460514702e+00 1.838660812688639901e+00 5.194429891562304946e-02 2.619595488542477146e-01 -3.706639850511356943e-02 9.629666748603040727e-01 +2.471655378637240386e+00 1.020278307185802591e+00 1.832890396937285393e+00 5.025958364461263067e-02 2.659871585894769686e-01 -1.512084190171237956e-02 9.625465771267009973e-01 +2.361805375437458387e+00 9.946352421541702071e-01 1.819262243611750929e+00 4.831907901680129042e-02 2.703590516105336405e-01 7.970878288176675916e-03 9.615131114867041529e-01 +2.254798573921629412e+00 9.657731475642721275e-01 1.801584821853835949e+00 4.607461141922492703e-02 2.744682041790506011e-01 3.195523318727293283e-02 9.599598623523349916e-01 +2.156331200628903044e+00 9.354610770299200961e-01 1.785182304753967220e+00 4.349284820289647802e-02 2.783964684725468985e-01 5.682084500715660347e-02 9.577969054901966928e-01 +2.081093664573391511e+00 9.146482249127811937e-01 1.775003960629129685e+00 4.067061785910941474e-02 2.825575148398388192e-01 8.211915980762943268e-02 9.548629899942776555e-01 +2.003133753503066661e+00 8.867706236324429669e-01 1.756695982983064619e+00 3.802693536825232229e-02 2.864982988596169178e-01 1.078791048614142212e-01 9.512278924864361329e-01 +1.947019822678452305e+00 8.674125084140920094e-01 1.743373598653120915e+00 3.509895256714958695e-02 2.906579821852781631e-01 1.337572597115262718e-01 9.467812376610010849e-01 +1.927366560612738144e+00 8.604708776888644328e-01 1.735590456236154155e+00 3.182196997947735889e-02 2.946261339476313190e-01 1.595424884228644480e-01 9.416627401571485700e-01 diff --git a/evaluator/pose_gt.txt b/evaluator/pose_gt.txt new file mode 100644 index 00000000..e29064ce --- /dev/null +++ b/evaluator/pose_gt.txt @@ -0,0 +1,734 @@ +8.257375717163085938e+00 -2.730143547058105469e+01 -3.229445695877075195e+00 -0.000000000000000000e+00 -0.000000000000000000e+00 1.324519515037536621e-01 9.911894202232360840e-01 +8.150029182434082031e+00 -2.726499938964843750e+01 -3.124113798141479492e+00 1.005725376307964325e-02 1.408183714374899864e-03 1.519933491945266724e-01 9.883292913436889648e-01 +8.035955429077148438e+00 -2.722590827941894531e+01 -3.013025999069213867e+00 2.116696164011955261e-02 2.910247072577476501e-03 1.725988239049911499e-01 9.847604036331176758e-01 +7.914939880371093750e+00 -2.718400382995605469e+01 -2.896314620971679688e+00 3.313439339399337769e-02 4.488728940486907959e-03 1.940394788980484009e-01 9.804237484931945801e-01 +7.786039829254150391e+00 -2.713848495483398438e+01 -2.775121927261352539e+00 4.576298221945762634e-02 6.125640124082565308e-03 2.160865813493728638e-01 9.752818942070007324e-01 +7.648814678192138672e+00 -2.708902359008789062e+01 -2.649977922439575195e+00 5.885510146617889404e-02 7.802580017596483231e-03 2.385131120681762695e-01 9.693228006362915039e-01 +7.502609729766845703e+00 -2.703505706787109375e+01 -2.521782159805297852e+00 7.221274077892303467e-02 9.501649998128414154e-03 2.610951364040374756e-01 9.625613689422607422e-01 +7.346512317657470703e+00 -2.697579002380371094e+01 -2.391965389251708984e+00 8.563899993896484375e-02 1.120452024042606354e-02 2.836139798164367676e-01 9.550411701202392578e-01 +7.179455280303955078e+00 -2.691020011901855469e+01 -2.262508392333984375e+00 9.893891215324401855e-02 1.289336383342742920e-02 3.058579564094543457e-01 9.468346238136291504e-01 +7.000294685363769531e+00 -2.683707046508789062e+01 -2.136049747467041016e+00 1.119204610586166382e-01 1.455131731927394867e-02 3.276241421699523926e-01 9.380428791046142578e-01 +6.807950973510742188e+00 -2.675503349304199219e+01 -2.016015529632568359e+00 1.243962049484252930e-01 1.616092585027217865e-02 3.487199246883392334e-01 9.287942051887512207e-01 +6.599474906921386719e+00 -2.666633796691894531e+01 -1.908085942268371582e+00 1.361834555864334106e-01 1.770585030317306519e-02 3.689627945423126221e-01 9.192425608634948730e-01 +6.370777606964111328e+00 -2.657961273193359375e+01 -1.817972421646118164e+00 1.471050679683685303e-01 1.917048171162605286e-02 3.881823122501373291e-01 9.095642566680908203e-01 +6.139701843261718750e+00 -2.650517082214355469e+01 -1.749771714210510254e+00 1.569896787405014038e-01 2.053925022482872009e-02 4.062187373638153076e-01 8.999547958374023438e-01 +5.910547256469726562e+00 -2.644154167175292969e+01 -1.696130275726318359e+00 1.656711250543594360e-01 2.179830893874168396e-02 4.229246973991394043e-01 8.906247615814208984e-01 +5.684411525726318359e+00 -2.639022445678710938e+01 -1.656192541122436523e+00 1.729882657527923584e-01 2.293346077203750610e-02 4.381606578826904297e-01 8.817959427833557129e-01 +5.464765071868896484e+00 -2.634597015380859375e+01 -1.622294902801513672e+00 1.787836253643035889e-01 2.393117547035217285e-02 4.517953991889953613e-01 8.736959099769592285e-01 +5.251664161682128906e+00 -2.630884170532226562e+01 -1.594280958175659180e+00 1.825749278068542480e-01 2.460363134741783142e-02 4.637119174003601074e-01 8.666211366653442383e-01 +5.046442508697509766e+00 -2.627592277526855469e+01 -1.568546056747436523e+00 1.834198236465454102e-01 2.448996528983116150e-02 4.738091528415679932e-01 8.609658479690551758e-01 +4.848206520080566406e+00 -2.625026321411132812e+01 -1.548382520675659180e+00 1.838009655475616455e-01 2.502397820353507996e-02 4.818847477436065674e-01 8.563749194145202637e-01 +4.658301830291748047e+00 -2.622618103027343750e+01 -1.529111266136169434e+00 1.836267709732055664e-01 2.628898248076438904e-02 4.877998232841491699e-01 8.530189990997314453e-01 +4.476706981658935547e+00 -2.620547866821289062e+01 -1.510836124420166016e+00 1.795126795768737793e-01 2.640318125486373901e-02 4.915642440319061279e-01 8.517292737960815430e-01 +4.302931308746337891e+00 -2.619043922424316406e+01 -1.495709180831909180e+00 1.732770353555679321e-01 2.629615366458892822e-02 4.932430088520050049e-01 8.520532846450805664e-01 +4.137679100036621094e+00 -2.617677116394042969e+01 -1.480880141258239746e+00 1.651134490966796875e-01 2.594937756657600403e-02 4.929910898208618164e-01 8.538290262222290039e-01 +3.980953931808471680e+00 -2.616441345214843750e+01 -1.466370820999145508e+00 1.552121192216873169e-01 2.534341439604759216e-02 4.909519553184509277e-01 8.568739891052246094e-01 +3.832751274108886719e+00 -2.615327072143554688e+01 -1.452200889587402344e+00 1.437613666057586670e-01 2.445927262306213379e-02 4.872626960277557373e-01 8.609933257102966309e-01 +3.692717790603637695e+00 -2.614628410339355469e+01 -1.440113544464111328e+00 1.309500336647033691e-01 2.327736094594001770e-02 4.820578396320343018e-01 8.659853339195251465e-01 +3.561160087585449219e+00 -2.614063453674316406e+01 -1.428563237190246582e+00 1.169686764478683472e-01 2.177853137254714966e-02 4.754727780818939209e-01 8.716476559638977051e-01 +3.438129901885986328e+00 -2.613575172424316406e+01 -1.417299747467041016e+00 1.020105704665184021e-01 1.994415000081062317e-02 4.676474928855895996e-01 8.777823448181152344e-01 +3.323622465133666992e+00 -2.613155174255371094e+01 -1.406351327896118164e+00 8.627232909202575684e-02 1.775621995329856873e-02 4.587280750274658203e-01 8.842004537582397461e-01 +3.217639923095703125e+00 -2.612795257568359375e+01 -1.395756840705871582e+00 6.995402276515960693e-02 1.519817486405372620e-02 4.488692879676818848e-01 8.907254338264465332e-01 +3.120190143585205078e+00 -2.612490653991699219e+01 -1.385557889938354492e+00 5.325971171259880066e-02 1.225320342928171158e-02 4.382355511188507080e-01 8.971971869468688965e-01 +3.031288385391235352e+00 -2.612232780456542969e+01 -1.375803232192993164e+00 3.639610856771469116e-02 8.906225673854351044e-03 4.270016551017761230e-01 9.034742116928100586e-01 +2.950957059860229492e+00 -2.612017059326171875e+01 -1.366545438766479492e+00 1.957202330231666565e-02 5.143407732248306274e-03 4.153527021408081055e-01 9.094352722167968750e-01 +2.879151344299316406e+00 -2.611909103393554688e+01 -1.358444809913635254e+00 2.997935982421040535e-03 9.512035176157951355e-04 4.034842848777770996e-01 9.149811863899230957e-01 +2.815986633300781250e+00 -2.611833000183105469e+01 -1.350934982299804688e+00 -1.311498880386352539e-02 -3.683640155941247940e-03 3.916012048721313477e-01 9.200341701507568359e-01 +2.761515855789184570e+00 -2.611777305603027344e+01 -1.344009995460510254e+00 -2.855683118104934692e-02 -8.773547597229480743e-03 3.799151778221130371e-01 9.245388507843017578e-01 +2.715790271759033203e+00 -2.611742591857910156e+01 -1.337728261947631836e+00 -4.311827197670936584e-02 -1.433096732944250107e-02 3.686465024948120117e-01 9.284585118293762207e-01 +2.678865909576416016e+00 -2.611726570129394531e+01 -1.332148432731628418e+00 -5.659235641360282898e-02 -2.036875113844871521e-02 3.580188453197479248e-01 9.317751526832580566e-01 +2.650802850723266602e+00 -2.611730003356933594e+01 -1.327322959899902344e+00 -6.877423077821731567e-02 -2.690066583454608917e-02 3.482596874237060547e-01 9.344847798347473145e-01 +2.631665229797363281e+00 -2.611752891540527344e+01 -1.323305606842041016e+00 -7.946231216192245483e-02 -3.394139930605888367e-02 3.395984470844268799e-01 9.365930557250976562e-01 +2.621506929397583008e+00 -2.611796760559082031e+01 -1.320130586624145508e+00 -8.851067721843719482e-02 -4.149623960256576538e-02 3.322108387947082520e-01 9.381257891654968262e-01 +2.604746103286743164e+00 -2.611786651611328125e+01 -1.316929936408996582e+00 -9.599139541387557983e-02 -4.952628165483474731e-02 3.260566592216491699e-01 9.391590952873229980e-01 +2.581374406814575195e+00 -2.611726570129394531e+01 -1.313673019409179688e+00 -1.020307838916778564e-01 -5.798066779971122742e-02 3.210361599922180176e-01 9.397679567337036133e-01 +2.551380872726440430e+00 -2.611620140075683594e+01 -1.310332059860229492e+00 -1.067542657256126404e-01 -6.680898368358612061e-02 3.170435726642608643e-01 9.400123953819274902e-01 +2.514750719070434570e+00 -2.611468696594238281e+01 -1.306879878044128418e+00 -1.102860048413276672e-01 -7.595979422330856323e-02 3.139690458774566650e-01 9.399418234825134277e-01 +2.471467494964599609e+00 -2.611276245117187500e+01 -1.303287267684936523e+00 -1.127503067255020142e-01 -8.538196235895156860e-02 3.116994798183441162e-01 9.395960569381713867e-01 +2.421512603759765625e+00 -2.611042404174804688e+01 -1.299526333808898926e+00 -1.142703592777252197e-01 -9.502364695072174072e-02 3.101196289062500000e-01 9.390093684196472168e-01 +2.376385927200317383e+00 -2.610828590393066406e+01 -1.296202421188354492e+00 -1.149689331650733948e-01 -1.048334240913391113e-01 3.091127574443817139e-01 9.382117986679077148e-01 +2.336065053939819336e+00 -2.610634613037109375e+01 -1.293288588523864746e+00 -1.149692237377166748e-01 -1.147588342428207397e-01 3.085614442825317383e-01 9.372311830520629883e-01 +2.300527811050415039e+00 -2.610463714599609375e+01 -1.290760517120361328e+00 -1.143935322761535645e-01 -1.247479841113090515e-01 3.083480596542358398e-01 9.360948801040649414e-01 +2.269750118255615234e+00 -2.610315322875976562e+01 -1.288591265678405762e+00 -1.133648008108139038e-01 -1.347490549087524414e-01 3.083551526069641113e-01 9.348304867744445801e-01 +2.243707180023193359e+00 -2.610190773010253906e+01 -1.286761403083801270e+00 -1.120056807994842529e-01 -1.447095274925231934e-01 3.084664642810821533e-01 9.334679245948791504e-01 +2.222373247146606445e+00 -2.610091781616210938e+01 -1.285245299339294434e+00 -1.104394048452377319e-01 -1.545778214931488037e-01 3.085660040378570557e-01 9.320386052131652832e-01 +2.205722808837890625e+00 -2.610018539428710938e+01 -1.284022212028503418e+00 -1.087885349988937378e-01 -1.643026769161224365e-01 3.085390627384185791e-01 9.305768609046936035e-01 +2.193727970123291016e+00 -2.609972190856933594e+01 -1.283072471618652344e+00 -1.071762964129447937e-01 -1.738324314355850220e-01 3.082725405693054199e-01 9.291197657585144043e-01 +2.186362266540527344e+00 -2.609954452514648438e+01 -1.282379150390625000e+00 -1.057260483503341675e-01 -1.831168383359909058e-01 3.076536953449249268e-01 9.277065396308898926e-01 +2.183596372604370117e+00 -2.609965705871582031e+01 -1.281921386718750000e+00 -1.045607924461364746e-01 -1.921051144599914551e-01 3.065711855888366699e-01 9.263783693313598633e-01 +2.178739786148071289e+00 -2.609973526000976562e+01 -1.281318306922912598e+00 -1.038029193878173828e-01 -2.007473111152648926e-01 3.049142658710479736e-01 9.251772165298461914e-01 +2.171762704849243164e+00 -2.609978866577148438e+01 -1.280552983283996582e+00 -1.035755872726440430e-01 -2.089937329292297363e-01 3.025719523429870605e-01 9.241449236869812012e-01 +2.162633657455444336e+00 -2.609983253479003906e+01 -1.279610514640808105e+00 -1.040007025003433228e-01 -2.167947590351104736e-01 2.994336187839508057e-01 9.233219027519226074e-01 +2.151756286621093750e+00 -2.609991073608398438e+01 -1.279266357421875000e+00 -1.018563807010650635e-01 -2.230551093816757202e-01 2.962332963943481445e-01 9.231020808219909668e-01 +2.138787031173706055e+00 -2.609995079040527344e+01 -1.278807401657104492e+00 -1.000821962952613831e-01 -2.287934869527816772e-01 2.924018502235412598e-01 9.231132864952087402e-01 +2.123752832412719727e+00 -2.609994125366210938e+01 -1.278233647346496582e+00 -9.863399714231491089e-02 -2.340759038925170898e-01 2.880798876285552979e-01 9.233037829399108887e-01 +2.106680870056152344e+00 -2.609985733032226562e+01 -1.277545094490051270e+00 -9.746373444795608521e-02 -2.389639019966125488e-01 2.834067344665527344e-01 9.236220121383666992e-01 +2.087599992752075195e+00 -2.609968185424804688e+01 -1.276743173599243164e+00 -9.652115404605865479e-02 -2.435137331485748291e-01 2.785216569900512695e-01 9.240186214447021484e-01 +2.066539525985717773e+00 -2.609939956665039062e+01 -1.275826334953308105e+00 -9.575416892766952515e-02 -2.477771490812301636e-01 2.735641896724700928e-01 9.244459271430969238e-01 +2.043530464172363281e+00 -2.609897804260253906e+01 -1.274796128273010254e+00 -9.510961920022964478e-02 -2.518011033535003662e-01 2.686747014522552490e-01 9.248589873313903809e-01 +2.018604755401611328e+00 -2.609842681884765625e+01 -1.273653507232666016e+00 -9.453330934047698975e-02 -2.556293010711669922e-01 2.639941573143005371e-01 9.252157807350158691e-01 +1.991794824600219727e+00 -2.609771347045898438e+01 -1.272398710250854492e+00 -9.397020936012268066e-02 -2.593019306659698486e-01 2.596642374992370605e-01 9.254763126373291016e-01 +1.963134527206420898e+00 -2.609683036804199219e+01 -1.271032691001892090e+00 -9.336430579423904419e-02 -2.628570795059204102e-01 2.558271884918212891e-01 9.256033897399902344e-01 +1.932657837867736816e+00 -2.609576606750488281e+01 -1.269554376602172852e+00 -9.265825897455215454e-02 -2.663317620754241943e-01 2.526248395442962646e-01 9.255605936050415039e-01 +1.900395274162292480e+00 -2.609452629089355469e+01 -1.268021225929260254e+00 -9.179296344518661499e-02 -2.697627544403076172e-01 2.501989006996154785e-01 9.253121614456176758e-01 +1.866372346878051758e+00 -2.609314346313476562e+01 -1.266556382179260254e+00 -9.070674329996109009e-02 -2.731886208057403564e-01 2.486893981695175171e-01 9.248208999633789062e-01 +1.830633640289306641e+00 -2.609154319763183594e+01 -1.264996290206909180e+00 -8.933471143245697021e-02 -2.766507267951965332e-01 2.482342422008514404e-01 9.240472912788391113e-01 +1.790276765823364258e+00 -2.608957481384277344e+01 -1.263203144073486328e+00 -8.760775625705718994e-02 -2.801944017410278320e-01 2.489677965641021729e-01 9.229469299316406250e-01 +1.745332121849060059e+00 -2.608722686767578125e+01 -1.261175513267517090e+00 -8.545089513063430786e-02 -2.838713824748992920e-01 2.510198652744293213e-01 9.214685559272766113e-01 +1.695828557014465332e+00 -2.608447265625000000e+01 -1.258919596672058105e+00 -8.278183639049530029e-02 -2.877405583858489990e-01 2.545136511325836182e-01 9.195516109466552734e-01 +1.641791701316833496e+00 -2.608129310607910156e+01 -1.256438016891479492e+00 -7.950858026742935181e-02 -2.918704450130462646e-01 2.595636546611785889e-01 9.171241521835327148e-01 +1.583243012428283691e+00 -2.607766532897949219e+01 -1.253734111785888672e+00 -7.552697509527206421e-02 -2.963385283946990967e-01 2.662736177444458008e-01 9.140993356704711914e-01 +1.520200014114379883e+00 -2.607355880737304688e+01 -1.250813007354736328e+00 -7.071685791015625000e-02 -3.012339174747467041e-01 2.747328281402587891e-01 9.103729724884033203e-01 +1.454235196113586426e+00 -2.606877899169921875e+01 -1.249844908714294434e+00 -5.525906383991241455e-02 -3.035594820976257324e-01 2.882252037525177002e-01 9.064901471138000488e-01 +1.383903503417968750e+00 -2.606328582763671875e+01 -1.248920917510986328e+00 -3.777214884757995605e-02 -3.056705296039581299e-01 3.037523031234741211e-01 9.015948772430419922e-01 +1.309079766273498535e+00 -2.605702018737792969e+01 -1.247990727424621582e+00 -1.855715364217758179e-02 -3.074791133403778076e-01 3.209738135337829590e-01 8.955936431884765625e-01 +1.229634761810302734e+00 -2.604996109008789062e+01 -1.246994614601135254e+00 2.079017460346221924e-03 -3.089032173156738281e-01 3.395516574382781982e-01 8.884138464927673340e-01 +1.145437955856323242e+00 -2.604207992553710938e+01 -1.245875239372253418e+00 2.382044494152069092e-02 -3.098701834678649902e-01 3.591489195823669434e-01 8.800143003463745117e-01 +1.056360840797424316e+00 -2.603338813781738281e+01 -1.244570255279541016e+00 4.634601622819900513e-02 -3.103204071521759033e-01 3.794378042221069336e-01 8.703909516334533691e-01 +9.622811079025268555e-01 -2.602390480041503906e+01 -1.243022441864013672e+00 6.933062523603439331e-02 -3.102084100246429443e-01 4.001006484031677246e-01 8.595832586288452148e-01 +8.630869388580322266e-01 -2.601369476318359375e+01 -1.241176724433898926e+00 9.244732558727264404e-02 -3.095055222511291504e-01 4.208358526229858398e-01 8.476773500442504883e-01 +7.586755752563476562e-01 -2.600251388549804688e+01 -1.239426255226135254e+00 1.153714805841445923e-01 -3.082002401351928711e-01 4.413614571094512939e-01 8.348065614700317383e-01 +6.489708423614501953e-01 -2.599065780639648438e+01 -1.237429141998291016e+00 1.377833187580108643e-01 -3.062991797924041748e-01 4.614176154136657715e-01 8.211518526077270508e-01 +5.339149236679077148e-01 -2.597833442687988281e+01 -1.235021948814392090e+00 1.593710333108901978e-01 -3.038252592086791992e-01 4.807699918746948242e-01 8.069394826889038086e-01 +4.134708344936370850e-01 -2.596566772460937500e+01 -1.232172846794128418e+00 1.798333376646041870e-01 -3.008187711238861084e-01 4.992105662822723389e-01 7.924372553825378418e-01 +2.876244187355041504e-01 -2.595279312133789062e+01 -1.228863477706909180e+00 1.988817751407623291e-01 -2.973341047763824463e-01 5.165591239929199219e-01 7.779493331909179688e-01 +1.563831120729446411e-01 -2.593984222412109375e+01 -1.225079298019409180e+00 2.162414491176605225e-01 -2.934379577636718750e-01 5.326616168022155762e-01 7.638098597526550293e-01 +1.977386511862277985e-02 -2.592696762084960938e+01 -1.220815420150756836e+00 2.316501736640930176e-01 -2.892060577869415283e-01 5.473881959915161133e-01 7.503760457038879395e-01 +-1.221602037549018860e-01 -2.591429710388183594e+01 -1.216070532798767090e+00 2.448578178882598877e-01 -2.847204804420471191e-01 5.606288909912109375e-01 7.380204200744628906e-01 +-2.693642973899841309e-01 -2.590196228027343750e+01 -1.210849523544311523e+00 2.556236982345581055e-01 -2.800659835338592529e-01 5.722882151603698730e-01 7.271215915679931641e-01 +-4.217575490474700928e-01 -2.588953018188476562e+01 -1.205434560775756836e+00 2.637114226818084717e-01 -2.753245532512664795e-01 5.822781920433044434e-01 7.180562615394592285e-01 +-5.792719125747680664e-01 -2.587693214416503906e+01 -1.199920654296875000e+00 2.688854634761810303e-01 -2.705728113651275635e-01 5.905099511146545410e-01 7.111884951591491699e-01 +-7.418780326843261719e-01 -2.586498069763183594e+01 -1.193951368331909180e+00 2.709034085273742676e-01 -2.658755183219909668e-01 5.968830585479736328e-01 7.068607807159423828e-01 +-9.095315337181091309e-01 -2.585373878479003906e+01 -1.187517046928405762e+00 2.696073949337005615e-01 -2.612811923027038574e-01 6.013295054435729980e-01 7.052990794181823730e-01 +-1.082196712493896484e+00 -2.584315872192382812e+01 -1.180628657341003418e+00 2.652037143707275391e-01 -2.568131983280181885e-01 6.039624810218811035e-01 7.063591480255126953e-01 +-1.259857892990112305e+00 -2.583313941955566406e+01 -1.173294663429260254e+00 2.579801678657531738e-01 -2.524796426296234131e-01 6.049149036407470703e-01 7.097733616828918457e-01 +-1.442517638206481934e+00 -2.582359313964843750e+01 -1.165510177612304688e+00 2.482134401798248291e-01 -2.482767254114151001e-01 6.042959094047546387e-01 7.152449488639831543e-01 +-1.630190968513488770e+00 -2.581442260742187500e+01 -1.157275319099426270e+00 2.361755520105361938e-01 -2.441955357789993286e-01 6.021990776062011719e-01 7.224583029747009277e-01 +-1.822792649269104004e+00 -2.580361747741699219e+01 -1.149105191230773926e+00 2.221380621194839478e-01 -2.402243912220001221e-01 5.987128615379333496e-01 7.310880422592163086e-01 +-2.020425319671630859e+00 -2.579247474670410156e+01 -1.140615224838256836e+00 2.063753902912139893e-01 -2.363522201776504517e-01 5.939273834228515625e-01 7.408083677291870117e-01 +-2.223135709762573242e+00 -2.578133201599121094e+01 -1.131688237190246582e+00 1.891683191061019897e-01 -2.325716316699981689e-01 5.879410505294799805e-01 7.512996196746826172e-01 +-2.430940866470336914e+00 -2.577008819580078125e+01 -1.122332692146301270e+00 1.708054840564727783e-01 -2.288807183504104614e-01 5.808661580085754395e-01 7.622555494308471680e-01 +-2.643848896026611328e+00 -2.575863647460937500e+01 -1.112574458122253418e+00 1.515839397907257080e-01 -2.252849787473678589e-01 5.728331804275512695e-01 7.733894586563110352e-01 +-2.861857891082763672e+00 -2.574687385559082031e+01 -1.102440118789672852e+00 1.318101584911346436e-01 -2.217981219291687012e-01 5.639927983283996582e-01 7.844384908676147461e-01 +-3.084932088851928711e+00 -2.573441886901855469e+01 -1.092018961906433105e+00 1.117970794439315796e-01 -2.184428274631500244e-01 5.545181632041931152e-01 7.951689958572387695e-01 +-3.312824249267578125e+00 -2.571818351745605469e+01 -1.081887125968933105e+00 9.186533093452453613e-02 -2.152512967586517334e-01 5.446047186851501465e-01 8.053777217864990234e-01 +-3.545735597610473633e+00 -2.570132827758789062e+01 -1.071532011032104492e+00 7.233910262584686279e-02 -2.122652828693389893e-01 5.344696044921875000e-01 8.148942589759826660e-01 +-3.783617496490478516e+00 -2.568376922607421875e+01 -1.061015605926513672e+00 5.354552716016769409e-02 -2.095348089933395386e-01 5.243495106697082520e-01 8.235809803009033203e-01 +-4.026412487030029297e+00 -2.566546249389648438e+01 -1.050401568412780762e+00 3.581195324659347534e-02 -2.071186453104019165e-01 5.144988298416137695e-01 8.313304185867309570e-01 +-4.274055004119873047e+00 -2.564637565612792969e+01 -1.039759516716003418e+00 1.946479082107543945e-02 -2.050815224647521973e-01 5.051854252815246582e-01 8.380634784698486328e-01 +-4.526473522186279297e+00 -2.562646865844726562e+01 -1.029154062271118164e+00 4.827596247196197510e-03 -2.034938782453536987e-01 4.966876506805419922e-01 8.437229394912719727e-01 +-4.783144950866699219e+00 -2.560096168518066406e+01 -1.019245624542236328e+00 -7.779009640216827393e-03 -2.024299055337905884e-01 4.892896711826324463e-01 8.482671976089477539e-01 +-5.044416904449462891e+00 -2.557433128356933594e+01 -1.009541034698486328e+00 -1.803756505250930786e-02 -2.019653618335723877e-01 4.832766652107238770e-01 8.516620397567749023e-01 +-5.302582263946533203e+00 -2.554758262634277344e+01 -1.000302672386169434e+00 -2.571143954992294312e-02 -2.021553814411163330e-01 4.788711369037628174e-01 8.539054393768310547e-01 +-5.557634353637695312e+00 -2.552076148986816406e+01 -9.915307164192199707e-01 -3.087937086820602417e-02 -2.029705345630645752e-01 4.760487377643585205e-01 8.551180958747863770e-01 +-5.809582233428955078e+00 -2.549390983581542969e+01 -9.832091927528381348e-01 -3.369780629873275757e-02 -2.043549120426177979e-01 4.747093617916107178e-01 8.554264307022094727e-01 +-6.058428287506103516e+00 -2.546691322326660156e+01 -9.753307700157165527e-01 -3.432291001081466675e-02 -2.062465548515319824e-01 4.747377634048461914e-01 8.549318313598632812e-01 +-6.303567409515380859e+00 -2.543446159362792969e+01 -9.683629870414733887e-01 -3.290986269712448120e-02 -2.085783779621124268e-01 4.760079979896545410e-01 8.537144064903259277e-01 +-6.557874202728271484e+00 -2.540054130554199219e+01 -9.614318609237670898e-01 -2.961410582065582275e-02 -2.112799137830734253e-01 4.783855676651000977e-01 8.518398404121398926e-01 +-6.821374893188476562e+00 -2.536515998840332031e+01 -9.545104503631591797e-01 -2.458949387073516846e-02 -2.142781317234039307e-01 4.817292094230651855e-01 8.493627309799194336e-01 +-7.094101905822753906e+00 -2.532833862304687500e+01 -9.475768804550170898e-01 -1.799146831035614014e-02 -2.174982428550720215e-01 4.858947098255157471e-01 8.463315367698669434e-01 +-7.376088142395019531e+00 -2.529010200500488281e+01 -9.406054615974426270e-01 -9.974963963031768799e-03 -2.208639681339263916e-01 4.907353818416595459e-01 8.427920341491699219e-01 +-7.667158603668212891e+00 -2.524897003173828125e+01 -9.337072372436523438e-01 -6.955191493034362793e-04 -2.242999076843261719e-01 4.961045384407043457e-01 8.387904167175292969e-01 +-7.959429264068603516e+00 -2.520267486572265625e+01 -9.273742437362670898e-01 9.689696133136749268e-03 -2.277305126190185547e-01 5.018569231033325195e-01 8.343767523765563965e-01 +-8.253588676452636719e+00 -2.515594100952148438e+01 -9.211474657058715820e-01 2.102287113666534424e-02 -2.310820966958999634e-01 5.078500509262084961e-01 8.296068310737609863e-01 +-8.541360855102539062e+00 -2.511005783081054688e+01 -9.152233600616455078e-01 3.314618766307830811e-02 -2.342820912599563599e-01 5.139456987380981445e-01 8.245441317558288574e-01 +-8.822777748107910156e+00 -2.506504249572753906e+01 -9.095849394798278809e-01 4.589994251728057861e-02 -2.372606992721557617e-01 5.200105309486389160e-01 8.192616105079650879e-01 +-9.097865104675292969e+00 -2.502093696594238281e+01 -9.042126536369323730e-01 5.912540107965469360e-02 -2.399505525827407837e-01 5.259176492691040039e-01 8.138417601585388184e-01 +-9.365920066833496094e+00 -2.497324180603027344e+01 -8.995105028152465820e-01 7.266320288181304932e-02 -2.422876656055450439e-01 5.315462946891784668e-01 8.083781599998474121e-01 +-9.627545356750488281e+00 -2.492558479309082031e+01 -8.951293826103210449e-01 8.635501563549041748e-02 -2.442109286785125732e-01 5.367828607559204102e-01 8.029744625091552734e-01 +-9.882925987243652344e+00 -2.487905693054199219e+01 -8.909606933593750000e-01 1.000431627035140991e-01 -2.456623315811157227e-01 5.415208935737609863e-01 7.977446317672729492e-01 +-1.013208103179931641e+01 -2.483370018005371094e+01 -8.869934082031250000e-01 1.135715693235397339e-01 -2.465868890285491943e-01 5.456603169441223145e-01 7.928122282028198242e-01 +-1.037502384185791016e+01 -2.478955459594726562e+01 -8.832201957702636719e-01 1.267857998609542847e-01 -2.469325810670852661e-01 5.491075515747070312e-01 7.883086204528808594e-01 +-1.061176395416259766e+01 -2.474665451049804688e+01 -8.796362280845642090e-01 1.395600289106369019e-01 -2.466690540313720703e-01 5.517964959144592285e-01 7.843455076217651367e-01 +-1.084166145324707031e+01 -2.470154762268066406e+01 -8.765624761581420898e-01 1.518780887126922607e-01 -2.458456903696060181e-01 5.537524223327636719e-01 7.809297442436218262e-01 +-1.106510353088378906e+01 -2.465637207031250000e+01 -8.737902641296386719e-01 1.637502014636993408e-01 -2.445301562547683716e-01 5.550203323364257812e-01 7.780380845069885254e-01 +-1.128235054016113281e+01 -2.461257743835449219e+01 -8.711816072463989258e-01 1.751865893602371216e-01 -2.427901923656463623e-01 5.556436181068420410e-01 7.756434082984924316e-01 +-1.149339485168457031e+01 -2.457016563415527344e+01 -8.687292337417602539e-01 1.861974149942398071e-01 -2.406913191080093384e-01 5.556635260581970215e-01 7.737158536911010742e-01 +-1.169823074340820312e+01 -2.452912521362304688e+01 -8.664233088493347168e-01 1.967928707599639893e-01 -2.382993102073669434e-01 5.551197528839111328e-01 7.722227573394775391e-01 +-1.189685535430908203e+01 -2.448945236206054688e+01 -8.642578125000000000e-01 2.069828212261199951e-01 -2.356788516044616699e-01 5.540509819984436035e-01 7.711297273635864258e-01 +-1.208925914764404297e+01 -2.445113754272460938e+01 -8.622229099273681641e-01 2.167773693799972534e-01 -2.328945249319076538e-01 5.524944663047790527e-01 7.704008221626281738e-01 +-1.227489948272705078e+01 -2.441156768798828125e+01 -8.605554103851318359e-01 2.261860370635986328e-01 -2.300098091363906860e-01 5.504872798919677734e-01 7.699993848800659180e-01 +-1.245398521423339844e+01 -2.437176132202148438e+01 -8.591491580009460449e-01 2.352190017700195312e-01 -2.270886003971099854e-01 5.480658411979675293e-01 7.698873877525329590e-01 +-1.262686634063720703e+01 -2.433344650268554688e+01 -8.578307628631591797e-01 2.438857853412628174e-01 -2.241941392421722412e-01 5.452659130096435547e-01 7.700272202491760254e-01 +-1.280683422088623047e+01 -2.429367637634277344e+01 -8.563159108161926270e-01 2.521966099739074707e-01 -2.213897407054901123e-01 5.421235561370849609e-01 7.703801989555358887e-01 +-1.299388980865478516e+01 -2.425245094299316406e+01 -8.545935153961181641e-01 2.601614594459533691e-01 -2.187384665012359619e-01 5.386744737625122070e-01 7.709079980850219727e-01 +-1.318802261352539062e+01 -2.420975112915039062e+01 -8.526562452316284180e-01 2.677903175354003906e-01 -2.163032144308090210e-01 5.349546074867248535e-01 7.715730667114257812e-01 +-1.338922119140625000e+01 -2.416558074951171875e+01 -8.504919409751892090e-01 2.750933170318603516e-01 -2.141466438770294189e-01 5.309993624687194824e-01 7.723371386528015137e-01 +-1.359730148315429688e+01 -2.411916542053222656e+01 -8.481615781784057617e-01 2.820808291435241699e-01 -2.123317122459411621e-01 5.268448591232299805e-01 7.731623649597167969e-01 +-1.381124687194824219e+01 -2.406614685058593750e+01 -8.460729718208312988e-01 2.887633442878723145e-01 -2.109213173389434814e-01 5.225268006324768066e-01 7.740113139152526855e-01 +-1.403218841552734375e+01 -2.401143455505371094e+01 -8.437451124191284180e-01 2.951512634754180908e-01 -2.099776864051818848e-01 5.180809497833251953e-01 7.748466134071350098e-01 +-1.426011848449707031e+01 -2.395502471923828125e+01 -8.411706089973449707e-01 3.012549281120300293e-01 -2.095633149147033691e-01 5.135427117347717285e-01 7.756304144859313965e-01 +-1.449502277374267578e+01 -2.389689826965332031e+01 -8.383386135101318359e-01 3.070848882198333740e-01 -2.097403109073638916e-01 5.089473724365234375e-01 7.763249278068542480e-01 +-1.473693466186523438e+01 -2.383842658996582031e+01 -8.338268995285034180e-01 3.065032660961151123e-01 -2.145159691572189331e-01 5.026563405990600586e-01 7.793427705764770508e-01 +-1.498472881317138672e+01 -2.377401351928710938e+01 -8.295714855194091797e-01 3.060118556022644043e-01 -2.194902896881103516e-01 4.964650571346282959e-01 7.821146249771118164e-01 +-1.523827362060546875e+01 -2.370317268371582031e+01 -8.256250023841857910e-01 3.055872321128845215e-01 -2.245676517486572266e-01 4.904325902462005615e-01 7.846412062644958496e-01 +-1.549872779846191406e+01 -2.363027381896972656e+01 -8.215686082839965820e-01 3.052128553390502930e-01 -2.296506762504577637e-01 4.846248924732208252e-01 7.869207262992858887e-01 +-1.576608371734619141e+01 -2.355529212951660156e+01 -8.174071907997131348e-01 3.048793077468872070e-01 -2.346402853727340698e-01 4.791148006916046143e-01 7.889497280120849609e-01 +-1.604001426696777344e+01 -2.347719192504882812e+01 -8.132445812225341797e-01 3.045835494995117188e-01 -2.394354343414306641e-01 4.739812910556793213e-01 7.907220125198364258e-01 +-1.631705474853515625e+01 -2.338483428955078125e+01 -8.101818561553955078e-01 3.043285310268402100e-01 -2.439338266849517822e-01 4.693088233470916748e-01 7.922308444976806641e-01 +-1.660086822509765625e+01 -2.329003334045410156e+01 -8.070617318153381348e-01 3.041211366653442383e-01 -2.480305284261703491e-01 4.651857912540435791e-01 7.934691309928894043e-01 +-1.688272476196289062e+01 -2.319570350646972656e+01 -8.039770126342773438e-01 3.039715886116027832e-01 -2.516188025474548340e-01 4.617031812667846680e-01 7.944301962852478027e-01 +-1.715821075439453125e+01 -2.309016036987304688e+01 -8.021142482757568359e-01 3.038906455039978027e-01 -2.545894980430603027e-01 4.589523375034332275e-01 7.951083183288574219e-01 +-1.742863082885742188e+01 -2.297690391540527344e+01 -8.011242747306823730e-01 3.038873672485351562e-01 -2.568305432796478271e-01 4.570226073265075684e-01 7.955004572868347168e-01 +-1.769711875915527344e+01 -2.286419296264648438e+01 -8.001745343208312988e-01 3.039654791355133057e-01 -2.582265436649322510e-01 4.559979438781738281e-01 7.956066131591796875e-01 +-1.795545768737792969e+01 -2.273483276367187500e+01 -8.009973168373107910e-01 3.041208386421203613e-01 -2.586601376533508301e-01 4.559538066387176514e-01 7.954316139221191406e-01 +-1.820840263366699219e+01 -2.259877395629882812e+01 -8.026000857353210449e-01 3.043361306190490723e-01 -2.580100297927856445e-01 4.569530785083770752e-01 7.949869632720947266e-01 +-1.845356178283691406e+01 -2.245384216308593750e+01 -8.052062988281250000e-01 3.045781552791595459e-01 -2.561534345149993896e-01 4.590417444705963135e-01 7.942910790443420410e-01 +-1.868462753295898438e+01 -2.228983306884765625e+01 -8.098449707031250000e-01 3.047925829887390137e-01 -2.529663443565368652e-01 4.622446596622467041e-01 7.933721542358398438e-01 +-1.890363311767578125e+01 -2.211425209045410156e+01 -8.157787919044494629e-01 3.049005568027496338e-01 -2.483250051736831665e-01 4.665615260601043701e-01 7.922693490982055664e-01 +-1.910454940795898438e+01 -2.192168426513671875e+01 -8.215343952178955078e-01 2.945684194564819336e-01 -2.481755763292312622e-01 4.688011407852172852e-01 7.948985695838928223e-01 +-1.927557182312011719e+01 -2.170585823059082031e+01 -8.294323682785034180e-01 2.825427353382110596e-01 -2.472493946552276611e-01 4.717763364315032959e-01 7.977871894836425781e-01 +-1.942508697509765625e+01 -2.146347045898437500e+01 -8.392358422279357910e-01 2.687639594078063965e-01 -2.454302906990051270e-01 4.755074381828308105e-01 8.008886575698852539e-01 +-1.954216575622558594e+01 -2.119265556335449219e+01 -8.509130477905273438e-01 2.531774640083312988e-01 -2.426455467939376831e-01 4.799710512161254883e-01 8.041468262672424316e-01 +-1.962533950805664062e+01 -2.090949630737304688e+01 -8.627063035964965820e-01 2.359070032835006714e-01 -2.389250248670578003e-01 4.850493669509887695e-01 8.074588775634765625e-01 +-1.969269943237304688e+01 -2.062216758728027344e+01 -8.727245926856994629e-01 2.171254158020019531e-01 -2.343276143074035645e-01 4.906017482280731201e-01 8.107138276100158691e-01 +-1.976142501831054688e+01 -2.033530235290527344e+01 -8.793127536773681641e-01 1.970101296901702881e-01 -2.289136946201324463e-01 4.964909851551055908e-01 8.138071894645690918e-01 +-1.983432769775390625e+01 -2.004959869384765625e+01 -8.815551400184631348e-01 1.757451593875885010e-01 -2.227488011121749878e-01 5.025841593742370605e-01 8.166429996490478516e-01 +-1.991426658630371094e+01 -1.976594161987304688e+01 -8.786755204200744629e-01 1.535205245018005371e-01 -2.159026265144348145e-01 5.087547302246093750e-01 8.191374540328979492e-01 +-2.000371360778808594e+01 -1.948537635803222656e+01 -8.701708912849426270e-01 1.305329352617263794e-01 -2.084505409002304077e-01 5.148843526840209961e-01 8.212208151817321777e-01 +-2.010437202453613281e+01 -1.920896911621093750e+01 -8.559069633483886719e-01 1.069843769073486328e-01 -2.004730701446533203e-01 5.208641290664672852e-01 8.228398561477661133e-01 +-2.021696090698242188e+01 -1.893766021728515625e+01 -8.361364603042602539e-01 8.308219909667968750e-02 -1.920559257268905640e-01 5.265967249870300293e-01 8.239585757255554199e-01 +-2.034121322631835938e+01 -1.867202568054199219e+01 -8.114489316940307617e-01 5.903753638267517090e-02 -1.832901090383529663e-01 5.319957137107849121e-01 8.245604038238525391e-01 +-2.047609901428222656e+01 -1.841223526000976562e+01 -7.826293706893920898e-01 3.506408631801605225e-02 -1.742717623710632324e-01 5.369876623153686523e-01 8.246477842330932617e-01 +-2.062051963806152344e+01 -1.815816879272460938e+01 -7.515124082565307617e-01 1.137626916170120239e-02 -1.651008129119873047e-01 5.415123105049133301e-01 8.242430686950683594e-01 +-2.077400016784667969e+01 -1.790994644165039062e+01 -7.193176150321960449e-01 -1.181076467037200928e-02 -1.558807641267776489e-01 5.455222725868225098e-01 8.233875632286071777e-01 +-2.093643760681152344e+01 -1.766792488098144531e+01 -6.869445443153381348e-01 -3.428380936384201050e-02 -1.467182040214538574e-01 5.489829778671264648e-01 8.221411108970642090e-01 +-2.110804367065429688e+01 -1.743272018432617188e+01 -6.551440358161926270e-01 -5.583245679736137390e-02 -1.377217173576354980e-01 5.518721938133239746e-01 8.205806016921997070e-01 +-2.128930091857910156e+01 -1.720520401000976562e+01 -6.246276497840881348e-01 -7.624924182891845703e-02 -1.290009617805480957e-01 5.541790723800659180e-01 8.187981843948364258e-01 +-2.148101425170898438e+01 -1.698668479919433594e+01 -5.961560010910034180e-01 -9.533132612705230713e-02 -1.206667348742485046e-01 5.559023618698120117e-01 8.168990612030029297e-01 +-2.168679428100585938e+01 -1.678162574768066406e+01 -5.714086890220642090e-01 -1.128805875778198242e-01 -1.128291189670562744e-01 5.570487380027770996e-01 8.149995803833007812e-01 +-2.190575408935546875e+01 -1.659123039245605469e+01 -5.512145757675170898e-01 -1.287030577659606934e-01 -1.055976971983909607e-01 5.576310157775878906e-01 8.132233619689941406e-01 +-2.213914299011230469e+01 -1.641951560974121094e+01 -5.370470881462097168e-01 -1.426087766885757446e-01 -9.908163547515869141e-02 5.576655268669128418e-01 8.116985559463500977e-01 +-2.238475036621093750e+01 -1.626752853393554688e+01 -5.304577350616455078e-01 -1.490601301193237305e-01 -8.964521437883377075e-02 5.577902197837829590e-01 8.115508556365966797e-01 +-2.264039993286132812e+01 -1.613380813598632812e+01 -5.288525223731994629e-01 -1.544735133647918701e-01 -8.161737024784088135e-02 5.572797656059265137e-01 8.117362856864929199e-01 +-2.290334701538085938e+01 -1.601597213745117188e+01 -5.312219262123107910e-01 -1.589248329401016235e-01 -7.490587979555130005e-02 5.562464594841003418e-01 8.122325539588928223e-01 +-2.317114639282226562e+01 -1.591066360473632812e+01 -5.363464355468750000e-01 -1.624944806098937988e-01 -6.941533088684082031e-02 5.547821521759033203e-01 8.130152821540832520e-01 +-2.344164657592773438e+01 -1.581360816955566406e+01 -5.427783131599426270e-01 -1.652654111385345459e-01 -6.504709273576736450e-02 5.529615283012390137e-01 8.140575289726257324e-01 +-2.371278762817382812e+01 -1.571944808959960938e+01 -5.487646460533142090e-01 -1.673214584589004517e-01 -6.169995665550231934e-02 5.508458018302917480e-01 8.153315186500549316e-01 +-2.398210716247558594e+01 -1.562127399444580078e+01 -5.520458817481994629e-01 -1.687461286783218384e-01 -5.927060544490814209e-02 5.484846234321594238e-01 8.168085813522338867e-01 +-2.424491691589355469e+01 -1.550804615020751953e+01 -5.487365722656250000e-01 -1.696220040321350098e-01 -5.765402317047119141e-02 5.459191203117370605e-01 8.184599280357360840e-01 +-2.449951553344726562e+01 -1.537872505187988281e+01 -5.386352539062500000e-01 -1.700302809476852417e-01 -5.674361437559127808e-02 5.431839823722839355e-01 8.202565908432006836e-01 +-2.474444007873535156e+01 -1.523342704772949219e+01 -5.220702886581420898e-01 -1.700503081083297729e-01 -5.643201619386672974e-02 5.403098464012145996e-01 8.221699595451354980e-01 +-2.497766494750976562e+01 -1.507148361206054688e+01 -4.995800554752349854e-01 -1.697595268487930298e-01 -5.661123991012573242e-02 5.373245477676391602e-01 8.241718411445617676e-01 +-2.519788742065429688e+01 -1.489331054687500000e+01 -4.744763076305389404e-01 -1.692334264516830444e-01 -5.717277154326438904e-02 5.342547893524169922e-01 8.262342810630798340e-01 +-2.539336204528808594e+01 -1.468873500823974609e+01 -4.596862792968750000e-01 -1.685453206300735474e-01 -5.800805985927581787e-02 5.311273932456970215e-01 8.283303380012512207e-01 +-2.555798339843750000e+01 -1.445811462402343750e+01 -4.592394828796386719e-01 -1.677662283182144165e-01 -5.900888144969940186e-02 5.279706120491027832e-01 8.304332494735717773e-01 +-2.571812248229980469e+01 -1.422478961944580078e+01 -4.612707495689392090e-01 -1.669649779796600342e-01 -6.006729975342750549e-02 5.248143672943115234e-01 8.325169086456298828e-01 +-2.587863731384277344e+01 -1.399217700958251953e+01 -4.633276164531707764e-01 -1.662081480026245117e-01 -6.107582896947860718e-02 5.216907262802124023e-01 8.345557451248168945e-01 +-2.603939819335937500e+01 -1.376019477844238281e+01 -4.652734398841857910e-01 -1.655599474906921387e-01 -6.192769110202789307e-02 5.186341404914855957e-01 8.365246057510375977e-01 +-2.620061683654785156e+01 -1.352896499633789062e+01 -4.669726490974426270e-01 -1.650823801755905151e-01 -6.251683831214904785e-02 5.156816840171813965e-01 8.383983969688415527e-01 +-2.636240959167480469e+01 -1.329857921600341797e+01 -4.683166444301605225e-01 -1.648352891206741333e-01 -6.273782253265380859e-02 5.128720402717590332e-01 8.401520252227783203e-01 +-2.652549934387207031e+01 -1.306953620910644531e+01 -4.689233303070068359e-01 -1.648764610290527344e-01 -6.248602271080017090e-02 5.102450251579284668e-01 8.417608141899108887e-01 +-2.668920898437500000e+01 -1.284157180786132812e+01 -4.689306616783142090e-01 -1.635180413722991943e-01 -6.064473092555999756e-02 5.079550147056579590e-01 8.435435891151428223e-01 +-2.678941345214843750e+01 -1.259829521179199219e+01 -4.772912561893463135e-01 -1.627251207828521729e-01 -5.846070125699043274e-02 5.058341622352600098e-01 8.451240658760070801e-01 +-2.651661872863769531e+01 -1.259877395629882812e+01 -5.171887278556823730e-01 -1.624446660280227661e-01 -5.598696693778038025e-02 5.038542747497558594e-01 8.465270996093750000e-01 +-2.624497032165527344e+01 -1.265571308135986328e+01 -5.533349514007568359e-01 -1.626231074333190918e-01 -5.327646434307098389e-02 5.019860267639160156e-01 8.477767109870910645e-01 +-2.597594642639160156e+01 -1.272301197052001953e+01 -5.885253548622131348e-01 -1.632073819637298584e-01 -5.038213729858398438e-02 5.001997947692871094e-01 8.488964438438415527e-01 +-2.570717620849609375e+01 -1.279211902618408203e+01 -6.183996200561523438e-01 -1.641437411308288574e-01 -4.735671356320381165e-02 4.984661638736724854e-01 8.499091863632202148e-01 +-2.543681907653808594e+01 -1.285688400268554688e+01 -6.373022198677062988e-01 -1.653789579868316650e-01 -4.425322264432907104e-02 4.967552125453948975e-01 8.508382439613342285e-01 +-2.515522003173828125e+01 -1.291918945312500000e+01 -6.406725645065307617e-01 -1.668590009212493896e-01 -4.112435504794120789e-02 4.950375556945800781e-01 8.517069220542907715e-01 +-2.486792182922363281e+01 -1.299890136718750000e+01 -6.366809010505676270e-01 -1.685309559106826782e-01 -3.802309930324554443e-02 4.932837784290313721e-01 8.525389432907104492e-01 +-2.459251213073730469e+01 -1.309572219848632812e+01 -6.340332031250000000e-01 -1.703415215015411377e-01 -3.500250354409217834e-02 4.914650619029998779e-01 8.533584475517272949e-01 +-2.432781219482421875e+01 -1.320330047607421875e+01 -6.343395709991455078e-01 -1.722373217344284058e-01 -3.211538866162300110e-02 4.895527064800262451e-01 8.541902303695678711e-01 +-2.407213020324707031e+01 -1.331618118286132812e+01 -6.366015672683715820e-01 -1.741653680801391602e-01 -2.941481396555900574e-02 4.875183403491973877e-01 8.550596237182617188e-01 +-2.382385635375976562e+01 -1.343023872375488281e+01 -6.396130323410034180e-01 -1.760728061199188232e-01 -2.695365622639656067e-02 4.853337705135345459e-01 8.559924364089965820e-01 +-2.358245468139648438e+01 -1.354421329498291016e+01 -6.429601907730102539e-01 -1.779067516326904297e-01 -2.478495612740516663e-02 4.829712510108947754e-01 8.570144176483154297e-01 +-2.334757423400878906e+01 -1.365731906890869141e+01 -6.463440060615539551e-01 -1.796139925718307495e-01 -2.296158671379089355e-02 4.804029166698455811e-01 8.581519126892089844e-01 +-2.311899566650390625e+01 -1.376906681060791016e+01 -6.494702100753784180e-01 -1.811420321464538574e-01 -2.153661847114562988e-02 4.776009321212768555e-01 8.594307899475097656e-01 +-2.289647483825683594e+01 -1.387895011901855469e+01 -6.519653201103210449e-01 -1.824380159378051758e-01 -2.056293934583663940e-02 4.745368361473083496e-01 8.608764410018920898e-01 +-2.267963409423828125e+01 -1.398621082305908203e+01 -6.532312035560607910e-01 -1.834485381841659546e-01 -2.009310945868492126e-02 4.711823761463165283e-01 8.625138401985168457e-01 +-2.246773719787597656e+01 -1.408929157257080078e+01 -6.521801352500915527e-01 -1.841205060482025146e-01 -2.018003538250923157e-02 4.675078690052032471e-01 8.643661141395568848e-01 +-2.226006698608398438e+01 -1.418655204772949219e+01 -6.480712890625000000e-01 -1.844001263380050659e-01 -2.087630331516265869e-02 4.634829461574554443e-01 8.664549589157104492e-01 +-2.205663490295410156e+01 -1.427795410156250000e+01 -6.416552662849426270e-01 -1.835716813802719116e-01 -2.185546979308128357e-02 4.591004848480224609e-01 8.689364194869995117e-01 +-2.185772132873535156e+01 -1.436379337310791016e+01 -6.333520412445068359e-01 -1.824225485324859619e-01 -2.347820624709129333e-02 4.543474614620208740e-01 8.716301321983337402e-01 +-2.166368293762207031e+01 -1.444483852386474609e+01 -6.238781809806823730e-01 -1.810006201267242432e-01 -2.567527443170547485e-02 4.492349326610565186e-01 8.745098710060119629e-01 +-2.147487449645996094e+01 -1.452191352844238281e+01 -6.138256788253784180e-01 -1.793531924486160278e-01 -2.837654948234558105e-02 4.437734782695770264e-01 8.775489926338195801e-01 +-2.129187965393066406e+01 -1.459654712677001953e+01 -6.037365794181823730e-01 -1.775269359350204468e-01 -3.151117265224456787e-02 4.379730820655822754e-01 8.807217478752136230e-01 +-2.111501884460449219e+01 -1.466954517364501953e+01 -5.938305258750915527e-01 -1.755676269531250000e-01 -3.500741720199584961e-02 4.318441450595855713e-01 8.840028047561645508e-01 +-2.094495010375976562e+01 -1.474252891540527344e+01 -5.844531059265136719e-01 -1.735200583934783936e-01 -3.879258409142494202e-02 4.253970980644226074e-01 8.873687386512756348e-01 +-2.078098678588867188e+01 -1.481380367279052734e+01 -5.754565596580505371e-01 -1.714278608560562134e-01 -4.279293864965438843e-02 4.186428785324096680e-01 8.907969594001770020e-01 +-2.062461853027343750e+01 -1.488681602478027344e+01 -5.673596262931823730e-01 -1.693332791328430176e-01 -4.693398624658584595e-02 4.115937650203704834e-01 8.942673206329345703e-01 +-2.047404289245605469e+01 -1.495735359191894531e+01 -5.595715045928955078e-01 -1.672767847776412964e-01 -5.114042758941650391e-02 4.042624533176422119e-01 8.977610468864440918e-01 +-2.033163452148437500e+01 -1.503049278259277344e+01 -5.529308915138244629e-01 -1.652971953153610229e-01 -5.533592775464057922e-02 3.966634571552276611e-01 9.012618064880371094e-01 +-2.019488525390625000e+01 -1.510086917877197266e+01 -5.465551614761352539e-01 -1.634310036897659302e-01 -5.944371595978736877e-02 3.888122439384460449e-01 9.047551155090332031e-01 +-2.006615447998046875e+01 -1.517303657531738281e+01 -5.412658452987670898e-01 -1.617124378681182861e-01 -6.338612735271453857e-02 3.807254731655120850e-01 9.082287549972534180e-01 +-1.994371604919433594e+01 -1.524365234375000000e+01 -5.364623665809631348e-01 -1.601731330156326294e-01 -6.708491593599319458e-02 3.724210858345031738e-01 9.116724133491516113e-01 +-1.982761192321777344e+01 -1.531261730194091797e+01 -5.321472287178039551e-01 -1.588416397571563721e-01 -7.046176493167877197e-02 3.639198243618011475e-01 9.150775074958801270e-01 +-1.971994972229003906e+01 -1.538352966308593750e+01 -5.290173292160034180e-01 -1.577431112527847290e-01 -7.343824952840805054e-02 3.552419245243072510e-01 9.184372425079345703e-01 +-1.961760330200195312e+01 -1.545106887817382812e+01 -5.260412693023681641e-01 -1.568995416164398193e-01 -7.593537867069244385e-02 3.464096486568450928e-01 9.217464923858642578e-01 +-1.952189826965332031e+01 -1.551718235015869141e+01 -5.236254930496215820e-01 -1.563290804624557495e-01 -7.787409424781799316e-02 3.374458253383636475e-01 9.250012040138244629e-01 +-1.943454551696777344e+01 -1.558438968658447266e+01 -5.222949385643005371e-01 -1.560456752777099609e-01 -7.917611300945281982e-02 3.283739984035491943e-01 9.281979203224182129e-01 +-1.934015464782714844e+01 -1.565674781799316406e+01 -5.208557248115539551e-01 -1.560593098402023315e-01 -7.976308465003967285e-02 3.192176818847656250e-01 9.313342571258544922e-01 +-1.924914169311523438e+01 -1.572825622558593750e+01 -5.196911692619323730e-01 -1.563673317432403564e-01 -7.958032190799713135e-02 3.100039660930633545e-01 9.344055056571960449e-01 +-1.916583824157714844e+01 -1.580432605743408203e+01 -5.200195312500000000e-01 -1.569329351186752319e-01 -7.866371423006057739e-02 3.007761240005493164e-01 9.373994469642639160e-01 +-1.908487319946289062e+01 -1.587828063964843750e+01 -5.203344821929931641e-01 -1.577120125293731689e-01 -7.707326114177703857e-02 2.915808260440826416e-01 9.403016567230224609e-01 +-1.900623321533203125e+01 -1.595010185241699219e+01 -5.206396579742431641e-01 -1.586629748344421387e-01 -7.486814260482788086e-02 2.824644148349761963e-01 9.430984258651733398e-01 +-1.893425178527832031e+01 -1.602438926696777344e+01 -5.220336914062500000e-01 -1.597469151020050049e-01 -7.210765033960342407e-02 2.734732627868652344e-01 9.457767605781555176e-01 +-1.886517524719238281e+01 -1.609718704223632812e+01 -5.235705375671386719e-01 -1.609278172254562378e-01 -6.885146349668502808e-02 2.646539509296417236e-01 9.483247995376586914e-01 +-1.879824447631835938e+01 -1.616769027709960938e+01 -5.250585675239562988e-01 -1.621732115745544434e-01 -6.515870243310928345e-02 2.560534775257110596e-01 9.507316946983337402e-01 +-1.873452568054199219e+01 -1.623689460754394531e+01 -5.267516970634460449e-01 -1.634541451930999756e-01 -6.108817085623741150e-02 2.477196604013442993e-01 9.529878497123718262e-01 +-1.867581558227539062e+01 -1.630647850036621094e+01 -5.290759205818176270e-01 -1.647452563047409058e-01 -5.669882893562316895e-02 2.397010773420333862e-01 9.550851583480834961e-01 +-1.861907958984375000e+01 -1.637364196777343750e+01 -5.313208103179931641e-01 -1.660249382257461548e-01 -5.204921215772628784e-02 2.320473194122314453e-01 9.570164680480957031e-01 +-1.856431198120117188e+01 -1.643838310241699219e+01 -5.334875583648681641e-01 -1.672755330801010132e-01 -4.719660058617591858e-02 2.248092293739318848e-01 9.587763547897338867e-01 +-1.851239585876464844e+01 -1.650145912170410156e+01 -5.357751250267028809e-01 -1.684827357530593872e-01 -4.219894483685493469e-02 2.180386632680892944e-01 9.603602290153503418e-01 +-1.846445465087890625e+01 -1.656378936767578125e+01 -5.384314060211181641e-01 -1.696358472108840942e-01 -3.711352124810218811e-02 2.117889374494552612e-01 9.617648720741271973e-01 +-1.841833114624023438e+01 -1.662360763549804688e+01 -5.409862995147705078e-01 -1.707274615764617920e-01 -3.199715912342071533e-02 2.061144709587097168e-01 9.629875421524047852e-01 +-1.837400627136230469e+01 -1.668091773986816406e+01 -5.434387326240539551e-01 -1.717531234025955200e-01 -2.690691873431205750e-02 2.010709494352340698e-01 9.640266299247741699e-01 +-1.833147239685058594e+01 -1.673570823669433594e+01 -5.457910299301147461e-01 -1.727110296487808228e-01 -2.190021425485610962e-02 1.967148929834365845e-01 9.648805260658264160e-01 +-1.829236221313476562e+01 -1.678922843933105469e+01 -5.483788847923278809e-01 -1.736016720533370972e-01 -1.703507639467716217e-02 1.931038051843643188e-01 9.655480384826660156e-01 +-1.825531387329101562e+01 -1.684044837951660156e+01 -5.509252548217773438e-01 -1.744272559881210327e-01 -1.237064786255359650e-02 1.902956515550613403e-01 9.660277962684631348e-01 +-1.821992683410644531e+01 -1.688907623291015625e+01 -5.533496141433715820e-01 -1.751911938190460205e-01 -7.967818528413772583e-03 1.883485168218612671e-01 9.663174152374267578e-01 +-1.818618583679199219e+01 -1.693511199951171875e+01 -5.556518435478210449e-01 -1.758974492549896240e-01 -3.889763727784156799e-03 1.873202025890350342e-01 9.664139747619628906e-01 +-1.815403366088867188e+01 -1.697879791259765625e+01 -5.585265755653381348e-01 -1.736778020858764648e-01 3.683120012283325195e-04 1.872485131025314331e-01 9.668369889259338379e-01 +-1.812410545349121094e+01 -1.702033615112304688e+01 -5.615234375000000000e-01 -1.708639562129974365e-01 4.365487024188041687e-03 1.880719512701034546e-01 9.671686887741088867e-01 +-1.809640502929687500e+01 -1.705971717834472656e+01 -5.646276473999023438e-01 -1.675173193216323853e-01 8.118055760860443115e-03 1.897289156913757324e-01 9.674062728881835938e-01 +-1.807031250000000000e+01 -1.709648895263671875e+01 -5.677074790000915527e-01 -1.636992692947387695e-01 1.164237223565578461e-02 1.921575218439102173e-01 9.675445556640625000e-01 +-1.804584503173828125e+01 -1.713065338134765625e+01 -5.707470774650573730e-01 -1.594703197479248047e-01 1.495485939085483551e-02 1.952953934669494629e-01 9.675769805908203125e-01 +-1.802301406860351562e+01 -1.716219711303710938e+01 -5.737353563308715820e-01 -1.548913419246673584e-01 1.807173900306224823e-02 1.990799605846405029e-01 9.674964547157287598e-01 +-1.800183868408203125e+01 -1.719112205505371094e+01 -5.766589045524597168e-01 -1.500232070684432983e-01 2.100928872823715210e-02 2.034485489130020142e-01 9.672953486442565918e-01 +-1.798233222961425781e+01 -1.721742630004882812e+01 -5.795056223869323730e-01 -1.449269354343414307e-01 2.378391660749912262e-02 2.083385735750198364e-01 9.669671654701232910e-01 +-1.796454048156738281e+01 -1.724111747741699219e+01 -5.822631716728210449e-01 -1.396637409925460815e-01 2.641172707080841064e-02 2.136875092983245850e-01 9.665061235427856445e-01 +-1.794881820678710938e+01 -1.726243591308593750e+01 -5.849756002426147461e-01 -1.342951357364654541e-01 2.890913002192974091e-02 2.194330692291259766e-01 9.659079313278198242e-01 +-1.793476104736328125e+01 -1.728108406066894531e+01 -5.875573754310607910e-01 -1.288829147815704346e-01 3.129223734140396118e-02 2.255132198333740234e-01 9.651703834533691406e-01 +-1.792238235473632812e+01 -1.729707527160644531e+01 -5.899950861930847168e-01 -1.234894543886184692e-01 3.357748687267303467e-02 2.318663746118545532e-01 9.642929434776306152e-01 +-1.791169548034667969e+01 -1.731039047241210938e+01 -5.922704935073852539e-01 -1.181771308183670044e-01 3.578108549118041992e-02 2.384315133094787598e-01 9.632779359817504883e-01 +-1.790271568298339844e+01 -1.732105445861816406e+01 -5.943713188171386719e-01 -1.130089387297630310e-01 3.791945800185203552e-02 2.451479583978652954e-01 9.621296525001525879e-01 +-1.789545440673828125e+01 -1.732906150817871094e+01 -5.962817072868347168e-01 -1.080475375056266785e-01 4.000906646251678467e-02 2.519558668136596680e-01 9.608554244041442871e-01 +-1.788992500305175781e+01 -1.733441925048828125e+01 -5.979833602905273438e-01 -1.033566072583198547e-01 4.206611216068267822e-02 2.587959468364715576e-01 9.594647884368896484e-01 +-1.788613891601562500e+01 -1.733712768554687500e+01 -5.994641184806823730e-01 -9.899981319904327393e-02 4.410721734166145325e-02 2.656095325946807861e-01 9.579692482948303223e-01 +-1.788411140441894531e+01 -1.733719635009765625e+01 -6.007080078125000000e-01 -9.504061937332153320e-02 4.614873975515365601e-02 2.723386883735656738e-01 9.563834071159362793e-01 +-1.787696456909179688e+01 -1.734501457214355469e+01 -6.022863388061523438e-01 -9.154327213764190674e-02 4.820729792118072510e-02 2.789262533187866211e-01 9.547230601310729980e-01 +-1.786470603942871094e+01 -1.736057662963867188e+01 -6.041833162307739258e-01 -8.857118338346481323e-02 5.029954761266708374e-02 2.853153944015502930e-01 9.530058503150939941e-01 +-1.784735107421875000e+01 -1.738390541076660156e+01 -6.063903570175170898e-01 -8.616801351308822632e-02 5.243882536888122559e-02 2.914660573005676270e-01 9.512479901313781738e-01 +-1.782488632202148438e+01 -1.741499900817871094e+01 -6.089184284210205078e-01 -8.429352939128875732e-02 5.462608486413955688e-02 2.974020540714263916e-01 9.494538903236389160e-01 +-1.779734039306640625e+01 -1.745387077331542969e+01 -6.117821931838989258e-01 -8.288758993148803711e-02 5.685858055949211121e-02 3.031627237796783447e-01 9.476228952407836914e-01 +-1.776491355895996094e+01 -1.750066947937011719e+01 -6.150036454200744629e-01 -8.188873529434204102e-02 5.913389846682548523e-02 3.087868690490722656e-01 9.457526803016662598e-01 +-1.772739982604980469e+01 -1.755525779724121094e+01 -6.185900568962097168e-01 -8.123598992824554443e-02 6.144924834370613098e-02 3.143127262592315674e-01 9.438390731811523438e-01 +-1.768478775024414062e+01 -1.761763572692871094e+01 -6.225597858428955078e-01 -8.086805045604705811e-02 6.380198150873184204e-02 3.197781145572662354e-01 9.418767094612121582e-01 +-1.763625717163085938e+01 -1.768726539611816406e+01 -6.266626119613647461e-01 -8.072343468666076660e-02 6.618919223546981812e-02 3.252205848693847656e-01 9.398586750030517578e-01 +-1.758230400085449219e+01 -1.776447677612304688e+01 -6.310778856277465820e-01 -8.074045926332473755e-02 6.860806047916412354e-02 3.306772112846374512e-01 9.377774000167846680e-01 +-1.752128601074218750e+01 -1.784814834594726562e+01 -6.353161334991455078e-01 -8.085796236991882324e-02 7.105553895235061646e-02 3.361848294734954834e-01 9.356243014335632324e-01 +-1.745257949829101562e+01 -1.793774414062500000e+01 -6.392089724540710449e-01 -8.101430535316467285e-02 7.352856546640396118e-02 3.417798578739166260e-01 9.333900213241577148e-01 +-1.737313652038574219e+01 -1.803073692321777344e+01 -6.418249607086181641e-01 -8.114737272262573242e-02 7.602420449256896973e-02 3.474985361099243164e-01 9.310639500617980957e-01 +-1.727821540832519531e+01 -1.812207412719726562e+01 -6.416015625000000000e-01 -8.119583874940872192e-02 7.853914797306060791e-02 3.533766865730285645e-01 9.286354780197143555e-01 +-1.716444396972656250e+01 -1.820580101013183594e+01 -6.372119188308715820e-01 -8.109773695468902588e-02 8.107020705938339233e-02 3.594494760036468506e-01 9.260922670364379883e-01 +-1.703792572021484375e+01 -1.828765106201171875e+01 -6.308032274246215820e-01 -8.079120516777038574e-02 8.361406624317169189e-02 3.657518625259399414e-01 9.234213232994079590e-01 +-1.690320205688476562e+01 -1.837402725219726562e+01 -6.242114305496215820e-01 -8.021453022956848145e-02 8.616720885038375854e-02 3.723181784152984619e-01 9.206085205078125000e-01 +-1.676093673706054688e+01 -1.846594619750976562e+01 -6.178197860717773438e-01 -7.930594682693481445e-02 8.872600644826889038e-02 3.791821002960205078e-01 9.176378250122070312e-01 +-1.661141777038574219e+01 -1.856386184692382812e+01 -6.118798851966857910e-01 -7.800345122814178467e-02 9.128685295581817627e-02 3.863770961761474609e-01 9.144915938377380371e-01 +-1.645495605468750000e+01 -1.866820716857910156e+01 -6.066784262657165527e-01 -7.624515146017074585e-02 9.384562075138092041e-02 3.939341008663177490e-01 9.111507534980773926e-01 +-1.629194259643554688e+01 -1.877953529357910156e+01 -6.025720238685607910e-01 -7.396907359361648560e-02 9.639839082956314087e-02 4.018841981887817383e-01 9.075930118560791016e-01 +-1.612274742126464844e+01 -1.889830017089843750e+01 -5.998827815055847168e-01 -7.111330330371856689e-02 9.894046932458877563e-02 4.102570116519927979e-01 9.037936329841613770e-01 +-1.594792461395263672e+01 -1.902517127990722656e+01 -5.990747213363647461e-01 -6.764376163482666016e-02 1.014612764120101929e-01 4.190501570701599121e-01 8.997371196746826172e-01 +-1.576822853088378906e+01 -1.916101074218750000e+01 -6.007885336875915527e-01 -6.363680213689804077e-02 1.039256975054740906e-01 4.281411468982696533e-01 8.954579234123229980e-01 +-1.558430385589599609e+01 -1.930643463134765625e+01 -6.056188941001892090e-01 -5.919722840189933777e-02 1.062933802604675293e-01 4.373798668384552002e-01 8.910086154937744141e-01 +-1.539637660980224609e+01 -1.946148300170898438e+01 -6.137255430221557617e-01 -5.443003028631210327e-02 1.085248515009880066e-01 4.466195404529571533e-01 8.864483833312988281e-01 +-1.520430183410644531e+01 -1.962582397460937500e+01 -6.249060034751892090e-01 -4.944133758544921875e-02 1.105812788009643555e-01 4.557167887687683105e-01 8.818444013595581055e-01 +-1.500771331787109375e+01 -1.979891586303710938e+01 -6.387646198272705078e-01 -4.433740675449371338e-02 1.124248802661895752e-01 4.645321965217590332e-01 8.772711157798767090e-01 +-1.480619621276855469e+01 -1.998026275634765625e+01 -6.548547148704528809e-01 -3.922503814101219177e-02 1.140190213918685913e-01 4.729304611682891846e-01 8.728103041648864746e-01 +-1.459937191009521484e+01 -2.016944694519042969e+01 -6.727819442749023438e-01 -3.421109169721603394e-02 1.153278648853302002e-01 4.807797670364379883e-01 8.685504198074340820e-01 +-1.438695049285888672e+01 -2.036620521545410156e+01 -6.922289729118347168e-01 -2.940253913402557373e-02 1.163163855671882629e-01 4.879520535469055176e-01 8.645858764648437500e-01 +-1.416900730133056641e+01 -2.057060050964355469e+01 -7.132446169853210449e-01 -2.490628883242607117e-02 1.169503927230834961e-01 4.943219423294067383e-01 8.610157370567321777e-01 +-1.395810794830322266e+01 -2.076930618286132812e+01 -7.336339950561523438e-01 -2.082914486527442932e-02 1.171961426734924316e-01 4.997668564319610596e-01 8.579419851303100586e-01 +-1.375402069091796875e+01 -2.096210861206054688e+01 -7.532275319099426270e-01 -1.727757975459098816e-02 1.170200556516647339e-01 5.041647553443908691e-01 8.554680943489074707e-01 +-1.355647563934326172e+01 -2.114881706237792969e+01 -7.714196443557739258e-01 -1.435786113142967224e-02 1.163884699344635010e-01 5.073940157890319824e-01 8.536972403526306152e-01 +-1.336550045013427734e+01 -2.132947158813476562e+01 -7.884838581085205078e-01 -1.217595487833023071e-02 1.152671799063682556e-01 5.093313455581665039e-01 8.527289628982543945e-01 +-1.318074798583984375e+01 -2.150379371643066406e+01 -8.037194609642028809e-01 -1.083766296505928040e-02 1.136212199926376343e-01 5.098505020141601562e-01 8.526577949523925781e-01 +-1.300255870819091797e+01 -2.167208480834960938e+01 -8.177490234375000000e-01 -1.044839248061180115e-02 1.114140003919601440e-01 5.088196992874145508e-01 8.535690903663635254e-01 +-1.283029842376708984e+01 -2.183377456665039062e+01 -8.294262290000915527e-01 -1.111348345875740051e-02 1.086074858903884888e-01 5.061002373695373535e-01 8.555368781089782715e-01 +-1.266489505767822266e+01 -2.198973655700683594e+01 -8.402550816535949707e-01 -1.293786615133285522e-02 1.051610410213470459e-01 5.015448331832885742e-01 8.586189746856689453e-01 +-1.250496673583984375e+01 -2.213861274719238281e+01 -8.478466868400573730e-01 -1.602597907185554504e-02 1.010316461324691772e-01 4.949942231178283691e-01 8.628536462783813477e-01 +-1.235201644897460938e+01 -2.228182601928710938e+01 -8.545812964439392090e-01 -2.048139087855815887e-02 9.617313742637634277e-02 4.862766563892364502e-01 8.682547211647033691e-01 +-1.220498275756835938e+01 -2.241820335388183594e+01 -8.585851788520812988e-01 -2.635845541954040527e-02 9.055834263563156128e-02 4.752687513828277588e-01 8.747708797454833984e-01 +-1.206440067291259766e+01 -2.254821205139160156e+01 -8.607397079467773438e-01 -3.351867198944091797e-02 8.424679934978485107e-02 4.620925784111022949e-01 8.821844458580017090e-01 +-1.193075942993164062e+01 -2.267219161987304688e+01 -8.618810772895812988e-01 -4.177390038967132568e-02 7.732103765010833740e-02 4.469355344772338867e-01 8.902387619018554688e-01 +-1.180233383178710938e+01 -2.278814315795898438e+01 -8.590893149375915527e-01 -5.093406885862350464e-02 6.986640393733978271e-02 4.299928843975067139e-01 8.986826539039611816e-01 +-1.168124580383300781e+01 -2.289830017089843750e+01 -8.560631871223449707e-01 -6.080749630928039551e-02 6.197084113955497742e-02 4.114713370800018311e-01 9.072780609130859375e-01 +-1.156612873077392578e+01 -2.300089836120605469e+01 -8.504064679145812988e-01 -7.120185345411300659e-02 5.372554808855056763e-02 3.915930092334747314e-01 9.158050417900085449e-01 +-1.145700263977050781e+01 -2.309589767456054688e+01 -8.422644138336181641e-01 -8.192436397075653076e-02 4.522506892681121826e-02 3.705942034721374512e-01 9.240686893463134766e-01 +-1.135530757904052734e+01 -2.318506240844726562e+01 -8.344018459320068359e-01 -9.278335422277450562e-02 3.656715154647827148e-02 3.487282693386077881e-01 9.319027662277221680e-01 +-1.125894165039062500e+01 -2.326542854309082031e+01 -8.236218094825744629e-01 -1.035891473293304443e-01 2.785192057490348816e-02 3.262639045715332031e-01 9.391727447509765625e-01 +-1.116942977905273438e+01 -2.333920860290527344e+01 -8.125329613685607910e-01 -1.141555085778236389e-01 1.918116211891174316e-02 3.034849464893341064e-01 9.457788467407226562e-01 +-1.108734512329101562e+01 -2.340727424621582031e+01 -8.022240996360778809e-01 -1.243009939789772034e-01 1.065819710493087769e-02 2.806864678859710693e-01 9.516568779945373535e-01 +-1.101012325286865234e+01 -2.346564865112304688e+01 -7.894347906112670898e-01 -1.338488608598709106e-01 2.386640757322311401e-03 2.581741809844970703e-01 9.567784667015075684e-01 +-1.094018077850341797e+01 -2.351834869384765625e+01 -7.775878906250000000e-01 -1.426293998956680298e-01 -5.530703812837600708e-03 2.362618595361709595e-01 9.611486196517944336e-01 +-1.087761116027832031e+01 -2.356570243835449219e+01 -7.669897079467773438e-01 -1.504779756069183350e-01 -1.299132406711578369e-02 2.152677923440933228e-01 9.648043513298034668e-01 +-1.081989383697509766e+01 -2.360318374633789062e+01 -7.549633383750915527e-01 -1.572377234697341919e-01 -1.989493519067764282e-02 1.955124735832214355e-01 9.678095579147338867e-01 +-1.076939964294433594e+01 -2.363549232482910156e+01 -7.443163990974426270e-01 -1.627555489540100098e-01 -2.614275738596916199e-02 1.773162335157394409e-01 9.702506065368652344e-01 +-1.072629261016845703e+01 -2.366316795349121094e+01 -7.353747487068176270e-01 -1.668835878372192383e-01 -3.163781389594078064e-02 1.609973907470703125e-01 9.722288250923156738e-01 +-1.068942451477050781e+01 -2.368360710144042969e+01 -7.270935177803039551e-01 -1.694756001234054565e-01 -3.628516569733619690e-02 1.468703299760818481e-01 9.738534092903137207e-01 +-1.065877342224121094e+01 -2.369713401794433594e+01 -7.197473049163818359e-01 -1.697092056274414062e-01 -3.989725559949874878e-02 1.352724879980087280e-01 9.753503203392028809e-01 +-1.063575077056884766e+01 -2.370730972290039062e+01 -7.143371701240539551e-01 -1.694652587175369263e-01 -4.266242682933807373e-02 1.264244019985198975e-01 9.764621257781982422e-01 +-1.062023162841796875e+01 -2.371432495117187500e+01 -7.113623023033142090e-01 -1.666205227375030518e-01 -4.424036294221878052e-02 1.206160113215446472e-01 9.776155352592468262e-01 +-1.061051654815673828e+01 -2.371881866455078125e+01 -7.102355957031250000e-01 -1.619942039251327515e-01 -4.480173811316490173e-02 1.176587045192718506e-01 9.787273406982421875e-01 +-1.060666942596435547e+01 -2.372078132629394531e+01 -7.109069824218750000e-01 -1.557830721139907837e-01 -4.445625096559524536e-02 1.172960177063941956e-01 9.797943234443664551e-01 +-1.060481262207031250e+01 -2.372170448303222656e+01 -7.124841213226318359e-01 -1.481798291206359863e-01 -4.331202805042266846e-02 1.192679628729820251e-01 9.807863831520080566e-01 +-1.059402942657470703e+01 -2.372573280334472656e+01 -7.125634551048278809e-01 -1.393745392560958862e-01 -4.147681593894958496e-02 1.233121752738952637e-01 9.816560149192810059e-01 +-1.057428169250488281e+01 -2.373179626464843750e+01 -7.108715772628784180e-01 -1.295560449361801147e-01 -3.905843943357467651e-02 1.291646510362625122e-01 9.823472499847412109e-01 +-1.054468154907226562e+01 -2.373078536987304688e+01 -7.053527832031250000e-01 -1.189149618148803711e-01 -3.616411983966827393e-02 1.365606486797332764e-01 9.828034639358520508e-01 +-1.050600719451904297e+01 -2.372926712036132812e+01 -6.974206566810607910e-01 -1.076428443193435669e-01 -3.290275484323501587e-02 1.452350765466690063e-01 9.829736351966857910e-01 +-1.047626781463623047e+01 -2.370073127746582031e+01 -6.884130835533142090e-01 -9.593401104211807251e-02 -2.938275039196014404e-02 1.549237966537475586e-01 9.828183650970458984e-01 +-1.046522426605224609e+01 -2.364887619018554688e+01 -6.820385456085205078e-01 -8.398548513650894165e-02 -2.571449242532253265e-02 1.653640419244766235e-01 9.823135137557983398e-01 +-1.048062133789062500e+01 -2.358564949035644531e+01 -6.827343702316284180e-01 -7.199695706367492676e-02 -2.200762741267681122e-02 1.762954741716384888e-01 9.814540743827819824e-01 +-1.050563335418701172e+01 -2.351642608642578125e+01 -6.861621141433715820e-01 -6.017067655920982361e-02 -1.837365329265594482e-02 1.874611973762512207e-01 9.802551865577697754e-01 +-1.054297256469726562e+01 -2.344232940673828125e+01 -6.934130787849426270e-01 -4.871069639921188354e-02 -1.492377743124961853e-02 1.986082196235656738e-01 9.787539839744567871e-01 +-1.058514404296875000e+01 -2.336031723022460938e+01 -7.011474370956420898e-01 -3.782265260815620422e-02 -1.176953222602605820e-02 2.094882875680923462e-01 9.770084619522094727e-01 +-1.063856792449951172e+01 -2.327448272705078125e+01 -7.121984958648681641e-01 -2.771227434277534485e-02 -9.021600708365440369e-03 2.198581695556640625e-01 9.750964045524597168e-01 +-1.069721889495849609e+01 -2.318099975585937500e+01 -7.237438559532165527e-01 -1.858626678586006165e-02 -6.791889201849699020e-03 2.294794023036956787e-01 9.731123447418212891e-01 +-1.076325702667236328e+01 -2.308148384094238281e+01 -7.366576790809631348e-01 -1.065042708069086075e-02 -5.190695635974407196e-03 2.381179630756378174e-01 9.711639881134033203e-01 +-1.083692359924316406e+01 -2.297613716125488281e+01 -7.509692311286926270e-01 -4.110292997211217880e-03 -4.328842274844646454e-03 2.455432265996932983e-01 9.693673253059387207e-01 +-1.091626167297363281e+01 -2.286353874206542969e+01 -7.657372951507568359e-01 8.294742438010871410e-04 -4.317172802984714508e-03 2.515261769294738770e-01 9.678404927253723145e-01 +-1.100432872772216797e+01 -2.274613761901855469e+01 -7.821130156517028809e-01 3.964609466493129730e-03 -5.266502965241670609e-03 2.558379769325256348e-01 9.666971564292907715e-01 +-1.109833145141601562e+01 -2.262172889709472656e+01 -7.989257574081420898e-01 5.153934471309185028e-03 -7.251162547618150711e-03 2.583153545856475830e-01 9.660197496414184570e-01 +-1.119967460632324219e+01 -2.249148941040039062e+01 -8.166686892509460449e-01 4.504605196416378021e-03 -1.019955892115831375e-02 2.590637207031250000e-01 9.657959342002868652e-01 +-1.130787372589111328e+01 -2.235502433776855469e+01 -8.352453708648681641e-01 2.185793127864599228e-03 -1.400303561240434647e-02 2.582513689994812012e-01 9.659738540649414062e-01 +-1.142283821105957031e+01 -2.221224975585937500e+01 -8.545776009559631348e-01 -1.633108127862215042e-03 -1.855275034904479980e-02 2.560428678989410400e-01 9.664859771728515625e-01 +-1.154491806030273438e+01 -2.206347084045410156e+01 -8.747839331626892090e-01 -6.783263292163610458e-03 -2.373933419585227966e-02 2.526000142097473145e-01 9.672556519508361816e-01 +-1.167372322082519531e+01 -2.190831565856933594e+01 -8.956835865974426270e-01 -1.309422217309474945e-02 -2.945379167795181274e-02 2.480840981006622314e-01 9.682021141052246094e-01 +-1.180952262878417969e+01 -2.174700164794921875e+01 -9.173119664192199707e-01 -2.039594948291778564e-02 -3.558594360947608948e-02 2.426568120718002319e-01 9.692447185516357422e-01 +-1.195242786407470703e+01 -2.157956504821777344e+01 -9.393078684806823730e-01 -2.851795963943004608e-02 -4.202570021152496338e-02 2.364814728498458862e-01 9.703077077865600586e-01 +-1.210221576690673828e+01 -2.140580940246582031e+01 -9.616162180900573730e-01 -3.728902339935302734e-02 -4.866314306855201721e-02 2.297237962484359741e-01 9.713229537010192871e-01 +-1.225943660736083984e+01 -2.122608375549316406e+01 -9.834057688713073730e-01 -4.653758928179740906e-02 -5.538772046566009521e-02 2.225524336099624634e-01 9.722328782081604004e-01 +-1.242544555664062500e+01 -2.104152297973632812e+01 -1.003858566284179688e+00 -5.609222501516342163e-02 -6.208969652652740479e-02 2.151391804218292236e-01 9.729921221733093262e-01 +-1.259703445434570312e+01 -2.086024856567382812e+01 -1.021265864372253418e+00 -6.578211486339569092e-02 -6.865978240966796875e-02 2.076589465141296387e-01 9.735688567161560059e-01 +-1.277709674835205078e+01 -2.068539428710937500e+01 -1.034840106964111328e+00 -7.543698698282241821e-02 -7.498934864997863770e-02 2.002898007631301880e-01 9.739454984664916992e-01 +-1.297280883789062500e+01 -2.052606964111328125e+01 -1.043343424797058105e+00 -8.488766103982925415e-02 -8.097057044506072998e-02 1.932124793529510498e-01 9.741185307502746582e-01 +-1.318554782867431641e+01 -2.038809967041015625e+01 -1.050672531127929688e+00 -9.396622329950332642e-02 -8.649715036153793335e-02 1.866097748279571533e-01 9.740972518920898438e-01 +-1.340810298919677734e+01 -2.026439857482910156e+01 -1.056845664978027344e+00 -1.025063842535018921e-01 -9.146361798048019409e-02 1.806665956974029541e-01 9.739026427268981934e-01 +-1.363603401184082031e+01 -2.014865112304687500e+01 -1.056191325187683105e+00 -1.103432998061180115e-01 -9.576536715030670166e-02 1.755688339471817017e-01 9.735651016235351562e-01 +-1.386581039428710938e+01 -2.003540420532226562e+01 -1.043540000915527344e+00 -1.173135638236999512e-01 -9.929943084716796875e-02 1.715029180049896240e-01 9.731207489967346191e-01 +-1.409475421905517578e+01 -1.992141151428222656e+01 -1.015662789344787598e+00 -1.232542917132377625e-01 -1.019623205065727234e-01 1.686556339263916016e-01 9.726085066795349121e-01 +-1.432707595825195312e+01 -1.981404304504394531e+01 -9.837145805358886719e-01 -1.280037760734558105e-01 -1.036513596773147583e-01 1.672129184007644653e-01 9.720654487609863281e-01 +-1.456527996063232422e+01 -1.971718215942382812e+01 -9.577209353446960449e-01 -1.314439326524734497e-01 -1.042973548173904419e-01 1.673095226287841797e-01 9.715204834938049316e-01 +-1.480920982360839844e+01 -1.963162612915039062e+01 -9.416223168373107910e-01 -1.336328685283660889e-01 -1.039666831493377686e-01 1.688769906759262085e-01 9.709860086441040039e-01 +-1.505674266815185547e+01 -1.955385780334472656e+01 -9.336132407188415527e-01 -1.346721351146697998e-01 -1.027587950229644775e-01 1.717943102121353149e-01 9.704590439796447754e-01 +-1.530693912506103516e+01 -1.948230361938476562e+01 -9.326086044311523438e-01 -1.346603780984878540e-01 -1.007723584771156311e-01 1.759385019540786743e-01 9.699262976646423340e-01 +-1.555902957916259766e+01 -1.941506385803222656e+01 -9.368615746498107910e-01 -1.336965858936309814e-01 -9.810473024845123291e-02 1.811851710081100464e-01 9.693671464920043945e-01 +-1.581249237060546875e+01 -1.935045433044433594e+01 -9.446935653686523438e-01 -1.318787783384323120e-01 -9.485309571027755737e-02 1.874091774225234985e-01 9.687562584877014160e-01 +-1.606719398498535156e+01 -1.928809928894042969e+01 -9.559924006462097168e-01 -1.293048858642578125e-01 -9.111483395099639893e-02 1.944845765829086304e-01 9.680672287940979004e-01 +-1.632287406921386719e+01 -1.922676658630371094e+01 -9.694970250129699707e-01 -1.260729134082794189e-01 -8.698722720146179199e-02 2.022854983806610107e-01 9.672741889953613281e-01 +-1.657949256896972656e+01 -1.916606903076171875e+01 -9.848546981811523438e-01 -1.222814619541168213e-01 -8.256836235523223877e-02 2.106860280036926270e-01 9.663545489311218262e-01 +-1.683703422546386719e+01 -1.910580062866210938e+01 -1.001964092254638672e+00 -1.180305927991867065e-01 -7.795666903257369995e-02 2.195609360933303833e-01 9.652899503707885742e-01 +-1.709544563293457031e+01 -1.904576110839843750e+01 -1.021319508552551270e+00 -1.134206950664520264e-01 -7.325114309787750244e-02 2.287859469652175903e-01 9.640679359436035156e-01 +-1.735464859008789062e+01 -1.898541450500488281e+01 -1.042510986328125000e+00 -1.085525155067443848e-01 -6.855186820030212402e-02 2.382379472255706787e-01 9.626835584640502930e-01 +-1.761455535888671875e+01 -1.892434120178222656e+01 -1.065726280212402344e+00 -1.035291403532028198e-01 -6.395925581455230713e-02 2.477953881025314331e-01 9.611391425132751465e-01 +-1.787494087219238281e+01 -1.886177253723144531e+01 -1.091593027114868164e+00 -9.845310449600219727e-02 -5.957423523068428040e-02 2.573384940624237061e-01 9.594449996948242188e-01 +-1.813428115844726562e+01 -1.879277229309082031e+01 -1.122253417968750000e+00 -9.342893958091735840e-02 -5.549824237823486328e-02 2.667495608329772949e-01 9.576197862625122070e-01 +-1.833241462707519531e+01 -1.866669464111328125e+01 -1.176586866378784180e+00 -8.856072276830673218e-02 -5.183271691203117371e-02 2.759130597114562988e-01 9.556894898414611816e-01 +-1.808251571655273438e+01 -1.856697273254394531e+01 -1.208829283714294434e+00 -8.395332098007202148e-02 -4.868030920624732971e-02 2.847153842449188232e-01 9.536872506141662598e-01 +-1.782111358642578125e+01 -1.851432037353515625e+01 -1.220994830131530762e+00 -7.971203327178955078e-02 -4.614233970642089844e-02 2.930452525615692139e-01 9.516519308090209961e-01 +-1.756674957275390625e+01 -1.847419929504394531e+01 -1.227602481842041016e+00 -7.594230771064758301e-02 -4.432166740298271179e-02 3.007927834987640381e-01 9.496273398399353027e-01 +-1.732123565673828125e+01 -1.843797302246093750e+01 -1.232556104660034180e+00 -7.274919003248214722e-02 -4.332016408443450928e-02 3.078496754169464111e-01 9.476599693298339844e-01 +-1.708448410034179688e+01 -1.840636253356933594e+01 -1.235462665557861328e+00 -7.021540403366088867e-02 -4.320727288722991943e-02 3.141236603260040283e-01 9.457956552505493164e-01 +-1.685700225830078125e+01 -1.837602424621582031e+01 -1.238062739372253418e+00 -6.833245605230331421e-02 -4.392163828015327454e-02 3.195825815200805664e-01 9.440701603889465332e-01 +-1.663839530944824219e+01 -1.835005760192871094e+01 -1.238934278488159180e+00 -6.706956028938293457e-02 -4.536860436201095581e-02 3.242086470127105713e-01 9.425137042999267578e-01 +-1.642906761169433594e+01 -1.832528686523437500e+01 -1.239571452140808105e+00 -6.639516353607177734e-02 -4.745297878980636597e-02 3.279826641082763672e-01 9.411520957946777344e-01 +-1.622902488708496094e+01 -1.830168914794921875e+01 -1.240007281303405762e+00 -6.627741456031799316e-02 -5.008045583963394165e-02 3.308842480182647705e-01 9.400079250335693359e-01 +-1.603810691833496094e+01 -1.828070259094238281e+01 -1.239680171012878418e+00 -6.668455898761749268e-02 -5.315614491701126099e-02 3.328922688961029053e-01 9.391008615493774414e-01 +-1.585641098022460938e+01 -1.826147842407226562e+01 -1.238952636718750000e+00 -6.758426874876022339e-02 -5.658433213829994202e-02 3.339850008487701416e-01 9.384479522705078125e-01 +-1.568401622772216797e+01 -1.824333953857421875e+01 -1.238115191459655762e+00 -6.894429028034210205e-02 -6.027023121714591980e-02 3.341394960880279541e-01 9.380645155906677246e-01 +-1.552092266082763672e+01 -1.822630310058593750e+01 -1.237186193466186523e+00 -7.073239982128143311e-02 -6.411853432655334473e-02 3.333325684070587158e-01 9.379633069038391113e-01 +-1.536710643768310547e+01 -1.821068763732910156e+01 -1.236071705818176270e+00 -7.291604578495025635e-02 -6.803405284881591797e-02 3.315400183200836182e-01 9.381555318832397461e-01 +-1.522249126434326172e+01 -1.819730377197265625e+01 -1.234512925148010254e+00 -7.546215504407882690e-02 -7.192133367061614990e-02 3.287371993064880371e-01 9.386504292488098145e-01 +-1.508719921112060547e+01 -1.818493080139160156e+01 -1.232949137687683105e+00 -7.833813130855560303e-02 -7.568459212779998779e-02 3.248988687992095947e-01 9.394549727439880371e-01 +-1.496123886108398438e+01 -1.817356491088867188e+01 -1.231396436691284180e+00 -8.151099085807800293e-02 -7.922795414924621582e-02 3.199989199638366699e-01 9.405741095542907715e-01 +-1.484461498260498047e+01 -1.816320228576660156e+01 -1.229871749877929688e+00 -8.494706451892852783e-02 -8.245579898357391357e-02 3.140104711055755615e-01 9.420098066329956055e-01 +-1.473733615875244141e+01 -1.815383720397949219e+01 -1.228391051292419434e+00 -8.861301839351654053e-02 -8.527182042598724365e-02 3.069058656692504883e-01 9.437612295150756836e-01 +-1.463940525054931641e+01 -1.814546394348144531e+01 -1.226967692375183105e+00 -9.247442334890365601e-02 -8.757954835891723633e-02 2.986566722393035889e-01 9.458237290382385254e-01 +-1.455079936981201172e+01 -1.813845634460449219e+01 -1.225509047508239746e+00 -9.649711102247238159e-02 -8.928236365318298340e-02 2.892331182956695557e-01 9.481883049011230469e-01 +-1.447151565551757812e+01 -1.813287544250488281e+01 -1.224000215530395508e+00 -1.006453931331634521e-01 -9.028363227844238281e-02 2.786045968532562256e-01 9.508411288261413574e-01 +-1.440161228179931641e+01 -1.812816429138183594e+01 -1.222614765167236328e+00 -1.048841774463653564e-01 -9.048581123352050781e-02 2.667394876480102539e-01 9.537618160247802734e-01 +-1.434109973907470703e+01 -1.812429237365722656e+01 -1.221358656883239746e+00 -1.091762632131576538e-01 -8.979181945323944092e-02 2.536047101020812988e-01 9.569235444068908691e-01 +-1.428998184204101562e+01 -1.812124443054199219e+01 -1.220239281654357910e+00 -1.134869679808616638e-01 -8.813484013080596924e-02 2.391924560070037842e-01 9.602811336517333984e-01 +-1.424823951721191406e+01 -1.811898422241210938e+01 -1.219243168830871582e+00 -1.177903041243553162e-01 -8.556693792343139648e-02 2.236001640558242798e-01 9.637461304664611816e-01 +-1.421585559844970703e+01 -1.811746978759765625e+01 -1.218361735343933105e+00 -1.220636069774627686e-01 -8.217258751392364502e-02 2.069532722234725952e-01 9.672220349311828613e-01 +-1.419280338287353516e+01 -1.811666488647460938e+01 -1.217582941055297852e+00 -1.262835711240768433e-01 -7.803602516651153564e-02 1.893805265426635742e-01 9.706172347068786621e-01 +-1.417905616760253906e+01 -1.811654281616210938e+01 -1.216898202896118164e+00 -1.304282695055007935e-01 -7.324372977018356323e-02 1.710139065980911255e-01 9.738470911979675293e-01 +-1.417458438873291016e+01 -1.811705970764160156e+01 -1.216296315193176270e+00 -1.344764232635498047e-01 -6.788312643766403198e-02 1.519887447357177734e-01 9.768354892730712891e-01 +-1.417400646209716797e+01 -1.811774826049804688e+01 -1.215728759765625000e+00 -1.384075284004211426e-01 -6.204353272914886475e-02 1.324436813592910767e-01 9.795166254043579102e-01 +-1.417728614807128906e+01 -1.811858940124511719e+01 -1.215190410614013672e+00 -1.422036290168762207e-01 -5.581462383270263672e-02 1.125206649303436279e-01 9.818360805511474609e-01 +-1.417791461944580078e+01 -1.811901283264160156e+01 -1.214627623558044434e+00 -1.458467990159988403e-01 -4.928795993328094482e-02 9.236415475606918335e-02 9.837521910667419434e-01 +-1.417585754394531250e+01 -1.811901855468750000e+01 -1.214035630226135254e+00 -1.493225842714309692e-01 -4.255578666925430298e-02 7.212089747190475464e-02 9.852362275123596191e-01 +-1.417107486724853516e+01 -1.811859321594238281e+01 -1.213415503501892090e+00 -1.526171863079071045e-01 -3.571120649576187134e-02 5.193909257650375366e-02 9.862733483314514160e-01 +-1.416352653503417969e+01 -1.811774444580078125e+01 -1.212767362594604492e+00 -1.557197868824005127e-01 -2.884677797555923462e-02 3.196797147393226624e-02 9.868622422218322754e-01 +-1.415317249298095703e+01 -1.811647415161132812e+01 -1.212092280387878418e+00 -1.586212366819381714e-01 -2.205622941255569458e-02 1.235679350793361664e-02 9.870157241821289062e-01 +-1.413997554779052734e+01 -1.811479949951171875e+01 -1.211398839950561523e+00 -1.613143682479858398e-01 -1.543178688734769821e-02 -6.745595484972000122e-03 9.867593050003051758e-01 +-1.412389755249023438e+01 -1.811273384094238281e+01 -1.210687279701232910e+00 -1.637944579124450684e-01 -9.066479280591011047e-03 -2.519115246832370758e-02 9.861310720443725586e-01 +-1.410490608215332031e+01 -1.811030197143554688e+01 -1.209967017173767090e+00 -1.660586595535278320e-01 -3.051096573472023010e-03 -4.283371195197105408e-02 9.851804375648498535e-01 +-1.408296585083007812e+01 -1.810753822326660156e+01 -1.209245562553405762e+00 -1.681053489446640015e-01 2.523428294807672501e-03 -5.952922254800796509e-02 9.839667081832885742e-01 +-1.406326961517333984e+01 -1.810489273071289062e+01 -1.208572983741760254e+00 -1.699351519346237183e-01 7.567468099296092987e-03 -7.513505220413208008e-02 9.825576543807983398e-01 +-1.404578781127929688e+01 -1.810241699218750000e+01 -1.207955241203308105e+00 -1.715495586395263672e-01 1.199221983551979065e-02 -8.951156586408615112e-02 9.810273051261901855e-01 +-1.403049373626708984e+01 -1.810012626647949219e+01 -1.207407236099243164e+00 -1.729509383440017700e-01 1.571034267544746399e-02 -1.025211811065673828e-01 9.794542193412780762e-01 +-1.401740169525146484e+01 -1.809819793701171875e+01 -1.207285165786743164e+00 -1.726683527231216431e-01 1.848724856972694397e-02 -1.140902489423751831e-01 9.781754612922668457e-01 +-1.400649261474609375e+01 -1.809649848937988281e+01 -1.207183837890625000e+00 -1.724350452423095703e-01 2.053248509764671326e-02 -1.242277249693870544e-01 9.769400954246520996e-01 +-1.399778175354003906e+01 -1.809504318237304688e+01 -1.207100749015808105e+00 -1.722651720046997070e-01 2.192180231213569641e-02 -1.329989433288574219e-01 9.757844805717468262e-01 +-1.399128532409667969e+01 -1.809384727478027344e+01 -1.207037329673767090e+00 -1.721656471490859985e-01 2.272762730717658997e-02 -1.404699087142944336e-01 9.747360944747924805e-01 +-1.398701858520507812e+01 -1.809292030334472656e+01 -1.206994652748107910e+00 -1.721377372741699219e-01 2.301858924329280853e-02 -1.467078775167465210e-01 9.738149046897888184e-01 +-1.398499679565429688e+01 -1.809226608276367188e+01 -1.206970214843750000e+00 -1.721778661012649536e-01 2.286203764379024506e-02 -1.517801433801651001e-01 9.730338454246520996e-01 +-1.398523807525634766e+01 -1.809188461303710938e+01 -1.206966519355773926e+00 -1.722793132066726685e-01 2.232120744884014130e-02 -1.557542830705642700e-01 9.724001884460449219e-01 +-1.397761917114257812e+01 -1.809093666076660156e+01 -1.206903100013732910e+00 -1.724327653646469116e-01 2.145808935165405273e-02 -1.586971580982208252e-01 9.719166159629821777e-01 +-1.396215820312500000e+01 -1.808941841125488281e+01 -1.206783413887023926e+00 -1.726271212100982666e-01 2.033315971493721008e-02 -1.606758087873458862e-01 9.715810418128967285e-01 +-1.393886661529541016e+01 -1.808732795715332031e+01 -1.206604003906250000e+00 -1.728504449129104614e-01 1.900516077876091003e-02 -1.617571413516998291e-01 9.713887572288513184e-01 +-1.390776252746582031e+01 -1.808465385437011719e+01 -1.206368327140808105e+00 -1.730903536081314087e-01 1.753239706158638000e-02 -1.620070487260818481e-01 9.713321328163146973e-01 +-1.386885452270507812e+01 -1.808140182495117188e+01 -1.206072926521301270e+00 -1.733345538377761841e-01 1.597235724329948425e-02 -1.614910960197448730e-01 9.714013934135437012e-01 +-1.382213211059570312e+01 -1.807789993286132812e+01 -1.205638408660888672e+00 -1.735712736845016479e-01 1.438270509243011475e-02 -1.602747738361358643e-01 9.715853929519653320e-01 +-1.376761054992675781e+01 -1.807411575317382812e+01 -1.205068349838256836e+00 -1.737896353006362915e-01 1.282062474638223648e-02 -1.584229916334152222e-01 9.718718528747558594e-01 +-1.370531749725341797e+01 -1.806981468200683594e+01 -1.204416513442993164e+00 -1.739798337221145630e-01 1.134419813752174377e-02 -1.559999138116836548e-01 9.722481369972229004e-01 +-1.363526439666748047e+01 -1.806501007080078125e+01 -1.203685283660888672e+00 -1.741333454847335815e-01 1.001187786459922791e-02 -1.530704051256179810e-01 9.727007746696472168e-01 +-1.355746555328369141e+01 -1.805967712402343750e+01 -1.202871084213256836e+00 -1.742431223392486572e-01 8.882367983460426331e-03 -1.496979445219039917e-01 9.732167720794677734e-01 +-1.347193241119384766e+01 -1.805382728576660156e+01 -1.201976299285888672e+00 -1.743036210536956787e-01 8.014990016818046570e-03 -1.459468007087707520e-01 9.737830758094787598e-01 +-1.337867641448974609e+01 -1.804744148254394531e+01 -1.200998544692993164e+00 -1.743105649948120117e-01 7.470415905117988586e-03 -1.418801993131637573e-01 9.743869900703430176e-01 +-1.327770996093750000e+01 -1.804051780700683594e+01 -1.199940204620361328e+00 -1.742613017559051514e-01 7.308905944228172302e-03 -1.375627517700195312e-01 9.750158786773681641e-01 +-1.316905403137207031e+01 -1.803308486938476562e+01 -1.198902606964111328e+00 -1.737243086099624634e-01 7.511528208851814270e-03 -1.330658644437789917e-01 9.757340550422668457e-01 +-1.305272388458251953e+01 -1.802510261535644531e+01 -1.197773456573486328e+00 -1.731890290975570679e-01 8.101944811642169952e-03 -1.284751296043395996e-01 9.764395356178283691e-01 +-1.292867183685302734e+01 -1.801776313781738281e+01 -1.196290254592895508e+00 -1.726641356945037842e-01 9.012149646878242493e-03 -1.238846331834793091e-01 9.771173596382141113e-01 +-1.279695129394531250e+01 -1.801057624816894531e+01 -1.194560527801513672e+00 -1.721579730510711670e-01 1.017384883016347885e-02 -1.193878725171089172e-01 9.777548909187316895e-01 +-1.265762901306152344e+01 -1.800292396545410156e+01 -1.192717313766479492e+00 -1.716792434453964233e-01 1.151873078197240829e-02 -1.150800734758377075e-01 9.783405065536499023e-01 +-1.251072597503662109e+01 -1.799479866027832031e+01 -1.190762877464294434e+00 -1.712377369403839111e-01 1.297887600958347321e-02 -1.110554561018943787e-01 9.788646101951599121e-01 +-1.235627460479736328e+01 -1.798620986938476562e+01 -1.188693761825561523e+00 -1.708422154188156128e-01 1.448602043092250824e-02 -1.074089184403419495e-01 9.793193936347961426e-01 +-1.219427490234375000e+01 -1.797763061523437500e+01 -1.186416029930114746e+00 -1.705030798912048340e-01 1.597205176949501038e-02 -1.042353734374046326e-01 9.796981811523437500e-01 +-1.202464580535888672e+01 -1.797151756286621094e+01 -1.183442354202270508e+00 -1.702296584844589233e-01 1.736923307180404663e-02 -1.016294136643409729e-01 9.799957871437072754e-01 +-1.184753894805908203e+01 -1.796508789062500000e+01 -1.180319786071777344e+00 -1.700322329998016357e-01 1.860933378338813782e-02 -9.968673437833786011e-02 9.802067875862121582e-01 +-1.166297626495361328e+01 -1.795832443237304688e+01 -1.177045822143554688e+00 -1.699207425117492676e-01 1.962437480688095093e-02 -9.850159287452697754e-02 9.803261756896972656e-01 +-1.147096920013427734e+01 -1.795227050781250000e+01 -1.173431396484375000e+00 -1.699048429727554321e-01 2.034642919898033142e-02 -9.816955029964447021e-02 9.803473353385925293e-01 +-1.127146911621093750e+01 -1.795106887817382812e+01 -1.168714523315429688e+00 -1.699938774108886719e-01 2.070740051567554474e-02 -9.878458082675933838e-02 9.802626967430114746e-01 +-1.106458854675292969e+01 -1.794975471496582031e+01 -1.163802504539489746e+00 -1.701969504356384277e-01 2.063925191760063171e-02 -1.004416123032569885e-01 9.800604581832885742e-01 +-1.085038566589355469e+01 -1.795021438598632812e+01 -1.158355712890625000e+00 -1.705220788717269897e-01 2.007384411990642548e-02 -1.032341718673706055e-01 9.797254204750061035e-01 +-1.062896347045898438e+01 -1.795693778991699219e+01 -1.151569843292236328e+00 -1.709766089916229248e-01 1.894273981451988220e-02 -1.072558686137199402e-01 9.792366027832031250e-01 +-1.040914535522460938e+01 -1.796353530883789062e+01 -1.144811987876892090e+00 -1.715665906667709351e-01 1.717771589756011963e-02 -1.125989109277725220e-01 9.785659313201904297e-01 +-1.019149208068847656e+01 -1.797900390625000000e+01 -1.136512398719787598e+00 -1.722959578037261963e-01 1.471004076302051544e-02 -1.193545386195182800e-01 9.776769280433654785e-01 +-9.975522041320800781e+00 -1.799488258361816406e+01 -1.128155469894409180e+00 -1.731677055358886719e-01 1.147142145782709122e-02 -1.276125013828277588e-01 9.765226840972900391e-01 +-9.762405395507812500e+00 -1.802145957946777344e+01 -1.118013858795166016e+00 -1.741821318864822388e-01 7.393093779683113098e-03 -1.374605298042297363e-01 9.750438332557678223e-01 +-9.551672935485839844e+00 -1.805210876464843750e+01 -1.107297301292419434e+00 -1.751508414745330811e-01 2.409156411886215210e-03 -1.489315479993820190e-01 9.732089638710021973e-01 +-9.343825340270996094e+00 -1.809015655517578125e+01 -1.095410108566284180e+00 -1.763336509466171265e-01 -3.357563167810440063e-03 -1.618455797433853149e-01 9.709279537200927734e-01 +-9.140208244323730469e+00 -1.813973617553710938e+01 -1.081787109375000000e+00 -1.778234690427780151e-01 -9.767286479473114014e-03 -1.759740561246871948e-01 9.681510329246520996e-01 +-8.940580368041992188e+00 -1.819780158996582031e+01 -1.067119121551513672e+00 -1.793223172426223755e-01 -1.674799993634223938e-02 -1.910861283540725708e-01 9.649089574813842773e-01 +-8.744725227355957031e+00 -1.826290512084960938e+01 -1.051865220069885254e+00 -1.807363778352737427e-01 -2.420132979750633240e-02 -2.069481462240219116e-01 9.612082242965698242e-01 +-8.550765037536621094e+00 -1.832936477661132812e+01 -1.037139892578125000e+00 -1.821496188640594482e-01 -3.199212625622749329e-02 -2.233315557241439819e-01 9.570375680923461914e-01 +-8.358754158020019531e+00 -1.839709854125976562e+01 -1.021613717079162598e+00 -1.835409551858901978e-01 -4.000447690486907959e-02 -2.400090098381042480e-01 9.524222612380981445e-01 +-8.169313430786132812e+00 -1.846738243103027344e+01 -1.003211617469787598e+00 -1.848921775817871094e-01 -4.812299087643623352e-02 -2.567564845085144043e-01 9.474044442176818848e-01 +-7.983161926269531250e+00 -1.854133224487304688e+01 -9.799682497978210449e-01 -1.861882060766220093e-01 -5.623311549425125122e-02 -2.733535170555114746e-01 9.420455098152160645e-01 +-7.801586627960205078e+00 -1.862045860290527344e+01 -9.491564631462097168e-01 -1.874181628227233887e-01 -6.422104686498641968e-02 -2.895855307579040527e-01 9.364241957664489746e-01 +-7.624364376068115234e+00 -1.870360755920410156e+01 -9.116979837417602539e-01 -1.885739862918853760e-01 -7.197412848472595215e-02 -3.052431046962738037e-01 9.306375980377197266e-01 +-7.451340675354003906e+00 -1.879007339477539062e+01 -8.682433962821960449e-01 -1.896513700485229492e-01 -7.938150316476821899e-02 -3.201229274272918701e-01 9.247984290122985840e-01 +-7.282464981079101562e+00 -1.887909126281738281e+01 -8.187023997306823730e-01 -1.906493306159973145e-01 -8.633489906787872314e-02 -3.340278267860412598e-01 9.190346002578735352e-01 +-7.118041038513183594e+00 -1.897014999389648438e+01 -7.621923685073852539e-01 -1.915690600872039795e-01 -9.272623807191848755e-02 -3.467673957347869873e-01 9.134853482246398926e-01 +-6.958520412445068359e+00 -1.906286621093750000e+01 -6.979882717132568359e-01 -1.924146562814712524e-01 -9.845100343227386475e-02 -3.581552803516387939e-01 9.083000421524047852e-01 +-6.804482936859130859e+00 -1.915691375732421875e+01 -6.254442930221557617e-01 -1.931910961866378784e-01 -1.034047901630401611e-01 -3.680100739002227783e-01 9.036333560943603516e-01 +-6.656631469726562500e+00 -1.925200653076171875e+01 -5.439599752426147461e-01 -1.939039826393127441e-01 -1.074857339262962341e-01 -3.761520385742187500e-01 8.996430635452270508e-01 +-6.515871524810791016e+00 -1.934782600402832031e+01 -4.528369009494781494e-01 -1.945595145225524902e-01 -1.105909198522567749e-01 -3.824028372764587402e-01 8.964843153953552246e-01 +-6.385496616363525391e+00 -1.944392967224121094e+01 -3.488501012325286865e-01 -1.951622217893600464e-01 -1.126182675361633301e-01 -3.865822553634643555e-01 8.943058252334594727e-01 +-6.265444755554199219e+00 -1.953947257995605469e+01 -2.338836640119552612e-01 -1.957140564918518066e-01 -1.134633868932723999e-01 -3.885057568550109863e-01 8.932442069053649902e-01 +-6.157030582427978516e+00 -1.963372993469238281e+01 -1.080126911401748657e-01 -1.962120831012725830e-01 -1.130470186471939087e-01 -3.880454897880554199e-01 8.933877944946289062e-01 +-6.059088706970214844e+00 -1.972624015808105469e+01 2.670959383249282837e-02 -1.966399848461151123e-01 -1.113923639059066772e-01 -3.853203356266021729e-01 8.946801424026489258e-01 +-5.969214439392089844e+00 -1.981676292419433594e+01 1.674096584320068359e-01 -1.969755291938781738e-01 -1.085469126701354980e-01 -3.805048465728759766e-01 8.970141410827636719e-01 +-5.885583877563476562e+00 -1.990472602844238281e+01 3.124322295188903809e-01 -1.971935629844665527e-01 -1.045555323362350464e-01 -3.737675249576568604e-01 9.002670049667358398e-01 +-5.803256034851074219e+00 -1.999086380004882812e+01 4.581799209117889404e-01 -1.972658038139343262e-01 -9.946345537900924683e-02 -3.652730286121368408e-01 9.043057560920715332e-01 +-5.719892024993896484e+00 -2.007541465759277344e+01 6.031121611595153809e-01 -1.971632838249206543e-01 -9.331437945365905762e-02 -3.551842272281646729e-01 9.089902639389038086e-01 +-5.633288860321044922e+00 -2.015843200683593750e+01 7.457769513130187988e-01 -1.968562752008438110e-01 -8.615399897098541260e-02 -3.436643779277801514e-01 9.141771793365478516e-01 +-5.540076732635498047e+00 -2.023985862731933594e+01 8.839520215988159180e-01 -1.963153928518295288e-01 -7.802811264991760254e-02 -3.308785259723663330e-01 9.197234511375427246e-01 +-5.434156894683837891e+00 -2.031917953491210938e+01 1.012612223625183105e+00 -1.955126374959945679e-01 -6.898463517427444458e-02 -3.169950842857360840e-01 9.254890680313110352e-01 +-5.314202308654785156e+00 -2.039573287963867188e+01 1.128260493278503418e+00 -1.944207549095153809e-01 -5.907347053289413452e-02 -3.021857738494873047e-01 9.313402175903320312e-01 +-5.178050518035888672e+00 -2.046792030334472656e+01 1.225153803825378418e+00 -1.930157095193862915e-01 -4.834614321589469910e-02 -2.866281270980834961e-01 9.371509552001953125e-01 +-5.027757644653320312e+00 -2.053473663330078125e+01 1.300881981849670410e+00 -1.893039792776107788e-01 -3.742266073822975159e-02 -2.704261243343353271e-01 9.432036876678466797e-01 +-4.867827892303466797e+00 -2.059556579589843750e+01 1.357622623443603516e+00 -1.852363497018814087e-01 -2.571909502148628235e-02 -2.538959681987762451e-01 9.489797949790954590e-01 +-4.701978206634521484e+00 -2.065056037902832031e+01 1.398209810256958008e+00 -1.813626885414123535e-01 -1.315394416451454163e-02 -2.372401058673858643e-01 9.542806744575500488e-01 +-4.532223224639892578e+00 -2.069898414611816406e+01 1.422392487525939941e+00 -1.777279376983642578e-01 1.920461654663085938e-04 -2.206349968910217285e-01 9.590271115303039551e-01 +-4.361598491668701172e+00 -2.074292373657226562e+01 1.436777949333190918e+00 -1.743630915880203247e-01 1.422951556742191315e-02 -2.042547166347503662e-01 9.631588459014892578e-01 +-4.190948486328125000e+00 -2.078312873840332031e+01 1.443652868270874023e+00 -1.712842732667922974e-01 2.886412292718887329e-02 -1.882722675800323486e-01 9.666343331336975098e-01 +-4.020798206329345703e+00 -2.082008171081542969e+01 1.444533705711364746e+00 -1.684927195310592651e-01 4.399876669049263000e-02 -1.728609502315521240e-01 9.694294333457946777e-01 +-3.851472377777099609e+00 -2.085371017456054688e+01 1.439882755279541016e+00 -1.659740358591079712e-01 5.953872203826904297e-02 -1.581941694021224976e-01 9.715360999107360840e-01 +-3.683309555053710938e+00 -2.088486862182617188e+01 1.432135581970214844e+00 -1.636987477540969849e-01 7.539305090904235840e-02 -1.444470286369323730e-01 9.729613065719604492e-01 +-3.516623497009277344e+00 -2.091453170776367188e+01 1.422302246093750000e+00 -1.584810763597488403e-01 9.103906154632568359e-02 -1.320538371801376343e-01 9.742470979690551758e-01 +-3.351352214813232422e+00 -2.094268989562988281e+01 1.411395192146301270e+00 -1.529230773448944092e-01 1.067758351564407349e-01 -1.208692938089370728e-01 9.749891757965087891e-01 +-3.186737537384033203e+00 -2.096947669982910156e+01 1.399062514305114746e+00 -1.470785140991210938e-01 1.224749907851219177e-01 -1.108664870262145996e-01 9.752315282821655273e-01 +-3.022862434387207031e+00 -2.099501991271972656e+01 1.384777188301086426e+00 -1.410022526979446411e-01 1.380095779895782471e-01 -1.020165681838989258e-01 9.750201702117919922e-01 +-2.859816312789916992e+00 -2.101975059509277344e+01 1.368644952774047852e+00 -1.347483843564987183e-01 1.532539427280426025e-01 -9.429048746824264526e-02 9.744052290916442871e-01 +-2.697672605514526367e+00 -2.104387092590332031e+01 1.350438237190246582e+00 -1.283714473247528076e-01 1.680841445922851562e-01 -8.765873312950134277e-02 9.734395146369934082e-01 +-2.536515951156616211e+00 -2.106760787963867188e+01 1.329924345016479492e+00 -1.219269409775733948e-01 1.823779642581939697e-01 -8.209069073200225830e-02 9.721795916557312012e-01 +-2.376441240310668945e+00 -2.109122467041015625e+01 1.306878685951232910e+00 -1.154689937829971313e-01 1.960151493549346924e-01 -7.755572348833084106e-02 9.706854224205017090e-01 +-2.217573881149291992e+00 -2.111502838134765625e+01 1.280995488166809082e+00 -1.090524122118949890e-01 2.088771462440490723e-01 -7.402298599481582642e-02 9.690194129943847656e-01 +-2.060139656066894531e+00 -2.113944244384765625e+01 1.251676559448242188e+00 -1.027315035462379456e-01 2.208474874496459961e-01 -7.146216928958892822e-02 9.672465920448303223e-01 +-1.904189229011535645e+00 -2.116470146179199219e+01 1.219267606735229492e+00 -9.656047075986862183e-02 2.318109124898910522e-01 -6.984190642833709717e-02 9.654335379600524902e-01 +-1.749730229377746582e+00 -2.119121551513671875e+01 1.184332847595214844e+00 -9.059253334999084473e-02 2.416539192199707031e-01 -6.913200020790100098e-02 9.636478424072265625e-01 +-1.596755623817443848e+00 -2.121939849853515625e+01 1.147445678710937500e+00 -8.488062024116516113e-02 2.502637505531311035e-01 -6.930173933506011963e-02 9.619567394256591797e-01 +-1.445254445075988770e+00 -2.124968147277832031e+01 1.109163761138916016e+00 -7.947713881731033325e-02 2.575280368328094482e-01 -7.032090425491333008e-02 9.604257345199584961e-01 +-1.295220732688903809e+00 -2.128248977661132812e+01 1.070039033889770508e+00 -7.443322986364364624e-02 2.633346617221832275e-01 -7.215952128171920776e-02 9.591181874275207520e-01 +-1.146725416183471680e+00 -2.131830596923828125e+01 1.030656099319458008e+00 -6.996620446443557739e-02 2.663185894489288330e-01 -7.495104521512985229e-02 9.584161043167114258e-01 +-9.999613165855407715e-01 -2.135830497741699219e+01 9.917449951171875000e-01 -6.614603102207183838e-02 2.662808001041412354e-01 -7.866744697093963623e-02 9.584000706672668457e-01 +-8.547224998474121094e-01 -2.140241241455078125e+01 9.539013504981994629e-01 -6.259322166442871094e-02 2.662970125675201416e-01 -8.287088572978973389e-02 9.582799673080444336e-01 +-7.111460566520690918e-01 -2.145109748840332031e+01 9.177319407463073730e-01 -5.932302400469779968e-02 2.663649320602416992e-01 -8.752603083848953247e-02 9.580551385879516602e-01 +-5.694254040718078613e-01 -2.150481796264648438e+01 8.838702440261840820e-01 -5.633988976478576660e-02 2.664817869663238525e-01 -9.259188920259475708e-02 9.577264785766601562e-01 +-4.298233687877655029e-01 -2.156326675415039062e+01 8.526470661163330078e-01 -5.446594208478927612e-02 2.611390650272369385e-01 -9.870256483554840088e-02 9.586958885192871094e-01 +-2.920832037925720215e-01 -2.162565803527832031e+01 8.238085508346557617e-01 -5.321475118398666382e-02 2.537637054920196533e-01 -1.053738519549369812e-01 9.600356817245483398e-01 +-1.560231447219848633e-01 -2.169121932983398438e+01 7.971881031990051270e-01 -5.256302654743194580e-02 2.444927394390106201e-01 -1.125296354293823242e-01 9.616639018058776855e-01 +-2.139944955706596375e-02 -2.175920295715332031e+01 7.726220488548278809e-01 -5.248617380857467651e-02 2.334626466035842896e-01 -1.200938150286674500e-01 9.634925127029418945e-01 +1.120875328779220581e-01 -2.182886123657226562e+01 7.500683665275573730e-01 -5.295992642641067505e-02 2.208105325698852539e-01 -1.279888451099395752e-01 9.654309749603271484e-01 +2.449163943529129028e-01 -2.189912986755371094e+01 7.292101979255676270e-01 -5.395935475826263428e-02 2.066756784915924072e-01 -1.361361443996429443e-01 9.673885107040405273e-01 +3.775641918182373047e-01 -2.196906280517578125e+01 7.098785042762756348e-01 -5.545983836054801941e-02 1.911994516849517822e-01 -1.444572955369949341e-01 9.692776799201965332e-01 +5.106136798858642578e-01 -2.203748512268066406e+01 6.919341683387756348e-01 -5.743588507175445557e-02 1.745266765356063843e-01 -1.528737545013427734e-01 9.710155129432678223e-01 +6.447994709014892578e-01 -2.210284042358398438e+01 6.752325296401977539e-01 -5.986256152391433716e-02 1.568054258823394775e-01 -1.613068580627441406e-01 9.725269079208374023e-01 +7.830833792686462402e-01 -2.215785598754882812e+01 6.589977741241455078e-01 -6.271472573280334473e-02 1.381875276565551758e-01 -1.696794927120208740e-01 9.737452864646911621e-01 +9.247810244560241699e-01 -2.220174217224121094e+01 6.425030231475830078e-01 -6.596759706735610962e-02 1.188281029462814331e-01 -1.779153048992156982e-01 9.746149182319641113e-01 +1.067692518234252930e+00 -2.223961830139160156e+01 6.257092356681823730e-01 -6.959612667560577393e-02 9.888577461242675781e-02 -1.859395205974578857e-01 9.750919938087463379e-01 +1.211504101753234863e+00 -2.227413940429687500e+01 6.087017655372619629e-01 -7.357654720544815063e-02 7.852183282375335693e-02 -1.936799436807632446e-01 9.751455783843994141e-01 +1.356289744377136230e+00 -2.230418968200683594e+01 5.912957787513732910e-01 -7.788492739200592041e-02 5.789966508746147156e-02 -2.010660767555236816e-01 9.747585058212280273e-01 +1.501374959945678711e+00 -2.233302116394042969e+01 5.737719535827636719e-01 -8.249861747026443481e-02 3.718444705009460449e-02 -2.080305963754653931e-01 9.739274382591247559e-01 +1.646695852279663086e+00 -2.236085891723632812e+01 5.561267137527465820e-01 -8.739582449197769165e-02 1.654189079999923706e-02 -2.145096361637115479e-01 9.726633429527282715e-01 +1.792532801628112793e+00 -2.238619613647460938e+01 5.381982326507568359e-01 -9.255601465702056885e-02 -3.862014040350914001e-03 -2.204417586326599121e-01 9.709911942481994629e-01 +1.938458919525146484e+00 -2.241155624389648438e+01 5.202868580818176270e-01 -9.795944392681121826e-02 -2.386232092976570129e-02 -2.257693856954574585e-01 9.689492583274841309e-01 +2.084487915039062500e+00 -2.243694686889648438e+01 5.024065971374511719e-01 -1.035886555910110474e-01 -4.329508915543556213e-02 -2.304384112358093262e-01 9.665883779525756836e-01 +2.230934143066406250e+00 -2.246038055419921875e+01 4.842815995216369629e-01 -1.094269901514053345e-01 -6.199895590543746948e-02 -2.343970835208892822e-01 9.639708995819091797e-01 +2.377528190612792969e+00 -2.248369598388671875e+01 4.661981165409088135e-01 -1.154559776186943054e-01 -7.984423637390136719e-02 -2.376135885715484619e-01 9.611631035804748535e-01 +2.524234294891357422e+00 -2.250704956054687500e+01 4.481854140758514404e-01 -1.216437593102455139e-01 -9.682249277830123901e-02 -2.401245534420013428e-01 9.582110643386840820e-01 +2.671039104461669922e+00 -2.253044891357421875e+01 4.302423000335693359e-01 -1.279535591602325439e-01 -1.129571571946144104e-01 -2.419821918010711670e-01 9.551507830619812012e-01 +2.818022966384887695e+00 -2.255319786071777344e+01 4.122344851493835449e-01 -1.343493461608886719e-01 -1.282716542482376099e-01 -2.432388663291931152e-01 9.520144462585449219e-01 +2.965167999267578125e+00 -2.257532119750976562e+01 3.941674828529357910e-01 -1.407942622900009155e-01 -1.427913308143615723e-01 -2.439457178115844727e-01 9.488298296928405762e-01 +3.112375974655151367e+00 -2.259748077392578125e+01 3.761584460735321045e-01 -1.472518146038055420e-01 -1.565414667129516602e-01 -2.441536337137222290e-01 9.456219077110290527e-01 +3.259636163711547852e+00 -2.261967277526855469e+01 3.582000732421875000e-01 -1.536853909492492676e-01 -1.695484369993209839e-01 -2.439132332801818848e-01 9.424121379852294922e-01 +3.406939029693603516e+00 -2.264188385009765625e+01 3.402874767780303955e-01 -1.600580364465713501e-01 -1.818387359380722046e-01 -2.432737946510314941e-01 9.392198324203491211e-01 +3.554276466369628906e+00 -2.266412544250488281e+01 3.224102854728698730e-01 -1.663337945938110352e-01 -1.934393793344497681e-01 -2.422850728034973145e-01 9.360620379447937012e-01 +3.701730251312255859e+00 -2.268562889099121094e+01 3.043792545795440674e-01 -1.724757254123687744e-01 -2.043778002262115479e-01 -2.409955710172653198e-01 9.329538941383361816e-01 +3.849213838577270508e+00 -2.270705032348632812e+01 2.863415479660034180e-01 -1.784478276968002319e-01 -2.146816551685333252e-01 -2.394533157348632812e-01 9.299087524414062500e-01 +3.996708631515502930e+00 -2.272849464416503906e+01 2.683117687702178955e-01 -1.842135637998580933e-01 -2.243779599666595459e-01 -2.377061247825622559e-01 9.269389510154724121e-01 +4.144206523895263672e+00 -2.274995613098144531e+01 2.502771019935607910e-01 -1.897367388010025024e-01 -2.334952950477600098e-01 -2.358017265796661377e-01 9.240548610687255859e-01 +4.291700839996337891e+00 -2.277143096923828125e+01 2.322283834218978882e-01 -1.949817240238189697e-01 -2.420607805252075195e-01 -2.337866723537445068e-01 9.212667942047119141e-01 +4.439185619354248047e+00 -2.279292488098144531e+01 2.141534388065338135e-01 -1.999120414257049561e-01 -2.501026988029479980e-01 -2.317075878381729126e-01 9.185833930969238281e-01 +4.586654663085937500e+00 -2.281444358825683594e+01 1.960394233465194702e-01 -2.044924050569534302e-01 -2.576487660408020020e-01 -2.296108454465866089e-01 9.160124063491821289e-01 +4.734113693237304688e+00 -2.283577537536621094e+01 1.777484118938446045e-01 -2.086867988109588623e-01 -2.647267580032348633e-01 -2.275423109531402588e-01 9.135611653327941895e-01 +4.881546497344970703e+00 -2.285709953308105469e+01 1.593688875436782837e-01 -2.124596685171127319e-01 -2.713642418384552002e-01 -2.255471348762512207e-01 9.112358093261718750e-01 +5.028945446014404297e+00 -2.287844276428222656e+01 1.409149169921875000e-01 -2.157747149467468262e-01 -2.775894701480865479e-01 -2.236704975366592407e-01 9.090417027473449707e-01 +5.176304817199707031e+00 -2.289980506896972656e+01 1.223730444908142090e-01 -2.185968756675720215e-01 -2.834294438362121582e-01 -2.219573408365249634e-01 9.069829583168029785e-01 +5.323926448822021484e+00 -2.292157745361328125e+01 1.032061725854873657e-01 -2.183007597923278809e-01 -2.895419895648956299e-01 -2.196118384599685669e-01 9.056935310363769531e-01 +5.471455097198486328e+00 -2.294329071044921875e+01 8.406127989292144775e-02 -2.180402576923370361e-01 -2.951793372631072998e-01 -2.176025211811065674e-01 9.044205546379089355e-01 +5.618889808654785156e+00 -2.296496009826660156e+01 6.493835151195526123e-02 -2.178272604942321777e-01 -3.003686070442199707e-01 -2.159234732389450073e-01 9.031649827957153320e-01 +5.766230106353759766e+00 -2.298657608032226562e+01 4.583679139614105225e-02 -2.176707684993743896e-01 -3.051361739635467529e-01 -2.145657837390899658e-01 9.019272923469543457e-01 +5.916031837463378906e+00 -2.300862312316894531e+01 2.632995508611202240e-02 -2.175770252943038940e-01 -3.095074892044067383e-01 -2.135170549154281616e-01 9.007084369659423828e-01 +6.068310260772705078e+00 -2.303104972839355469e+01 6.466064136475324631e-03 -2.175496369600296021e-01 -3.135075569152832031e-01 -2.127615511417388916e-01 8.995097279548645020e-01 +6.223081111907958984e+00 -2.305381202697753906e+01 -1.371154747903347015e-02 -2.175899446010589600e-01 -3.171609640121459961e-01 -2.122813165187835693e-01 8.983318805694580078e-01 +6.380347251892089844e+00 -2.307691383361816406e+01 -3.420227020978927612e-02 -2.176974266767501831e-01 -3.204920291900634766e-01 -2.120563983917236328e-01 8.971759676933288574e-01 +6.540111064910888672e+00 -2.310035514831542969e+01 -5.500915274024009705e-02 -2.178691923618316650e-01 -3.235246837139129639e-01 -2.120636552572250366e-01 8.960434198379516602e-01 +6.702379703521728516e+00 -2.312413978576660156e+01 -7.613097876310348511e-02 -2.181010395288467407e-01 -3.262832164764404297e-01 -2.122789770364761353e-01 8.949350714683532715e-01 +6.867156982421875000e+00 -2.314827537536621094e+01 -9.756835550069808960e-02 -2.183872163295745850e-01 -3.287917077541351318e-01 -2.126764357089996338e-01 8.938522338867187500e-01 +7.034446716308593750e+00 -2.317276382446289062e+01 -1.193243414163589478e-01 -2.187206745147705078e-01 -3.310744464397430420e-01 -2.132287174463272095e-01 8.927958011627197266e-01 +7.204215526580810547e+00 -2.319782638549804688e+01 -1.414691060781478882e-01 -2.190932780504226685e-01 -3.331558704376220703e-01 -2.139072418212890625e-01 8.917673230171203613e-01 +7.376455307006835938e+00 -2.322353553771972656e+01 -1.640246510505676270e-01 -2.194961309432983398e-01 -3.350614905357360840e-01 -2.146829664707183838e-01 8.907672762870788574e-01 +7.558326244354248047e+00 -2.325066757202148438e+01 -1.878265291452407837e-01 -2.199192792177200317e-01 -3.368162810802459717e-01 -2.155251652002334595e-01 8.897972106933593750e-01 +7.749835491180419922e+00 -2.327924728393554688e+01 -2.128747552633285522e-01 -2.203524261713027954e-01 -3.384456932544708252e-01 -2.164032459259033203e-01 8.888582587242126465e-01 +7.950988769531250000e+00 -2.330927276611328125e+01 -2.391711324453353882e-01 -2.207848131656646729e-01 -3.399763405323028564e-01 -2.172861248254776001e-01 8.879509568214416504e-01 +8.161792755126953125e+00 -2.334073638916015625e+01 -2.667163014411926270e-01 -2.212050259113311768e-01 -3.414342701435089111e-01 -2.181417942047119141e-01 8.870766758918762207e-01 +8.382266998291015625e+00 -2.337367630004882812e+01 -2.955285608768463135e-01 -2.215003967285156250e-01 -3.428717851638793945e-01 -2.188988626003265381e-01 8.862617015838623047e-01 +8.612287521362304688e+00 -2.340854835510253906e+01 -3.256640434265136719e-01 -2.219618260860443115e-01 -3.442403376102447510e-01 -2.196419537067413330e-01 8.854314684867858887e-01 +8.851962089538574219e+00 -2.344560432434082031e+01 -3.571130335330963135e-01 -2.221293747425079346e-01 -3.441322743892669678e-01 -2.200729548931121826e-01 8.853244185447692871e-01 +9.101294517517089844e+00 -2.348416900634765625e+01 -3.898266553878784180e-01 -2.222552895545959473e-01 -3.440509736537933350e-01 -2.203968763351440430e-01 8.852438330650329590e-01 +9.360280036926269531e+00 -2.352424240112304688e+01 -4.238024950027465820e-01 -2.223452627658843994e-01 -3.439927995204925537e-01 -2.206283807754516602e-01 8.851861357688903809e-01 +9.628916740417480469e+00 -2.356582069396972656e+01 -4.590429663658142090e-01 -2.224056422710418701e-01 -3.439537882804870605e-01 -2.207837700843811035e-01 8.851474523544311523e-01 +9.907197952270507812e+00 -2.360889053344726562e+01 -4.955468773841857910e-01 -2.224431037902832031e-01 -3.439295589923858643e-01 -2.208801507949829102e-01 8.851233720779418945e-01 +1.019474601745605469e+01 -2.365554618835449219e+01 -5.336694121360778809e-01 -2.224644124507904053e-01 -3.439157605171203613e-01 -2.209350764751434326e-01 8.851096630096435547e-01 +1.048197364807128906e+01 -2.370218658447265625e+01 -5.717553496360778809e-01 -2.224770784378051758e-01 -3.439075946807861328e-01 -2.209676057100296021e-01 8.851014971733093262e-01 +1.076888275146484375e+01 -2.374876976013183594e+01 -6.097985506057739258e-01 -2.224884331226348877e-01 -3.439002335071563721e-01 -2.209968268871307373e-01 8.850942254066467285e-01 +1.105547142028808594e+01 -2.379530143737792969e+01 -6.477990746498107910e-01 -2.225062996149063110e-01 -3.438886702060699463e-01 -2.210428118705749512e-01 8.850827813148498535e-01 +1.134161949157714844e+01 -2.384237670898437500e+01 -6.858483552932739258e-01 -2.225385308265686035e-01 -3.438678085803985596e-01 -2.211257815361022949e-01 8.850619792938232422e-01 +1.162697315216064453e+01 -2.389184570312500000e+01 -7.242211699485778809e-01 -2.225930988788604736e-01 -3.438324630260467529e-01 -2.212662696838378906e-01 8.850269317626953125e-01 +1.191199398040771484e+01 -2.394124984741210938e+01 -7.625512480735778809e-01 -2.226775139570236206e-01 -3.437778353691101074e-01 -2.214835584163665771e-01 8.849725723266601562e-01 +1.219667434692382812e+01 -2.399057579040527344e+01 -8.008385896682739258e-01 -2.227995544672012329e-01 -3.436987400054931641e-01 -2.217977046966552734e-01 8.848938941955566406e-01 +1.248101043701171875e+01 -2.403982925415039062e+01 -8.390832543373107910e-01 -2.229660153388977051e-01 -3.435907959938049316e-01 -2.222263514995574951e-01 8.847863674163818359e-01 +1.276442241668701172e+01 -2.409189414978027344e+01 -8.776794075965881348e-01 -2.231833934783935547e-01 -3.434496223926544189e-01 -2.227861881256103516e-01 8.846454620361328125e-01 +1.304715538024902344e+01 -2.414550781250000000e+01 -9.164562821388244629e-01 -2.234573364257812500e-01 -3.432714343070983887e-01 -2.234919369220733643e-01 8.844674825668334961e-01 +1.332954025268554688e+01 -2.419902801513671875e+01 -9.551879763603210449e-01 -2.237923741340637207e-01 -3.430531024932861328e-01 -2.243553698062896729e-01 8.842488527297973633e-01 +1.361156749725341797e+01 -2.425247001647949219e+01 -9.938769340515136719e-01 -2.241918444633483887e-01 -3.427921831607818604e-01 -2.253852337598800659e-01 8.839869499206542969e-01 +1.389249801635742188e+01 -2.430917930603027344e+01 -1.032952904701232910e+00 -2.246578484773635864e-01 -3.424869775772094727e-01 -2.265873253345489502e-01 8.836795687675476074e-01 +1.417225646972656250e+01 -2.436950111389160156e+01 -1.072458505630493164e+00 -2.251906096935272217e-01 -3.421368896961212158e-01 -2.279623448848724365e-01 8.833258748054504395e-01 +1.445251178741455078e+01 -2.443052101135253906e+01 -1.112601280212402344e+00 -2.207838743925094604e-01 -3.398961424827575684e-01 -2.274083197116851807e-01 8.854436874389648438e-01 +1.473253631591796875e+01 -2.449156761169433594e+01 -1.152830839157104492e+00 -2.156427800655364990e-01 -3.374349474906921387e-01 -2.267166227102279663e-01 8.878262639045715332e-01 +1.501059627532958984e+01 -2.455951690673828125e+01 -1.194051504135131836e+00 -2.098293602466583252e-01 -3.348003625869750977e-01 -2.259006351232528687e-01 8.904207348823547363e-01 +1.528816604614257812e+01 -2.462841796875000000e+01 -1.235473632812500000e+00 -2.034060060977935791e-01 -3.320398628711700439e-01 -2.249738425016403198e-01 8.931754231452941895e-01 +1.556547927856445312e+01 -2.469728469848632812e+01 -1.276966571807861328e+00 -1.964354664087295532e-01 -3.292009234428405762e-01 -2.239504456520080566e-01 8.960390686988830566e-01 +1.584055137634277344e+01 -2.477307510375976562e+01 -1.319479942321777344e+00 -1.889812648296356201e-01 -3.263326883316040039e-01 -2.228447943925857544e-01 8.989622592926025391e-01 +1.611485099792480469e+01 -2.485056114196777344e+01 -1.362290024757385254e+00 -1.811068356037139893e-01 -3.234843015670776367e-01 -2.216712534427642822e-01 9.018979668617248535e-01 +1.638828277587890625e+01 -2.492979431152343750e+01 -1.405413746833801270e+00 -1.728771626949310303e-01 -3.207059502601623535e-01 -2.204457521438598633e-01 9.048009514808654785e-01 +1.665892982482910156e+01 -2.501667404174804688e+01 -1.449704527854919434e+00 -1.643574535846710205e-01 -3.180485963821411133e-01 -2.191843688488006592e-01 9.076287150382995605e-01 +1.692925453186035156e+01 -2.510351562500000000e+01 -1.494035601615905762e+00 -1.556134819984436035e-01 -3.155647218227386475e-01 -2.179037779569625854e-01 9.103413224220275879e-01 +1.719555282592773438e+01 -2.520039939880371094e+01 -1.539997577667236328e+00 -1.467118263244628906e-01 -3.133070170879364014e-01 -2.166214287281036377e-01 9.129017591476440430e-01 +1.746067047119140625e+01 -2.529924201965332031e+01 -1.586348891258239746e+00 -1.377195268869400024e-01 -3.113292455673217773e-01 -2.153556346893310547e-01 9.152755737304687500e-01 +1.772199058532714844e+01 -2.540629768371582031e+01 -1.634212613105773926e+00 -1.287038028240203857e-01 -3.096866011619567871e-01 -2.141248285770416260e-01 9.174311757087707520e-01 +1.797966957092285156e+01 -2.552020454406738281e+01 -1.683673024177551270e+00 -1.197323352098464966e-01 -3.084343373775482178e-01 -2.129480689764022827e-01 9.193396568298339844e-01 +1.823372077941894531e+01 -2.564036560058593750e+01 -1.735097646713256836e+00 -1.108731925487518311e-01 -3.076283633708953857e-01 -2.118457108736038208e-01 9.209740757942199707e-01 +1.848494148254394531e+01 -2.576435089111328125e+01 -1.789418935775756836e+00 -1.021941900253295898e-01 -3.073254525661468506e-01 -2.108376473188400269e-01 9.223095774650573730e-01 +1.873287773132324219e+01 -2.589137077331542969e+01 -1.849500656127929688e+00 -9.376326948404312134e-02 -3.075828254222869873e-01 -2.099442481994628906e-01 9.233225584030151367e-01 +1.897032737731933594e+01 -2.602990150451660156e+01 -1.922786831855773926e+00 -8.564832061529159546e-02 -3.084577918052673340e-01 -2.091858983039855957e-01 9.239910244941711426e-01 +1.918661117553710938e+01 -2.619185066223144531e+01 -2.010993719100952148e+00 -7.791706919670104980e-02 -3.100074231624603271e-01 -2.085837125778198242e-01 9.242928028106689453e-01 +1.939688873291015625e+01 -2.636192321777343750e+01 -2.097397327423095703e+00 -7.063672691583633423e-02 -3.122891485691070557e-01 -2.081581056118011475e-01 9.242056608200073242e-01 +1.960333633422851562e+01 -2.653208923339843750e+01 -2.191108465194702148e+00 -6.386113911867141724e-02 -3.153225779533386230e-01 -2.079208791255950928e-01 9.237220287322998047e-01 +1.980067253112792969e+01 -2.670052719116210938e+01 -2.304293155670166016e+00 -5.759227648377418518e-02 -3.189783096313476562e-01 -2.078484743833541870e-01 9.228949546813964844e-01 +1.997805976867675781e+01 -2.686252403259277344e+01 -2.452465772628784180e+00 -5.181930959224700928e-02 -3.230887651443481445e-01 -2.079097777605056763e-01 9.217927455902099609e-01 +2.010663986206054688e+01 -2.700180625915527344e+01 -2.658095598220825195e+00 -4.653124511241912842e-02 -3.274874389171600342e-01 -2.080729454755783081e-01 9.204848408699035645e-01 +2.013336563110351562e+01 -2.708231353759765625e+01 -2.923445940017700195e+00 -4.171708226203918457e-02 -3.320077657699584961e-01 -2.083068042993545532e-01 9.190422892570495605e-01 +2.006044387817382812e+01 -2.710072135925292969e+01 -3.192740440368652344e+00 -3.736594691872596741e-02 -3.364843428134918213e-01 -2.085808515548706055e-01 9.175381064414978027e-01 +1.991547203063964844e+01 -2.707538032531738281e+01 -3.430675029754638672e+00 -3.346715122461318970e-02 -3.407529592514038086e-01 -2.088648378849029541e-01 9.160473942756652832e-01 +1.971638298034667969e+01 -2.702067375183105469e+01 -3.618968486785888672e+00 -3.000989928841590881e-02 -3.446498513221740723e-01 -2.091291546821594238e-01 9.146478772163391113e-01 +1.947625732421875000e+01 -2.694724464416503906e+01 -3.741216897964477539e+00 -2.698357030749320984e-02 -3.480124771595001221e-01 -2.093446254730224609e-01 9.134188890457153320e-01 +1.921686553955078125e+01 -2.686842155456542969e+01 -3.807093381881713867e+00 -2.437749505043029785e-02 -3.506780266761779785e-01 -2.094826698303222656e-01 9.124405384063720703e-01 +1.895020866394042969e+01 -2.679267120361328125e+01 -3.836425781250000000e+00 -2.218068391084671021e-02 -3.524843454360961914e-01 -2.095136344432830811e-01 9.117931723594665527e-01 +1.867999649047851562e+01 -2.672515487670898438e+01 -3.840672492980957031e+00 -2.038262039422988892e-02 -3.532688617706298828e-01 -2.094088792800903320e-01 9.115555882453918457e-01 +1.840722465515136719e+01 -2.667154693603515625e+01 -3.829312562942504883e+00 -1.897224783897399902e-02 -3.528676629066467285e-01 -2.091383486986160278e-01 9.118034839630126953e-01 +1.813268661499023438e+01 -2.663323211669921875e+01 -3.809109926223754883e+00 -1.793826371431350708e-02 -3.511150181293487549e-01 -2.086706757545471191e-01 9.126078486442565918e-01 +1.785753250122070312e+01 -2.660956573486328125e+01 -3.780355215072631836e+00 -1.726895570755004883e-02 -3.478419482707977295e-01 -2.079730629920959473e-01 9.140322804450988770e-01 +1.758689117431640625e+01 -2.659740638732910156e+01 -3.744694709777832031e+00 -1.695244759321212769e-02 -3.428765535354614258e-01 -2.070108056068420410e-01 9.161303043365478516e-01 +1.732136154174804688e+01 -2.659372901916503906e+01 -3.702745199203491211e+00 -1.697567105293273926e-02 -3.360415697097778320e-01 -2.057455033063888550e-01 9.189432263374328613e-01 +1.706144523620605469e+01 -2.659532737731933594e+01 -3.654067277908325195e+00 -1.732514798641204834e-02 -3.271546661853790283e-01 -2.041360139846801758e-01 9.224956631660461426e-01 +1.680853652954101562e+01 -2.660082435607910156e+01 -3.593966007232666016e+00 -1.798589155077934265e-02 -3.160273730754852295e-01 -2.021358907222747803e-01 9.267923831939697266e-01 +1.656593704223632812e+01 -2.660934448242187500e+01 -3.513918399810791016e+00 -1.894154399633407593e-02 -3.024637699127197266e-01 -1.996945291757583618e-01 9.318148493766784668e-01 +1.633611869812011719e+01 -2.661814308166503906e+01 -3.412678241729736328e+00 -2.016894891858100891e-02 -2.863315939903259277e-01 -1.967687010765075684e-01 9.374909400939941406e-01 +1.611628913879394531e+01 -2.662369537353515625e+01 -3.300189018249511719e+00 -2.162275835871696472e-02 -2.677738666534423828e-01 -1.933650076389312744e-01 9.436310529708862305e-01 +1.589969062805175781e+01 -2.662261199951171875e+01 -3.191188812255859375e+00 -2.325204573571681976e-02 -2.470081895589828491e-01 -1.895039975643157959e-01 9.500181674957275391e-01 +1.568132400512695312e+01 -2.661123466491699219e+01 -3.097897768020629883e+00 -2.500555105507373810e-02 -2.242593169212341309e-01 -1.852087676525115967e-01 9.564414024353027344e-01 +1.545940303802490234e+01 -2.658679199218750000e+01 -3.031638145446777344e+00 -2.683191560208797455e-02 -1.997609585523605347e-01 -1.805061548948287964e-01 9.627009630203247070e-01 +1.523797893524169922e+01 -2.655461883544921875e+01 -2.986737012863159180e+00 -2.867994084954261780e-02 -1.737575680017471313e-01 -1.754268705844879150e-01 9.686130285263061523e-01 +1.501963710784912109e+01 -2.652018547058105469e+01 -2.953201770782470703e+00 -3.049903176724910736e-02 -1.465035229921340942e-01 -1.700080633163452148e-01 9.740142822265625000e-01 +1.480522632598876953e+01 -2.648631858825683594e+01 -2.924599647521972656e+00 -3.223899379372596741e-02 -1.182626336812973022e-01 -1.642913967370986938e-01 9.787660837173461914e-01 +1.459505081176757812e+01 -2.645399284362792969e+01 -2.897641420364379883e+00 -3.385071828961372375e-02 -8.930751681327819824e-02 -1.583246886730194092e-01 9.827570915222167969e-01 +1.438920879364013672e+01 -2.642324638366699219e+01 -2.871393918991088867e+00 -3.528673201799392700e-02 -5.991753563284873962e-02 -1.521615684032440186e-01 9.859064817428588867e-01 +1.418772411346435547e+01 -2.639378929138183594e+01 -2.845865488052368164e+00 -3.650032728910446167e-02 -3.037654981017112732e-02 -1.458611339330673218e-01 9.881647229194641113e-01 +1.399059867858886719e+01 -2.636548233032226562e+01 -2.821068048477172852e+00 -3.744756802916526794e-02 -9.714961051940917969e-04 -1.394872367382049561e-01 9.895150661468505859e-01 +1.379781436920166016e+01 -2.633822631835937500e+01 -2.797016620635986328e+00 -3.808545321226119995e-02 2.801096439361572266e-02 -1.331087201833724976e-01 9.899731874465942383e-01 +1.360933780670166016e+01 -2.631202507019042969e+01 -2.773726701736450195e+00 -3.837392851710319519e-02 5.628693476319313049e-02 -1.267978847026824951e-01 9.895865917205810547e-01 +1.342513370513916016e+01 -2.628688812255859375e+01 -2.751210927963256836e+00 -3.827369213104248047e-02 8.357636630535125732e-02 -1.206306293606758118e-01 9.884322285652160645e-01 +1.324517345428466797e+01 -2.626273918151855469e+01 -2.729470252990722656e+00 -3.774780780076980591e-02 1.096056178212165833e-01 -1.146849542856216431e-01 9.866149425506591797e-01 +1.306941986083984375e+01 -2.623960304260253906e+01 -2.708507061004638672e+00 -3.676097095012664795e-02 1.341087967157363892e-01 -1.090409010648727417e-01 9.842630028724670410e-01 +1.289782524108886719e+01 -2.621754837036132812e+01 -2.688323974609375000e+00 -3.527792543172836304e-02 1.568278819322586060e-01 -1.037788391113281250e-01 9.815245866775512695e-01 +1.273034286499023438e+01 -2.619669914245605469e+01 -2.668940305709838867e+00 -3.326483443379402161e-02 1.775135546922683716e-01 -9.898018091917037964e-02 9.785629510879516602e-01 +1.256687068939208984e+01 -2.617734336853027344e+01 -2.650635957717895508e+00 -3.068697638809680939e-02 1.959243118762969971e-01 -9.472550451755523682e-02 9.755507111549377441e-01 +1.240734195709228516e+01 -2.615968132019042969e+01 -2.633720636367797852e+00 -2.752725780010223389e-02 2.118933647871017456e-01 -9.106374531984329224e-02 9.726514816284179688e-01 +1.225172710418701172e+01 -2.614393424987792969e+01 -2.618526458740234375e+00 -2.384060062468051910e-02 2.255300134420394897e-01 -8.791892975568771362e-02 9.699681401252746582e-01 +1.210001945495605469e+01 -2.613039398193359375e+01 -2.605453968048095703e+00 -1.969877257943153381e-02 2.370096743106842041e-01 -8.518087863922119141e-02 9.675652384757995605e-01 +1.195223331451416016e+01 -2.611929702758789062e+01 -2.594952344894409180e+00 -1.517291553318500519e-02 2.465046793222427368e-01 -8.273734152317047119e-02 9.654842019081115723e-01 +1.180842876434326172e+01 -2.611089324951171875e+01 -2.587496280670166016e+00 -1.033360138535499573e-02 2.541842758655548096e-01 -8.047319948673248291e-02 9.637466669082641602e-01 +1.166873264312744141e+01 -2.610503768920898438e+01 -2.583181142807006836e+00 -5.250874906778335571e-03 2.602048218250274658e-01 -7.827369868755340576e-02 9.623612165451049805e-01 +1.153323745727539062e+01 -2.610152244567871094e+01 -2.581868886947631836e+00 -4.532914608716964722e-04 2.597315609455108643e-01 -7.625352591276168823e-02 9.626653790473937988e-01 +1.140217590332031250e+01 -2.609998512268066406e+01 -2.583013772964477539e+00 4.624022170901298523e-03 2.592605948448181152e-01 -7.393597811460494995e-02 9.629621505737304688e-01 +1.127563953399658203e+01 -2.610012054443359375e+01 -2.586120605468750000e+00 9.884547442197799683e-03 2.588075399398803711e-01 -7.123043388128280640e-02 9.632481932640075684e-01 +1.115369224548339844e+01 -2.610171318054199219e+01 -2.590780019760131836e+00 1.523126568645238876e-02 2.583893537521362305e-01 -6.804589182138442993e-02 9.635209441184997559e-01 +1.103638744354248047e+01 -2.610457420349121094e+01 -2.596641778945922852e+00 2.056868188083171844e-02 2.580237686634063721e-01 -6.429013609886169434e-02 9.637777209281921387e-01 +1.092376804351806641e+01 -2.610856437683105469e+01 -2.603400707244873047e+00 2.580112963914871216e-02 2.577296495437622070e-01 -5.986779555678367615e-02 9.640153646469116211e-01 +1.081586933135986328e+01 -2.611361312866210938e+01 -2.610776424407958984e+00 3.083451092243194580e-02 2.575255334377288818e-01 -5.467998981475830078e-02 9.642302393913269043e-01 +1.070365047454833984e+01 -2.612030220031738281e+01 -2.619052648544311523e+00 3.557673841714859009e-02 2.574303746223449707e-01 -4.862414672970771790e-02 9.644167423248291016e-01 +1.058720302581787109e+01 -2.612927246093750000e+01 -2.628027200698852539e+00 3.993793204426765442e-02 2.574616968631744385e-01 -4.159193113446235657e-02 9.645665287971496582e-01 +1.046674633026123047e+01 -2.614217758178710938e+01 -2.637519359588623047e+00 4.383187368512153625e-02 2.576360106468200684e-01 -3.347089886665344238e-02 9.646668434143066406e-01 +1.034272193908691406e+01 -2.616141510009765625e+01 -2.647081136703491211e+00 4.717654734849929810e-02 2.579675316810607910e-01 -2.414281293749809265e-02 9.646990299224853516e-01 +1.021537590026855469e+01 -2.618688964843750000e+01 -2.656219482421875000e+00 4.989557713270187378e-02 2.584675848484039307e-01 -1.348417624831199646e-02 9.646362066268920898e-01 +1.008484077453613281e+01 -2.621813964843750000e+01 -2.664593458175659180e+00 5.191991105675697327e-02 2.591438591480255127e-01 -1.366918906569480896e-03 9.644412398338317871e-01 +9.950877189636230469e+00 -2.625335884094238281e+01 -2.672272920608520508e+00 5.318967998027801514e-02 2.599999010562896729e-01 1.234182342886924744e-02 9.640635251998901367e-01 +9.813652038574218750e+00 -2.629250335693359375e+01 -2.680364847183227539e+00 5.374157801270484924e-02 2.600106000900268555e-01 2.781768701970577240e-02 9.637076854705810547e-01 +9.673460960388183594e+00 -2.633624458312988281e+01 -2.690360069274902344e+00 5.356618016958236694e-02 2.605955302715301514e-01 4.487821832299232483e-02 9.629156589508056641e-01 +9.531424522399902344e+00 -2.638529205322265625e+01 -2.703675508499145508e+00 5.271744728088378906e-02 2.616814076900482178e-01 6.338652223348617554e-02 9.616267085075378418e-01 +9.388124465942382812e+00 -2.644035530090332031e+01 -2.721546649932861328e+00 5.124986916780471802e-02 2.631950974464416504e-01 8.320283889770507812e-02 9.597807526588439941e-01 +9.244585037231445312e+00 -2.650260734558105469e+01 -2.745594501495361328e+00 4.921869561076164246e-02 2.650635242462158203e-01 1.041846200823783875e-01 9.573215246200561523e-01 +9.102452278137207031e+00 -2.657352447509765625e+01 -2.777873516082763672e+00 4.668008908629417419e-02 2.672145068645477295e-01 1.261866539716720581e-01 9.541982412338256836e-01 +8.964381217956542969e+00 -2.665489768981933594e+01 -2.820977687835693359e+00 4.369113594293594360e-02 2.695775926113128662e-01 1.490615159273147583e-01 9.503681659698486328e-01 +8.832632064819335938e+00 -2.674715232849121094e+01 -2.876063108444213867e+00 4.040694609284400940e-02 2.716771364212036133e-01 1.727234572172164917e-01 9.458992481231689453e-01 +8.707996368408203125e+00 -2.684913444519042969e+01 -2.942261934280395508e+00 3.691590949892997742e-02 2.734744250774383545e-01 1.970320641994476318e-01 9.407589435577392578e-01 +8.590589523315429688e+00 -2.695952033996582031e+01 -3.018403291702270508e+00 3.319668024778366089e-02 2.753017246723175049e-01 2.217792868614196777e-01 9.348374009132385254e-01 +8.477613449096679688e+00 -2.707590675354003906e+01 -3.101557493209838867e+00 2.929470688104629517e-02 2.771500647068023682e-01 2.468045502901077271e-01 9.281256198883056641e-01 +8.368250846862792969e+00 -2.719570159912109375e+01 -3.189133167266845703e+00 2.524992823600769043e-02 2.790117561817169189e-01 2.719464898109436035e-01 9.206302165985107422e-01 +8.290827751159667969e+00 -2.728365135192871094e+01 -3.255115985870361328e+00 2.109719812870025635e-02 2.808790802955627441e-01 2.970450520515441895e-01 9.123739004135131836e-01 diff --git a/evaluator/tartanair_evaluator.py b/evaluator/tartanair_evaluator.py new file mode 100644 index 00000000..f9b080cd --- /dev/null +++ b/evaluator/tartanair_evaluator.py @@ -0,0 +1,51 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +from evaluator_base import ATEEvaluator, RPEEvaluator, KittiEvaluator, transform_trajs, quats2SEs +from os.path import isdir, isfile + +# from trajectory_transform import timestamp_associate + +class TartanAirEvaluator: + def __init__(self, scale = False, round=1): + self.ate_eval = ATEEvaluator() + self.rpe_eval = RPEEvaluator() + self.kitti_eval = KittiEvaluator() + + def evaluate_one_trajectory(self, gt_traj, est_traj, scale=False, kittitype=True): + """ + scale = True: calculate a global scale + """ + # load trajectories + try: + gt_traj = np.loadtxt(gt_traj) + est_traj = np.loadtxt(est_traj) + except: + pass + + if gt_traj.shape[0] != est_traj.shape[0]: + raise Exception("POSEFILE_LENGTH_ILLEGAL") + if gt_traj.shape[1] != 7 or est_traj.shape[1] != 7: + raise Exception("POSEFILE_FORMAT_ILLEGAL") + + # transform and scale + gt_traj_trans, est_traj_trans, s = transform_trajs(gt_traj, est_traj, scale) + gt_SEs, est_SEs = quats2SEs(gt_traj_trans, est_traj_trans) + + ate_score, gt_ate_aligned, est_ate_aligned = self.ate_eval.evaluate(gt_traj, est_traj, scale) + rpe_score = self.rpe_eval.evaluate(gt_SEs, est_SEs) + kitti_score = self.kitti_eval.evaluate(gt_SEs, est_SEs, kittitype=kittitype) + + return {'ate_score': ate_score, + 'rpe_score': rpe_score, + 'kitti_score': kitti_score, + 'gt_aligned': gt_ate_aligned, + 'est_aligned': est_ate_aligned} + +if __name__ == "__main__": + + # scale = True for monocular track, scale = False for stereo track + aicrowd_evaluator = TartanAirEvaluator() + result = aicrowd_evaluator.evaluate_one_trajectory('pose_gt.txt', 'pose_est.txt', scale=True) + print(result) diff --git a/evaluator/trajectory_transform.py b/evaluator/trajectory_transform.py new file mode 100644 index 00000000..a8564b02 --- /dev/null +++ b/evaluator/trajectory_transform.py @@ -0,0 +1,162 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +import transformation as tf + +def shift0(traj): + ''' + Traj: a list of [t + quat] + Return: translate and rotate the traj + ''' + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + traj_init = traj_ses[0] + traj_init_inv = np.linalg.inv(traj_init) + new_traj = [] + for tt in traj_ses: + ttt=traj_init_inv.dot(tt) + new_traj.append(tf.SE2pos_quat(ttt)) + return np.array(new_traj) + +def ned2cam(traj): + ''' + transfer a ned traj to camera frame traj + ''' + T = np.array([[0,1,0,0], + [0,0,1,0], + [1,0,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + + for tt in traj_ses: + ttt=T.dot(tt).dot(T_inv) + new_traj.append(tf.SE2pos_quat(ttt)) + + return np.array(new_traj) + +def cam2ned(traj): + ''' + transfer a camera traj to ned frame traj + ''' + T = np.array([[0,0,1,0], + [1,0,0,0], + [0,1,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + + for tt in traj_ses: + ttt=T.dot(tt).dot(T_inv) + new_traj.append(tf.SE2pos_quat(ttt)) + + return np.array(new_traj) + + +def trajectory_transform(gt_traj, est_traj): + ''' + 1. center the start frame to the axis origin + 2. align the GT frame (NED) with estimation frame (camera) + ''' + gt_traj_trans = shift0(gt_traj) + est_traj_trans = shift0(est_traj) + + # gt_traj_trans = ned2cam(gt_traj_trans) + # est_traj_trans = cam2ned(est_traj_trans) + + return gt_traj_trans, est_traj_trans + +def rescale_bk(poses_gt, poses): + motion_gt = tf.pose2motion(poses_gt) + motion = tf.pose2motion(poses) + + speed_square_gt = np.sum(motion_gt[:,0:3,3]*motion_gt[:,0:3,3],1) + speed_gt = np.sqrt(speed_square_gt) + speed_square = np.sum(motion[:,0:3,3]*motion[:,0:3,3],1) + speed = np.sqrt(speed_square) + # when the speed is small, the scale could become very large + # import ipdb;ipdb.set_trace() + mask = (speed_gt>0.0001) # * (speed>0.00001) + scale = np.mean((speed[mask])/speed_gt[mask]) + scale = 1.0/scale + motion[:,0:3,3] = motion[:,0:3,3]*scale + pose_update = tf.motion2pose(motion) + return pose_update, scale + +def pose2trans(pose_data): + data_size = len(pose_data) + trans = [] + for i in range(0,data_size-1): + tran = np.array(pose_data[i+1][:3]) - np.array(pose_data[i][:3]) # np.linalg.inv(data[i]).dot(data[i+1]) + trans.append(tran) + + return np.array(trans) # N x 3 + + +def rescale(poses_gt, poses): + ''' + similar to rescale + poses_gt/poses: N x 7 poselist in quaternion format + ''' + trans_gt = pose2trans(poses_gt) + trans = pose2trans(poses) + + speed_square_gt = np.sum(trans_gt*trans_gt,1) + speed_gt = np.sqrt(speed_square_gt) + speed_square = np.sum(trans*trans,1) + speed = np.sqrt(speed_square) + # when the speed is small, the scale could become very large + # import ipdb;ipdb.set_trace() + mask = (speed_gt>0.0001) # * (speed>0.00001) + scale = np.mean((speed[mask])/speed_gt[mask]) + scale = 1.0/scale + poses[:,0:3] = poses[:,0:3]*scale + return poses, scale + +def trajectory_scale(traj, scale): + for ttt in traj: + ttt[0:3,3] = ttt[0:3,3]*scale + return traj + +def timestamp_associate(first_list, second_list, max_difference): + """ + Associate two trajectory of [stamp,data]. As the time stamps never match exactly, we aim + to find the closest match for every input tuple. + + Input: + first_list -- first list of (stamp,data) + second_list -- second list of (stamp,data) + max_difference -- search radius for candidate generation + + Output: + first_res: matched data from the first list + second_res: matched data from the second list + + """ + first_dict = dict([(l[0],l[1:]) for l in first_list if len(l)>1]) + second_dict = dict([(l[0],l[1:]) for l in second_list if len(l)>1]) + + first_keys = first_dict.keys() + second_keys = second_dict.keys() + potential_matches = [(abs(a - b ), a, b) + for a in first_keys + for b in second_keys + if abs(a - b) < max_difference] + potential_matches.sort() + matches = [] + for diff, a, b in potential_matches: + if a in first_keys and b in second_keys: + first_keys.remove(a) + second_keys.remove(b) + matches.append((a, b)) + + matches.sort() + + first_res = [] + second_res = [] + for t1, t2 in matches: + first_res.append(first_dict[t1]) + second_res.append(second_dict[t2]) + return np.array(first_res), np.array(second_res) diff --git a/evaluator/transformation.py b/evaluator/transformation.py new file mode 100755 index 00000000..6abec0a0 --- /dev/null +++ b/evaluator/transformation.py @@ -0,0 +1,164 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. +# Cridit: Xiangwei Wang https://github.com/TimingSpace + +import numpy as np +from scipy.spatial.transform import Rotation as R + +def line2mat(line_data): + mat = np.eye(4) + mat[0:3,:] = line_data.reshape(3,4) + return np.matrix(mat) + +def motion2pose(data): + data_size = len(data) + all_pose = [] # np.zeros((data_size+1, 4, 4)) + all_pose.append(np.eye(4,4)) #[0,:] = np.eye(4,4) + pose = np.eye(4,4) + for i in range(0,data_size): + pose = pose.dot(data[i]) + all_pose.append(pose) + return all_pose + +def pose2motion(data): + data_size = len(data) + all_motion = [] + for i in range(0,data_size-1): + motion = np.linalg.inv(data[i]).dot(data[i+1]) + all_motion.append(motion) + + return np.array(all_motion) # N x 4 x 4 + +def SE2se(SE_data): + result = np.zeros((6)) + result[0:3] = np.array(SE_data[0:3,3].T) + result[3:6] = SO2so(SE_data[0:3,0:3]).T + return result + +def SO2so(SO_data): + return R.from_dcm(SO_data).as_rotvec() + +def so2SO(so_data): + return R.from_rotvec(so_data).as_dcm() + +def se2SE(se_data): + result_mat = np.matrix(np.eye(4)) + result_mat[0:3,0:3] = so2SO(se_data[3:6]) + result_mat[0:3,3] = np.matrix(se_data[0:3]).T + return result_mat +### can get wrong result +def se_mean(se_datas): + all_SE = np.matrix(np.eye(4)) + for i in range(se_datas.shape[0]): + se = se_datas[i,:] + SE = se2SE(se) + all_SE = all_SE*SE + all_se = SE2se(all_SE) + mean_se = all_se/se_datas.shape[0] + return mean_se + +def ses_mean(se_datas): + se_datas = np.array(se_datas) + se_datas = np.transpose(se_datas.reshape(se_datas.shape[0],se_datas.shape[1],se_datas.shape[2]*se_datas.shape[3]),(0,2,1)) + se_result = np.zeros((se_datas.shape[0],se_datas.shape[2])) + for i in range(0,se_datas.shape[0]): + mean_se = se_mean(se_datas[i,:,:]) + se_result[i,:] = mean_se + return se_result + +def ses2poses(data): + data_size = data.shape[0] + all_pose = np.zeros((data_size+1,12)) + temp = np.eye(4,4).reshape(1,16) + all_pose[0,:] = temp[0,0:12] + pose = np.matrix(np.eye(4,4)) + for i in range(0,data_size): + data_mat = se2SE(data[i,:]) + pose = pose*data_mat + pose_line = np.array(pose[0:3,:]).reshape(1,12) + all_pose[i+1,:] = pose_line + return all_pose + +def SEs2ses(motion_data): + data_size = motion_data.shape[0] + ses = np.zeros((data_size,6)) + for i in range(0,data_size): + SE = np.matrix(np.eye(4)) + SE[0:3,:] = motion_data[i,:].reshape(3,4) + ses[i,:] = SE2se(SE) + return ses + +def so2quat(so_data): + so_data = np.array(so_data) + theta = np.sqrt(np.sum(so_data*so_data)) + axis = so_data/theta + quat=np.zeros(4) + quat[0:3] = np.sin(theta/2)*axis + quat[3] = np.cos(theta/2) + return quat + +def quat2so(quat_data): + quat_data = np.array(quat_data) + sin_half_theta = np.sqrt(np.sum(quat_data[0:3]*quat_data[0:3])) + axis = quat_data[0:3]/sin_half_theta + cos_half_theta = quat_data[3] + theta = 2*np.arctan2(sin_half_theta,cos_half_theta) + so = theta*axis + return so + +# input so_datas batch*channel*height*width +# return quat_datas batch*numner*channel +def sos2quats(so_datas,mean_std=[[1],[1]]): + so_datas = np.array(so_datas) + so_datas = so_datas.reshape(so_datas.shape[0],so_datas.shape[1],so_datas.shape[2]*so_datas.shape[3]) + so_datas = np.transpose(so_datas,(0,2,1)) + quat_datas = np.zeros((so_datas.shape[0],so_datas.shape[1],4)) + for i_b in range(0,so_datas.shape[0]): + for i_p in range(0,so_datas.shape[1]): + so_data = so_datas[i_b,i_p,:] + quat_data = so2quat(so_data) + quat_datas[i_b,i_p,:] = quat_data + return quat_datas + +def SO2quat(SO_data): + rr = R.from_dcm(SO_data) + return rr.as_quat() + +def quat2SO(quat_data): + return R.from_quat(quat_data).as_dcm() + + +def pos_quat2SE(quat_data): + SO = R.from_quat(quat_data[3:7]).as_dcm() + SE = np.matrix(np.eye(4)) + SE[0:3,0:3] = np.matrix(SO) + SE[0:3,3] = np.matrix(quat_data[0:3]).T + SE = np.array(SE[0:3,:]).reshape(1,12) + return SE + + +def pos_quats2SEs(quat_datas): + data_len = quat_datas.shape[0] + SEs = np.zeros((data_len,12)) + for i_data in range(0,data_len): + SE = pos_quat2SE(quat_datas[i_data,:]) + SEs[i_data,:] = SE + return SEs + + +def pos_quats2SE_matrices(quat_datas): + data_len = quat_datas.shape[0] + SEs = [] + for quat in quat_datas: + SO = R.from_quat(quat[3:7]).as_dcm() + SE = np.eye(4) + SE[0:3,0:3] = SO + SE[0:3,3] = quat[0:3] + SEs.append(SE) + return SEs + +def SE2pos_quat(SE_data): + pos_quat = np.zeros(7) + pos_quat[3:] = SO2quat(SE_data[0:3,0:3]) + pos_quat[:3] = SE_data[0:3,3].T + return pos_quat \ No newline at end of file diff --git a/package.xml b/package.xml new file mode 100644 index 00000000..0666c703 --- /dev/null +++ b/package.xml @@ -0,0 +1,77 @@ + + + tartanvo + 0.0.0 + The tartanvo package + + + + + wenshan + + + + + + BSD + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + cv_bridge + geometry_msgs + nav_msgs + rospy + sensor_msgs + std_msgs + cv_bridge + geometry_msgs + nav_msgs + rospy + sensor_msgs + std_msgs + cv_bridge + geometry_msgs + nav_msgs + rospy + sensor_msgs + std_msgs + + + + + + + + diff --git a/publish_image_from_folder.py b/publish_image_from_folder.py new file mode 100644 index 00000000..b151c3d5 --- /dev/null +++ b/publish_image_from_folder.py @@ -0,0 +1,123 @@ +#!/usr/bin/env python + +# Software License Agreement (BSD License) +# +# Copyright (c) 2020, Wenshan Wang, Yaoyu Hu, CMU +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of CMU nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +import cv2 +import numpy as np +from os import listdir +from os.path import isfile +import time + +import rospy +from sensor_msgs.msg import Image, CameraInfo +from std_msgs.msg import Float32 +from cv_bridge import CvBridge + + +class PubImgFolder(object): + def __init__(self): + + image_dir = rospy.get_param('~img_dir', 'data/EuRoC_V102/image_left') + pose_file = rospy.get_param('~pose_file', 'data/EuRoC_V102/pose_left.txt') + + self.cv_bridge = CvBridge() + self.img_pub = rospy.Publisher("rgb_image", Image, queue_size=10) + self.caminfo_pub = rospy.Publisher("cam_info", CameraInfo, queue_size=10) + self.scale_pub = rospy.Publisher("vo_scale", Float32, queue_size=10) + + files = listdir(image_dir) + self.rgbfiles = [(image_dir +'/'+ ff) for ff in files if (ff.endswith('.png') or ff.endswith('.jpg'))] + self.rgbfiles.sort() + self.image_dir = image_dir + + print('Find {} image files in {}'.format(len(self.rgbfiles), image_dir)) + self.imgind = 0 + + if isfile(pose_file): + self.poselist = np.loadtxt(pose_file) + if len(self.poselist) != len(self.rgbfiles): + print('Posefile {} does not have the same length with the rgb images'.format(pose_file)) + self.poselist=None + else: + self.poselist=None + + def caminfo_publish(self): + caminfo = CameraInfo() + # image info for EuRoC + caminfo.width = 752 + caminfo.height = 480 + caminfo.K[0] = 458.6539916992 + caminfo.K[4] = 457.2959899902 + caminfo.K[2] = 367.2149963379 + caminfo.K[5] = 248.3750000000 + + # # image info for KTIIT_10 + # caminfo.width = 1226 + # caminfo.height = 370 + # caminfo.K[0] = 707.0912 + # caminfo.K[4] = 707.0912 + # caminfo.K[2] = 601.8873 + # caminfo.K[5] = 183.1104 + + self.caminfo_pub.publish(caminfo) + + def img_publish(self): + if self.imgind >= len(self.rgbfiles): + return False + # publish GT scale from the posefile + if self.poselist is not None and self.imgind > 0: + trans = self.poselist[self.imgind][:3] - self.poselist[self.imgind-1][:3] + dist = np.linalg.norm(trans) + scale_msg = Float32() + scale_msg.data = dist + self.scale_pub.publish(scale_msg) + # publish image + img = cv2.imread(self.rgbfiles[self.imgind]) + if len(img.shape)==2: + img = np.stack([img, img, img]) + img_msg = self.cv_bridge.cv2_to_imgmsg(img, "bgr8") + self.img_pub.publish(img_msg) + self.imgind += 1 + return True + +if __name__ == '__main__': + rospy.init_node("img_folder_pub", log_level=rospy.INFO) + node = PubImgFolder() + node.caminfo_publish() + time.sleep(0.1) + rate = rospy.Rate(10) + while not rospy.is_shutdown(): + node.caminfo_publish() + ret = node.img_publish() + rate.sleep() + if not ret: + break diff --git a/results/euroc_v102_tartanvo_1914.png b/results/euroc_v102_tartanvo_1914.png new file mode 100644 index 0000000000000000000000000000000000000000..94609fc253c71ce13d197edc12b56e82319554ff GIT binary patch literal 74330 zcmdS>RZyH;7dDFG5M09of(LhZ2^QRgySuv+Jh(&fV1eN71a~J`2(G~;xa`^AUw`d7 z7pLmno>i4B=yY}W`_4JXcx-f(vf@WHWI|*pC@3@;X$e&*DCh*pA0!0uNKiNTIQSo& ztC);B68O&#$t)85{>DjK+Z755!x-`h`nyP}HF%KEO;XEE&C$Zm)7Zrv%HG(`$LA&CQ9Qh2{T!0<)uwC5!YFZ6OpC8I+8~2X(LP;~Y;d z^`XU}_2S!-{3QmP<4*kJP9mbig0o9(;D8H*{FuS|=JEJ@8aa`*=P5VrL!@dh(Y ztU%f94V5VPT`Z9*1xf|-lr&`+i30FsZL$A()nhe^>SVD%dKv+1Do~i`*1WOsT_Xy>l3;uI`!|EY9;bA?!+`SrJ9rG zr>m_o@A#4&{BI%@jh(zJX@opr~mTu{Fp2f7(hWusofnQ zWWUm2e6clv`i@t5{dUnXaQA9Tq!e5PcpxDoRa!lL{edExWP_F0osnc1Oa_e#=_{{4ZSIl-U-0TV z(}#zpH;<1Q`P~kT=GQuXJ&he5S;WM}IfN`sOuo@-R%O%bHdUzj&U}-Utkh|YSpokR z78@ITu-aPR#Y9FXnvt0qr6lsKzFsnSC~>mVD7o1i7N+szS2G3yyTsDU$`?col7rtK zr>k^OwO$un@>BW+UU)Vra*2gtF~B>^XK~vftTZwh7#Q$zr$0a5UOnBrhGURA%nO_J zBT-OLEVa5?mJD%naTSXO!-R&16E;RfL?qKFkrZ+xA|l$^+0`^PEi~J&b!7JUOBC{1 za}q*UP*fDkaxxoQ6sc!0mdJX&OX&V;fAQ9SxsD24ww&jfT!9xcICDF+;Cmfr)Gqd+S zJw2-(-pK?U7B!YrBwsnLP3B8g3Z7Vob%}_-_z4m28Sg&8QKOsGVaf@ zv1stdmfovl=`7oS|9&m^?~lZKdU-rM%*FrjzsTZZDrRP8sS^zi4PHLJi-Va$RQ=cb zDPdEv?}Fw<+dNK2kC*FXAI5V8(i0LerDFaoaCCKb-ToO2>$904SlZ!zRnivT-YyUn zpcot+EOo+igNBSO_T!g{jm_5rUu9bM&)8&N-t~cxA?SU%ad`M z4LLo%Y!y;)+(%RB#KGpW{?o>_xw$!>&6hlxBj9>{paM>HNnUbsvH9048R6W^=TH78 z$H(k$7|4=RphzZCS~cn{RA`5kmePRAFw+bw#s5|!@HOBok7I6eEqJ!oN`rODRDDyE zV&gOo4iS;9S(X=p`DjXkd?q{8_2FDZi9*(FfjFXKu3*{O9N1^a$Hz+z*2!I!{*N~) zjM_<#UH4LsD0NLudl%b7){`{%UZb}Sd#@&jVHEBETPvrHpU^O{u-f$&XjF1(^WDNv z=i)){*h<>l+i^%qr|K=IVpdE|P2ZrQQ5kmmWs;~B&P*4};Vb6w4^-+lL$x?>BRt-m zaJc+}AI=frasNBNd3Uibn0z1(1pbG1Je_(N$TmHrdV23TmRm8nb)OH8qYc+0e%lj52hR;XM-Zy0H&V@Ygm zY-xFU&aZQI=40T!!xPD$!EKOoWd?-~Y@uu+U+!NS;M|N{uHt=3Pnrwp|ME&QGc(h> zwq^hd7VE_JP&_GqkXF5gLb<6UKYIVn4BMx7((xohp*cA@UN29rT_>OtZLKugQtW2p^Y7m;>FM}?+C8VP@22uZEO$p!%T^TR|wMqfIcdkO4 z1D%+^|0|d6-C=2748^kL#MgloIyGLOYubN*f593}=YQz$?+1UwUha;4G%_M%(5%`4 z_x$PRx8u^%5>x_@qrtp3@zf4x+&rto~(EYOqb?%!?GIj67gaRnpZ!9e>XTS}pwg26uzEAW1edKz; zqk?*cmdeud@*4pGfteO(Q|E)}0(E~J9Gn3RktZ@_Jo@*L7jJdh?FZFpF8gsH8ebAz zStw`+PA)Fk{twq!A3l5_XmbpssJ8;Eyx*S=Fb?gSW(s~9R>!qMc@Cn6o-fJRZ`uh5c227))qw@(8fw%SY@9pcO)2hi2 z@b|?B|DLd8&j30I1c427fARFzefhJhr3OCOfI$5J&mZ*v+m-ZpQ()^CC_jx&QxD_A za8estz@Iru+yvr5-cE9o98N+wcqo1ILek4c`{mshhM47nrOlg#NuzCw^~#){HR5-d zBiydKHLfAO?mg;EwvH(OWEgP2G%HPW@t(n_bBp#DYThmme%LX+_aX4`E|~qO+{&{< zpDX10sVG_siQL5pyIRi6i#IMVE;KBx%|w&3=B0^kk5WrVrkzk*DA&QOpTZ9a_Vn%*_emU$w{E?LwtI?uJ>9W^ zZiz(B$~H2V{{hELD8JvUr549e!;7u^3Jo20jn$j-~%Q34FPy0SKB6%GlVre_#Mq_?ywPY(eiNaLVd^{@Hvh-1S&K zk6&RgU4@t5>dn94ncj$AY*}s|daS9UgPbGw{=JDT0xlcePvz>y%d=FxB7AQw(|=aN ziq5i|?84#sitY+0H0!mQ{^<_PdxJw=<8h+1wY?2p)6h@^$^bw?nHrTk0Fq_zwuXm> zvU*>dz1(eMH0UtpdGBp5BCyRGt-CULaZX(>IY!?a>#ISiN=K4_=c#g=n>FW(*MmCe zeuRd@4qG&<8|?~I`E|&web4IO)NOcpc$FHX58%zp3_AHiJud-RyPAq~b_=ki>w}q) zEFMP}_i`F@lc|x6#GXg8Da2);%HutMt;PTCg=(`=eA2?J`)Kk{<0H1|DbORMSmo$J z<Q19;%!1|H?Da+xZX&HVQZseKYGEC>KRTzsU|TGsZl*ky(% zC51!z&Es>jxcPry-Wul_)qz;_u1eJPF`?j30n|JR^9fPf&0#KcsL}5xd-<=NZww6$ zp(b;M`K);5;=o+J0eLxr&te4$p+cd)G~^qhei&`Y zqIFaA!BAFr-2)kECr~AOhv<}{Mxf<`*Ng(}2inNea_GBCA+2iBFi}@j`jy~Xit{5= zrY^BOOU37J|IByV{!f*B!p9ODl!AN5gA_X*H2>_9y5seoq0{oT#H8h04`z#_Rc_lo&n`D3NViT-(1I!}nJ7QTnH>jt@FE_ES_&upSpMD8$5{(tjo5eM zWb~oS&Qd&+$9*g01$Aqsx=2v`1_GgTG^puOd5x!8zvU9%&SVU8QiS~#-Q-vP&b`#C zde;MMks>6%*5M7k)b7awi-=xiK9*Jn7YU9DfRLa&vbyX@cinBF=rt-CIdc$%1(=}w zx!|rcbW{rP^a9fM?`To2(C3q2w8V6a73$L!!S$c7oy!4vdWqJ$Fp8pg;#OA-DRy7| zx4S7JUE+yICMF_cAC++MnFABwVRdL8`%*Kt^&9eHFbvmh%p$FFJ`{k;)33Sj;<0dX z`$2=(Zn7f)Z0G0rII5hS9O$}opf9326WI!L6tP0LG%*dqA&I^`-QU}W;fuF%ZC|nq zRGhsFj>)m{pL6cTE;5>Kj5@3%gQ>d6eA&iiTvM|bGu!Rj@ z{k+{hVkBFTYA;Fj*%j+to0%Bz@!xN>WuC$cij%Ap}~e7O=HTMn^U7* zQ^4Nd2T{Cq_W?TQSADYV@-W-j#izR@;9RF!g z2l(qS9w0UjyCqhg2CKvysG)$=GxHTOFVz)~eTvMleOX(NXWgZ$_pyH0?;|h0b9>et z^S4O}NXdj{18&k6dVWoWKTwgng(4V^ijIyE6+zXGU0FC#M0nG{NdrI=6OhMlj(oK@ zu{~d=25F-sNYLawJ%RBtFX+6+9b9k;%`jdKDb;?dJv;x(HS&c0zk;H5(D((1M)5!5 zZvV%oHSVM@`<}a7$jUF`ckLMY!R#lqr>|*XUt26>w=!z6W-fa_O=sVJwh77qDYqKq zu5*9?Se3Gp%RT8-VTSVkl@GVv-0JE#`MMlu00&QEAGne4sdOsS+>aIjP?bDcvEILk zkB+8fo;)7_az*K~Qi0c5RQzXwkGl);uWR$Us!dhO6^X0NbZfl2^%KbC*S|*r=IooA z!eC%v5EK$xZgr&r9rzFhBWMm~$3u}#sjmZNF*Ox-9SgDz#?qK(>`2h@HDq)Lf^y2x z{$eSaB@Ne)#a#LG;UUDoWv8Zg^xk&GHYuusCMbAi*~!5ogNP*_CoBDfgC?MK00MKj z5z?TBCZEHfI+9G&y-Prk>j+IwwzN*h3ZwX+$nIAiX(Fj83*}XuRpH?q9RLwGAsURx z>r-+Pl^l#RkVB+m3B#hJQ2=&3UTwv(wLQ8B!B?82)KvjGv<<3cz1Td1h(3`qCVKsEcJ&^KwUnvCKKJ{9C!~ih z8(Nr`n!ek&i8vh`Fh%NRs@Woexqy@`R2wRF2R!ro-8p>~Gh1zO_ItVCe^~G9>x)(8 zXTUwflhPR^$^64jr5IN9lXe;P%RHi7I}dy8&!3_eQ@Im>v?8IP!2VocCryAU(&Ni~ zH#0aG&ZOHk9L6KWTp7~B>cmWszl^vR6rS;If;aH;z2#KyEJonQk40||K?#sP4@ zF2!fmN(c>wd-v`gD8fj1^y>LQcj2^Mh`|uP+t^*4gqdnsxC?#zt?ZAx8_mASmMUu8 z6Gdlzl06Z;?I=?f27kxOJsC6h4UN!_#_98lZqyn5nH_yHSQ*t0FXtDa258>+lZw6I zAq$l?#BArs^1S0|Owbjg%980xY&UDNC7|PT-9rUbaqq1Am74s+!a1#e8>eBwJr&sL zJDYtG?*u$z+T4!_^S;mZTnS)$k%&2rt?a2NeK4iZTl(N|gzJbp6u7OELAARtDE{MD z$yf2Y5{2b<&*~RXQ26}Q*6=T`uXh03Uv|Bck&u*}sghztca!TAuW-|~;^lU&8YcWp#baKk;L^ew2^u7-8`+Guj*yFyi4+fHh;IBF*lp7 z)-xH}{%a%TGL`mIIWFMMMNXT&Ql$ffgV=4MTxkcV7g?T#d1~zetW^ zM0NGq(eC1x_`wBFXaSM_;i%Xoru>=3gl^frp^m0cU5kVdiZph9`fG2X*&SASAt$Ur zEG#lI(g<|zcl>UVfEn&z&*OfnxQMeR7y(*FC{W2boHj(E^z`%&*1JV&YinZ&xkjzX zwDf)mYC_13gA|doVUr(3>65 z%(1(Og1MgiRHyTgkx2cQ1Ka;z(z!OVoKyqW&k}}~v$k?D$-v3HKKY#vcK$nJ;xgp| z7|`8IwCl6SG7FW>zQ$M)P-V#lt2Dgm`m*DRIbH6^03bL7IJk_oG-NXaT8EVo++n?p zJFcM6(&|plyx3Xu*lw%(BV6}QtG3^c@IBGB~1#nLi!JcWd#Og_KX; zgBLRqc}CB+&UAvhFK|;1GTScwl)U`ngHb6qXulBU9P2cZRBUZ+DYu_NOK0QYfXGVk zc%6c}{2woY5=O*Xa*cEoVV_6MbUj>2J#|shNsXk-6&e3SC&9}M!NPyRa)**TUm@s3 z=4P4Rf7kPcWiO{O*ev|kxLWywMIwuAE^L*L0(O)n+nc5##tg`+7nheN0D0)OIDJ?* z_@TiR@cd5`TxRM`)WwX`8j9j%DmQw9wG#c!MnF&8HPIC;1RH`z9|}ONaW9;my}k8% z6;q&k$7i);q3^eRoX;A2pmTB+5p-SW@!z*;{4B`l|Ew7UcpWaMRLi%cVM6>8P1*uD zx&;_Sr>*Cui_~!>Lgi-xPj}A9xU@m>@fb`x4L=_SHI}Yxf%5gxA&=r>TxrLkg@RCA zOZ9xs@5S=@>Id3Qir{YXIo%AW8q6(Fg;0sOLbF*OQeOf>$Z)-ggrOr&y%vtl~YMaZ=-$V2=a2)CM+ZtYO#lny`H#UCO82244 zR+BO_9}1#HtbR`J?z{i=Ao!`bj5T6wboM5TOM<3ISh8>ilY}HLM?XoVH>ufMERwS&vOQCt#ziItF&`uo}%ih1|=xV^cV*jGR5y|uN)>$Cwy zqnQ13YAQYggA^MN52)qlKxqNag6g^>sHR?CUdrX_bnlX1X4YxNhD(PZEy*_iTNQ>e zW?5nzw>Kvwn3ciFkYFuI_#B3Gd19@G$OWahQUY;93_5)X{{BGJ7jN%? zEm2X5+Zc3y!t|?N^7QX`wF>&Tno?oVN#K{$u-0r&e+fw7ELKf2$0;tES8z49#9&o?wIMBPJv4jbZ)Ga8(=jlAy{Q%~@F;AWHa$sF~}(U1~G$??n789rfkCBjx1BC6sjeUCJ&z~G{myZgEqTe!oy>UOw3#OdwS+6O^RjYwsP#6^3Y+JJ8mqS?GNq4>^o(An2!m7VnDrbJPt*CAtPBm(EPZ&YlD|97X5` zFbD*FZ(?dqhw6ZCpPg$Ervl6kd3pI^AmLAZLKe>cYii5&X;kLUWu1kXCuIWTSF-tmb60|=VPn78oIAQ45oAZA$Sd*+gsHVgnbkB#n2*OxVJzCd z64o#}lI>AVrBf|`R}#$N$c;ts2BRbMoi(_nU1o<)A;4-5YMtCQ; zQ+e@1<6pvE$Bb^_%CKHk5Otp4t3?(qQR9kj?C%d1h)1*pz6y)H+!YF9;>kzn-?ywB zw47^2?_bj94v7IKcL*wSED_IOZ|~<$-&-JZgruh8!6Kke#~(3`s(cC>$q{$SIvXet z6C38F86k-HJ(cKD{fa3YWX3V_FCW_H`XD$nlK>E*LSQU1YS)Fvi@an2ReJB7(G}t2 z$B!MIopgYKJ^ZGZQLoa=1o8=t3(FlSMgT~Y0Gj9L?_Z|UcP`<3cW&(e1$aKuYV96O zI={+-N+V#s-Q#BjFB4~Gt(lf?PA?BzMA7ItR~dq|%Oiu*aY$(M8emzZ3$AzA1u=f| z(lZguGhwEoBiX}E4UvuSZ9GhYn8tOWo^15DDMzqPk_GYnXqJo@TjB@!EMJYjnP0W6Lm0F z$Y6!mm2{+KnB|u&dqSAec~#^{zfVQev|8fS zZDYqSik_81*R=F4vu!4*&7WDBijP<^v3WG55mhO>tS2V-ksV)=Q{3)P}(Qv`*X%~ z5_gv{i_7uQ;R1WD)iC@LD zGL`+OZ6_qp0(_n553s#(-!N%PxX?*EtZQp)tCT7d|6Qz}vdr@jpQ{~l@`!RHCF#Ie zm30N1aiz%nmsH1=H{>9QlHDWd$A zB1)2MdXkaKw&XaQZA&A891(DYzX72P?0f=JQd0kR;LsM!rAw90ZEkOi1G4Svl;#+5 zcjpCGGn z0+#gk;6Ax{c#YKz1r#Wd(^j0;dr{>8mP7Pg-Jr9m7#mf^ZF&I`E0=VRKJM> zt-sdh7k!)CVeiAg%orzs48DLTUa;PjK=1e$h>je^4HQV1P ztXs#p!?X(*xzpDwJr|UT-sY7m29awWPpj|AakH-ew zL>?69j1W63P&?QO;FRC+_@TT080*dh${FVg%Ldr!pgTZzH{f)*EV*4y0zfbj=(71) zB$al6{Hv#bULHZ@Yld9xk@?`i#T|W}#aZ!X(Yj0kX`v6EFVrAx7)bjAKudUog5oPs zRmKO7BKv5Ib76RfgkaLE*GMm{nf07+sku({PRg?NH|QZ4_CX3wXD2!bFHdGh%HF6pKJIhS51(jAyux)$0Y;WDit|-@YDU(9Kac1 z-zoqz`@2@{w?rqO^9^X=`VOw@4dO5T{*8l={}CiO2so`UJAMAiia1bGy?o+1i+1TH&VU zR86baRazqi&QAR6^I0HB>0l+Cjsi0Dp>W1%I|(C8DgNhzimH{vqk6z?Y2F> zE>GqdJzBYXS#KP%fYof#8*qd5%0_2biz!Ss0hObH6=5x!2wbT8lV?!4W{aOkJr!y0hSG#wp- zgEO+A!Y3>3Ri)*{Q^dv|*y(*Pe?TeQD-78} zrSIL$$=bNibMnbuJ0RItB^=Wb5sfMlL`DVVfT}{P_A?QW0~9M*-EfTbS`2b>auCN+ z1&^!inqFL7K&&%}S>=1{z-_-G@pyCjhMSc&;bT0BO0jHejD6XF`BJ+`}gm(ReG(xpw72=T~Ks&b%ENO0311o)s|q) z&*0!WUwp&uSIFWn2BZQ~#L_l@)U>v1ww-Z5$s#vw5S?4X@_CKysZK}yNhh(Mawx5A z&BzeXt&0?ET=EtAQlR#_rKk)CH2nh>c`@drGcpMDEEJe_Ot#hg$rz7U*Zkl-uQ^&gk*gfjZ(=g`AH;j-VJ1+n zZc!F4PYQS!^kw?z$7A{>Ow$d4s>1L7w;vqUIi_w@r+W$>diGsc20v+D5bK`Tv-mQFcTsa(CZ69Wh6dj`hVeE`vF@1W zZ*3R3lS?VyZuZo3%)O>ny5(5q?&wH{2-P?7kiZ9!R!Mw)AKh5+Nk|ld?#}0ZS=0sL zb0Dn;Q2=FAXcI45QOKh?PqN;JaShWvKIDmqomS|y$B~QMU=b6?c6JJZD!~A(u5p*$ zuIXuIa9y!KelP%o5Z35t5Hy4f0}&TEZVI8V&MwP>?(1gM`pO&PI$_6O=8LY9DEzT%*kk?$ft=WdA#-WjOE^i33j(#dei7t zjQB>DbYv%HaYyiCJ=tRwLG}0FKkYpHIdQo{zOx|25sC@uV2#5c{>z<_K2TcC_Ol+1 z?MW*d=a6AnxYKI#{sTJ3C`!^?OAtf+f*h6vuaz} z!&!J1BC78Zoik$!u80b;p3siTo|foqeCkuq`&YX_>(&_B8>=^@mHyE@SJ=6K5=Z_e z!5q!@k0yTq9DBfR&E@Mzla%qE2cN~DqPi?GMzItqokUVfPoI8h>;g%*!Fn#dCj@b> z{1e0YIQ#wTTOY%=*frTNS2be{v3;q+vw>@_d*jBy6ZZ1)sk2+ITa25%y||bG?lTvc zidEX0#NJ;7j)0RTdoH%sa@1`EHQNH!WB*e8-VCOI^V z_0xxnXdMbz<{@q-zxAcK_ z*%`(HF~)=WGMuWaDpcaH6uIC0H1EH>Ne#@}PaA9C=wjIYA;F<-bF)Qwf4@_W{HN3C z6Hlv9QymKG3d5f-iDhnkQ+XIafk_jy>In?PQE-m?L!C{r1crL+iz0ry=;v<>x>4`- z@6t#A>%(E!x@JO3xP>kbHlqX?&iU^uA)nzjsOyGF-|e%+H1g+oe&{|huT>NFhu>p1Qu zk*(Y=k^dtWOgMdkp{)kj;yz`|;_<`0ht1XJnv{flZO9i3tU;|F(c%n$7S21*ioxP4>EwzQke!uiWM54ID?{ z^b{HQgt-Ig9WKdvlne>lma)fnuc0z?p z6=DH71rwyZc!YV_43N5W#41i08j`dBnXZ!9(+K}CCqHJwH1b*oY2!r7k6!>vF>{FH z&%qRC2)nDz?-=x~5_|WkfMoxzYYfOap&=n5Q2hzy;&q!LG7|vQ!;|SW*=2e}l=AF6 zbxl$3m;6Fz>khX2{j$q2gn@>JMO*Lm^c}FI}Di_HO0OmE9-4mZ2F2vXPF&5<74-Gi42}8A85IFXxaP-Gc^a`Zkm8 zNsyxtvg_}usl$OY z!3L77ZV0|YNgR}=KmNS8T%OQ1STSaHOd$F6_GY&4lnRObKVBy?9>=vJknsfQE`RQj z*X;lk7&SY9!Qb8A19orf<`2}Z)Aep8(64KUKfU|wPi^~^#??DSK7P))YJBXMGfBk> zeCZ3>Oeebqo(P4CvOrf#6sfCkzP(VqiUP&?HD|v!@FOE&H)RlNhVxPVKEGnQ z=zKOuJo{3#1_%(81juc&&#x~oYC`qS&vX96arD3@W$N!b3(d$LJ8x+E7LD1AK0-6Z z^AmtYcrxLK14{1`N8->W_P?=uN5%b;$hGbbn_ZTgSX&o(&yd=O0z|u7qaK(7g$G7A z{v4oZzkPjNf0Y2SML04LPIllt2HHa?GqWtx8I{<0nZtkJ3`|#^P)^!qP=d%Z6QCy5 zBH(6=0;gUXIQ=ELmIwaiFLoK6;q{mwE&j767DEEbO>RKp$)RT2+-FB*K2Q0KinfDu!a3 zoNx5NU`|d>ZUOj>)#Lhg)VAuFx?kLI`)o6BDl9VoEq>q$MSn9o#lvg1L~o&78H<}) z_+~a&XJ{mvlB+O~Xs~zx$eVTNed)X;sSoiq*Y_oOjV-5fj9Stn=uc6pE{Bli?f`$# zM}BBl2XG``uA{ixj{2ar!C8B~bHVhfPUm7?Q{K!vIIw~O{#TpJUvy9z;6$kIt zKEuwxlQN2M*F$Ds@&W1fU|=bThof$SRIYqBFBZV&<(k!#)!i?nKye32)Ng?7Nxi|4 z1F5~iUMY)c;s9hH`=G7Z4+qnFf5iSpUuuqT4y zn$9|@HQ<>av}8)4E|t#6tOt&BSi`E)qP-UY<|uX$B={aa#pkjU38p7XXOcCVFiB|p zSA@e$e-N05wzM(%+7q!DZ}msPV1gQwt`xb>kL2uduiM&$DHeHPDfYB1ZQyD1f!u)@ z8}xH5(7z$~6r`IOe;IgzeA2bj+QP!ZH{aV+6L2=IZBY*|?!I7VeU$z!d1?8orb2!b zz|gU$hyzJv8TQT0sMvj-Ry;`J>J#~kbaAX$PQJahC6P!W2}cIZaC(qRH#n>JeiIcH z^$m1r7)%fezy&2o;g3vda^7Jxx>&aMdwX5*88@4^i%pN*_*FW6+@T{u#;epmdidwl z&FL}~%;3n;>%y!m6bSkDv93)#Q#jjTk$1UcVr?G}d=5?xb&#?SNh|n;Tr>zkR5?rsT|LLUY=T@?xtNp))u32wWcaRO`jzdaCvof9XLU387Tx zmd5Z8h0cz@UJ~AUSz1_7*LQp#SGwkoL=MIyE@CKcMEQ1RVc~URe!NtB;KrXT>@N#U zw)21gc0m#H!T${;GcaMJ1crGIfqSzsJF#;wD)oUU2Tpjb$2aO)Sm1_%)LQ<4t&;Dt zH~Mns?js7UgIeaww)i{OdOh5t*yMWE1?Rkg?qd1;6Gb%=NC-oy_z9YTVg2u)S}w|Y|_^PYc#k(t@!mm$(XR=cGd9v)JA ziq$3fHI!l_r4Z*w)2OP;H-NJL{;vPNlr>NexU5^7n;(EN)%|pdV(51vxkBu(F-+EO zX7|Ua-}(*vTdmIp9G3tE=xSHGbgNP!qPa+tI>1R?GTUpt}~h zoM{@cn`g)0aa;QnxWXP^nT;_O|1V)nG%U~y*b6Plk9V2bmdsH1-mukpe#0e6eH<3! z=OYvRnID{yl||5@VYluibT?dD)6j@Za&s!-rXTITSq^5k3JWQLX9i-DOj1qsRQ z$|X$Ke_$v(3Z(uPg^MFzTRhQjI%lTm}tPe0+RB zXe5k`jQ+;m#%vo{30xKTngS82Lc5;Ym%7z98<(W2xZuG^)P{RRJ2n|d59R>QkJW^# z{a9Guw_?_w!)*kNvTPq5M1GPTV5$Ga@LCK!*Eoo>4cO!$XmK2Yb==V0sGsYjq0t($ zshd??lm`^wl5v;tPgAFwG%A=1ywAd9E9hsmfhT{F$mA1$J@I?l_H(0)$)S{rnNAnc z2Yv}K@&ntg&Gdv&4|!CT@78=SD{Nqh!hcd4cHQq0flGiS4y{3mVcYHOXDFOZM&ZjWRwPg_ktbj_ z>>6LHH7(O`=T1yajLGSGe{zBDmsc>x&(F^e(q($~Nev%xTx%XY(@ln1`D{OrkgR>F zr8`e@!+EL=atl-l0n73ROacJ+KUN+i@bSjp7$9vZXE3}Glb4Y}h8D8UFU|9ZA&bNR zgr^6Lz=U;ocO!M4Q0{Y688#V$8Y~a?=?7F&cG2ty34~iA5>pysJ5@;}atSb{aejS` z8~FO{nTFc5JXv^!u>G)^SDbbFt5S^7!5SCSbF<#>o0>I;@wddm8?fk606;_oM8w12 z2{KlY-%xTCX@I){PX>^_)hgXnt#MVd>l>_l&OaBxY?K7>1&$0j-cLRbLu|%k<9DJ4 zo{M*!)&D4TDmCn~|D}2fYfSRkbaYBTEi50@zs2z9aJvVSERpo5v#~q@UtP8pq^!vZ zcDHmgqd1uLN;0JT+{`R2q`bUZR7eV9R2!^R+B{O1W#(k-6PSHpln4J7T zi0JR~fiBILOixW!Yg|*+JwGU@Bi6|_tI#YjkV*2iEe_J0ZiH&|yi#?w?PwT7Z5O7G zpZh@FD*g7gC0tOoAyId-`U@B^^G4vga$mf;Ulncm&iTx}#fS&DWQGM zk=~C``fr0jUNP$5#$ua`GPK zWHKQ!hn|}v$;QpavzWcaaWJGqz~k_4ADsqoePlx|3&=vi5cYe0zMTg-2`~gO2RIcN zB@FKFF8Bt)WJ<#iQ`Uy>-^!0mAJ>IWzGh8=A&E?Wcbl~C5T4#jSQ$DVPSxpBW2d;- z*kT}5=(XO)C>ZauKK|uzc*b+_H6q{oPeVrT=YAZjYd0gqBXmGOfOdeEjK%ZAKTi9V z6d+I^gh|)k6wFwmR*kEW*Oa7h_U{nxSUa7paQTNHvY8G}m#LLjD6w+urB%UypH)KW zriNsKferzQ1ArmU3WH8UG->h2wWvC^iGpc=ctR9i@isC<&r^396RV& zYW^;Yz|P`1M!h6~+&awO{9yG{%Ju5fD%rHB1~4aSaV?Qfkkps}CKoXA@zXtM?7yjZ z;(W`Oe%9P08GQpfZ6D}7Ex!M!8b$Ty{cW&!k@2*4&FPhdzFGK9=lUVj;U zD3r}IQmU%o&UgLw8Xw5-12Z#;fSVnJdB@?9QeEi=k8kOG*J#rR)1)BXjB>PCJv6!o zUyc^KSz55@L#v0O=9ZzS2k&Z||L<=P&$F&-lif0-qb@H`wYZYhY(z{< zZ2rDQ5rqg*To|EpG3q1p@<2Jh`cQv%9RUacux%h? zA3KvdS>Qu$Y#lS&e#^^6v?|JS{E;`y_`l^Y$B^2Y zcHScfBv=m+qlhI(9eRKnSQ8M+0BOZw3dt}3p=V?a_Xoi?_2v8fEUKx!=2Y0;XG{JI zxqI1ef{eldiO$l-29gE_bFeM#?MHLbLA6lO8^dm8l9}3LNmb{w*DrwQSb+BeqqH~w zK9k(~QT{;rs{H|jrG|USwCmw716Z)nU@91l)uic~MU;%HpOG~-uk_6k`v6&CwV7$^ zDx(Oo^E(+`g!`?0ZTU?>#CDb30hL!zQa#*WMo?+>GIrY#V7@y4&Y)(}Qu`U%S6;3Q2PH^Rj~}4 zmFjp*&dcwE-PQ;!wYM`s?$A_Z;^ozP^}N}R7a_E^1Mdy_D5}w2?xM`&Wca%RA2-(C zur|wZS%`^!7A7eak62t)6>3HWArTSJuNe0~4ls%vsu_Xt=Ab~FV|~|cb)UTXfrS_} zWInHR%s{ltN$L3aJ-)7_$B%Enz8cL#unO>_Pb+dMcF?~!Gepndp|DUEfigUmlE$+3c8el2b#Z}n+5=J`)!#?zmy zs64kBnj86ekh}w-N=0zL4t_UR&#=+Z&;aE^F}f|axJF9)QM@?UH^`j=I`3S&rz5q(R|!CUixLzSzbv_7&lAc@L9XF8p5+N6F9UWl zwi&M4pc7d%N>6pJ`(Azs6nPGJxmS%8s1e#Qo3UF&OY>(`&RKu%^KUB6fiL$Fz;RWp zSUUQ(&;s}`7$}F#=!Oq|+&3T5=B$G|5(vkH0a7%eIpz3dz48bgD;Z2iwU! zktu+|{spIJ_Lh+~_Eto+XD#(98{{$+vS;~b* zJZ6n~Xw1W;8oJJiI!Ql`y-W#`D){&;AO$rrG!y~8s-lF1f#dEZh>LVYXJ@xfEQCeP z9n7xm0U^T#Q1iO9p{nZL;BZ6n&R6rlE{c-$n0aytp2G4~x3x#Mt#b(y0H40*bzY&{ zULN<}vApq(3__x4x$TYeJ+uGwyX|j9V_Z{H-pWdKWo7+BXXU4(HJzh1-?ONE`45Rg z>|G+cJa3E%EUZLMkG5cvIvjIFFLU>^UGp9-ZW=C@GHs`aaql|RaNfR^Qdd{sGuZA% zx`*!9YLTOJ`>DXDpjRAm_grnwM{)A*?b|`H++ftDG){G7gmmDxyi+yDiW{Dj5Dj?g zrog5IUJkIuCP4XiZ#=t=GFjyIj=^Msd`E)yYD+Ei&;QUGbuwP8)J;C>RN^CtL1Ldy z57&p+^=Ye8ORh6KP&54sVeanW`!@8a0d^z?5=v&E@ct~VPnDSP3%esSinHSK#JaIJ zCAMLpItYj{gF zuy?MJjYyx>dp?QC%slhQus{sH>)ou1V6~ig#j%9-$|4U{>gy}o|L)l*ywN6=9!xAU zb|_b(b0Hda&17=PL%I;i#^dJZhA`OeZA$i>(vSUw?Dro=6oEjL4QBXN0lR_BsenNp zFcL8|IT;5O`GZx05YqwOag9_y)nIhb7u}tngh}%Is62rBiA2VQijZrp*PW(c_KVn*j_tf+XvOj1=ZJ$s)1S7?7056 zVNre0eDX|NE|y0%x#gdyn6Va$JydPYF6azkNJIre@)@P{n7XkCyVWzceLvjAXX@kP=~z zPC`|Ea_bQmHy;Y5yPT$BiSO%`>OR8gU@Fnpl{POb7>h^UA{z+UC)}5ssM>WgCh*GkNBW@vzZNJqQB$)3HskslRXhQb^Bn4 zq7pLH`cl*@6KM|iu~lCDKQx^MRF!MAwKv@fOJVp zD5!LUbO;;-L>i=|MB-oj-v5qq#yICVh63B~d*8L@n)6ws`VTcSV}Tct0WsVQya89q zS+vnaJeyF$Kf0z%trOSLradI-U;GO8uXT+Y5{M{dtFE z=k}4r`Dq6bp{ut~*5=xquDJcRmGCjv&XDQv;E})sgnPPCfShk6chI;=5~W6G^Acc? zkOe<$Ys%)P>m#qpzw`c?H+HL7N%68YvWt>rOFOSn6UF5hSC?7G?4cT2hA-T!ky46Q z<%SWeCx_K^_cwOSh0WGis>p|hNbwY`O)((HZo4uFSYty1*an;>|NoE__t`B=tpKru z5x44&6P3byf9j-e8dnYgfV$<`E{F+RHd*9%!44@2y6%I>e^b67DZf%yWQ^hf`> zwLJrVM`cwN#3a>5TB5>wykw%f`#FB+6|BZ;%?cHvKTCF-l-^q<@_XCDCiHNa|H~dH z`+70{>ZdiQm{+e#fa^mm={I)XOp{JZzZ4?lS9)&i`AA&j_`r!ZVkopg%?s&;WMIDwz zZpic)jEU@FLOAp8%se!Z+U?=8u3R9IKWpm{`IrrVr9HPK!`|7{sOcrBox`iYQxJyH zCtWCb*HPHi2tTxB&%Q+S95WQ$X)9}M=^s4Tga|`8%NBXa^AA_`8FW9nK7qXE5RiJx zjQFuGjHnZ|?W!lx-qA&pCg?Pn^e@RY^$qN%q2+WOwZA-Kj-w{k*|804>MI`$&@ z->*$R6)jHahS=`h!L%#3@Eta;#ZHt-{DZ7}zK=fNVJY%;y+%n^5iwMBihJna{E@RR z1}b&vA{0$cX~7HdbiGK+!bKtm2kne{%&Nc{%3X*$~ir zm1np6*|R^{nXZVQt8eQ`uz74Vigkw$a_%2&hpC~`9fDrue}d?4ORez?GSXM!smq`c zfvkdp6(AvZKy=E+* zU&kE!^-sRb7ZT@L!}N&-JMB4+%Lhe6MFAR8nT!mw!H5CMhUc1x15-XU8f1<8%K`ew zBuCWHmcS&)$|Xlk>lJ{GaBuUdLkG~Y(bV+8dE_OVqYyQ!jN)$m`JaY zFHbdjb9i=U2bU=lXQS2E{E}YT+M*Y&Ka~YhcGqWp#|@qC6izp-mS8t71xkT7%iA~SfO`CKdFUu@{%rRZ1D)FY`k6h(N)ylt1Ae@j&zYaR*I6lbG68eTqj z_IsvVTd5hyTmIwq>c5sST`)b^7ZenDMMUbAYUWerkv-Qt65^qwPRRSbG>bU%jXNSk z2ypx`)n2~qbDhUD31bLkSQajSmn@OxKx^8F1uTjClnoO9h6ivR9}%M0zrSioP`Fni z_g5Y_*paj9(OV1&Fq^`|HC1Dti%YIc6nevpdFs0N6oI#G6(YsI+w#$viKcoXiy>eq#aNmr85c@{- znbn0lTf)QHnmp&C=Ob9ELMtGJAg%m> zpmLQCWV&YmnX%l?`fSgbh{MGNr<99)lAOs*;J`7&^ZEuq&K4QK5 zxIFE^y(X{i!uggv{%V)YCc$Dkxl1+_uaH*+^gOMf8s`<`G!4xRyg`p zh&Hu<6%i?=R)6HmoI6$5KCHR@LAlo$nhP5kO>jg0R3`Mza}0YW~N^=X_s3vu@5m zE3XZ(#+94pm?TyGgnqWYb(ZR!-Cl*uC~b~_y1Q7Jq@4XxC8gie(C;bKN zncM<6b&vt-x56g^%w-LToB%)?ZNlz0atHo&<7%Aoy=V*$&q& zU)`x`g8`z5q~8JKe%br5){of+3LNtFSat5qw_o6rCsu%1d1A*#PjXe}<}VQugLF5frNCdgU7uKXUmka3-b5!r3m1mN z8EP1ZYX;=1Lf_I7w&A4|3q0q8tF2s*p!DfamI@p)rI1zLAK+~`$oKL z)sYWbFva9@Ur0)E#n+J*D7bY6uujnv`cU!m!@*Rdp4ka;L4`5#`wZ39sMcda#r+>W zaOZcGQ@q>!|J*S&V?$Wgzv1}QseZBKU}JTJrc95+I4~y(%2X-j*i74kbD)!aWB+K2 z@m{%4WagW9PZr;p5dPHW`&Ey$q51^`{My?af$P8>H=Tzka?r-I<2gDerhr8|0@z+S zve2a(fj{OW4WGl>u8n~4I$FQpJ^wrc_yFB-*m{+4RDu#r((Jxo6#4bTr-G~|85;_4 z=lXwMU^ca>#gIA{S?YN{PBu<+U=zU0csZx~8bVZ90-5S|+hkN!128uE(At`vYhpr5 zRr7NLPt~@up<{lZ?7>2(>@>MDg>1td7It0xoWHyLgzeoq^yh9u+TVsbke+O?r5QJS zu)PQw?%Qi(U0QVY!Ii3Xjut_S#l^Id1R%qDPuG73rPwAjk;gXmm-q^ak|eSz5AL#8 zr7MjJ);^_pb z1GfUTSyKM;(T0rITD0J(AK8BAOd=Ua*dFPZCX|`n%X^EXCagBTRSt!t*@D^QNQ%GLS7}*8ro#3lS2M1t_ z<#fd#dWR26q(p=3kGEjWLz=VUBd3&l?)A#Jt>oPc>vpOAHDm3bTbd{@^_@!oeObkk zl;&RTl}lnz$#^Y9Epj9DilO3ySfCM+OV-M1D=?+Xf3o0#soumHIJOht|6w^l65I-K zt&y^+@&R3P5&ds{RSnuYE|vc7x9$@|NOo~Z@c!dJ^5EQyF00kVk3OMeGU6CN+NHeI z*AJPfEd}s^OXfL^HIpCQ{}ZKJ3}Bb0TxwyG(*LJmpjSoIa4F)%yJ*yJ{aL_3zHC+c zxl`Qrb!{o_;)i6w8Zfg&D%-pyUAkd9GQ~vZ0AOgIQT^*X(o5&N6qFHHk&;Kih@+E4 znQ@0*Qd~NDaVXcL7AtJTs3qjHrWd3AJ8-o#@$)Cc*kz*ni9~)0*EnuHwJccc2jRMm zefiP~B=y;LKA*(RQC zmfuhmoh7q|O5W@De7g6S#QIT_-b|8L`YQy^m)KDZ<65&$<9;t|KyvV9k|4-G3evQfQ*D8{Cu6?XVt6Xj(i zLw5?NPD5CZ^bu5$-GqVFGFZ{JsCSTuFVI=Gf)it6+9w5X$ER1)DunChaMZ;K*~fnT z_|Y`vX~)~FeJZmqd5)-8;;AVY96#ZE0836X$hyC_wg$kw-97SSpEQr;^W)6Ry!X?N zImYAgi-0d{W|p?Mvr}q$t~(~lb|Mge&(cBYGotRdt*EA^CQLsCu?#ZhIBqF)iSn3k zvNfjFDWvP#r{`qVe3CXWA~i0-^SQ^)G9ScI3oaY;2!Q(|Ku5_Kttc6aT@UW{iH+T>pK{4-bB=|x7?C|yL*CpjLgVqHqlvfYc zFH5?dYIKWn&1t3NZcJVoMN1N2o$7qp9B(N6S-K7xD!k z(=d{w_4?jpzWet_n2a@#bc%VE0HR)vc@Slwx= zZo+V5X71R)#W7{sBGVzADklT>HW=y=Q&2?dmMawN<{MN%Tm%YwkPJsRa`CACfUQ~k zqw~cTKj8C_GY=9e_@CB;ci4-DHS~*5BBOaBjV&rOq69G{7#_Fo@s2fp7YH*FnaFDeC0oaX5Q)kIRf^ z#3O3?T(J=TFOMEO(vV0(XAFm{C1@4;6$T0U44kuMWW*3+q35Lo*x~jasQn&zO7)}c_AWG#6cwNJevewR!C|Q@H_olMvH<%1x@Bb_PmY|@_O@`S!{Q*H5X{}mLAslY1z*rQStpQ;xFYDCxzmHXW zR{PuAgV1mQ4!C1s!PL+vZNM77)4{ayic1qCBjQ`P3TYP5n|$}_K}2gG98_fwH-o?? zw{K8)$BXyS@CZLsCb9ngqrI2PU!C$D#wzeqUIHdHsyD&Yoo9_945||$hv7%7ibfQ~ zOESc=j#I>68bP!z-19>F`?7c06SM8d(!_d}i)8R6B~WOegsLZ#$|T!9eK|c!Okh;3 z3!h=gVr!5ZME{H$9n)1NT+k?9e~ch^Q$RF-x}|?8>1Q`GjSzOakvQ+_TNQd0!prdm zLo#pL*WITYo1XC9m>XWxBby)djSxYhg$T`$C=O0g^T2S8)VDAV$|7;ek%>~wnO1?! z_^ru=eSTH~dPFo)TxA(F`_D^~MycK#w^H2tUDc-b#}xeIXcq7rA>*ZUdGl61l7@y! z?)j)4KN|83gO1Nuh5hlj++5=BBem-gl2dVqU{sxTIAoA^saijKXn z%Juh&Ab^olK_1g;qDbZZ;$p&m<+KiN*-^8yg+y;7~*bx;eCpe*Rt zw!i+W$HT$FS@_I`xeRv!uWMifL)c!-Zu4A&SK`^xQRjdE(S$5Be{=g?yl6W_C7vv=X9YrGpx9r}D+2F_l+x`c`Y12SNwe}V5zI*pvI4kOMHi`U zJtI7H09#3cs|863<}q&`>`t{UDjw%GT{wBKkuTkP4!X5_V9q*R31A zDl>|QQC3QHbf_=x%bXto;UyV{!Qh_}b-$*6`FUbw{k*b4xUrLUYcH%vK*0{eKWtFM zAm6=aft_S}(p!hiu%rdI(c&fsKRYHcxl&hl~dzro;sH;`jKb{3dW8V=hgK z359Laz*7vBawpg>0nGkRh0+=-4IvjU;Q?XlC&pux0=?j5Z}QQw{;pEbzUooiFWGns z8J)m?J?N)r^(A@f_>w#F8H&b#1V%B7FSYCb&kOK1@UO134|8~=cOAum+Ehx~z>bC7 zbNKO4|Dv!K^3{+1H>hf>w3QDR*X2PM5q!Lc$CA`q6a=3^g>)1XR(_e6ne684?#^ei z^#-^6b*=tkR9N7^p*();Rq)8D=$D1;?#yQS-P$81?fmecLAqPGH#?PZPu*uT&yz(l zs5TvdD<>0DEKt*ptSOd;B}I2?Eq zwKW|zrNxgsqT#D%*0f%zeyZrI=9{8n36?%wni{g$FD9x^#*{>!Xi@oI2ZY-Lm|T#t;(F z4nsYVdtZPukNcP6mMnm>!PpMjB{h5dvZlkoIEO8MXob5*snt@7h=GV~$@bK~L@MKB zl3}&C`6BglGa*hNmGi90;bdQf*Sf55ae24C?_fkoAc@l9rtsgt>s%I@P;1P!d7SHz zgC`HpgmFx8e?wvK?Llv1jDw)oBsT8PQnH$15o-`$M^)5Y%)o`KRulUDy53LvRAFgYgL+lNRVuGIFAMLjo4Put*N^KSc=j@1RMju$ zE)Q;#`Q9bNg_vvyR0UpjtngPcCeuDBhhO+2>9;bW3(inK{wg?d(G{AxwK^%eYWDpR znyvcKRhmz#C@Ms@R}HUhMCBG=Bt6)0{Y6v#utX>I;3#F!M{npcAY<@Dp^J?nRdW_S zS5bd|^gCWWS|k(-^C$ogQ7&c*g_fmJMzSj{@82L8o&K0}e4lCh)A6KCl;3y@%%*IxVq;Wx-gqt^NzTFGiN zKYg0I>)621JEi{G3uUznH5tz0%d1cJqG#LFchPtm?GBea&|s0m`+b|uvajWWAJRs9 zv}YX5$su1qlE7B-YUr*)O>f~V$`$n}kk0RDz5A9R`}3O}N%a}m_tPMC3>U=s_@`XD zTck&kgW-Cdg(LYnG#=jG8s#EcY03voYG@XV87#_|p0%57)3o>}eN>H6*}X9A?*Li! zLqmi03A=X^n*y$t!rxbUY0`-*Rk3i!AaqQyP5l4&=*x^$a!EdVzw&c^pK}i^;Ef%$ z4Vq3<3-$hev~GQ-(M|kFbM&;-Y-_*jA48 zX)?wFVmW(UDAF z)sO!sEt~rS)(sSW735b*6}!;*ydlqMrN@*`$?NCaG0S%YRECV!!O~ay{S%jb zS9saE%HJyP=%G)l|D#T|WsLpsd35WujA9Kd?+J}YEZpM8{nql{-IiS2Io=!Bmz>L0sa|DUTHTHfFVzw1t1wg~DuzTJ)#CudE(=2R z;~F;3N4j|BH#$u|_gk-K&>vcwETjhtY`?;6X72g16m&)hm1QC1*M+vl6&5H@O_jd4 zKq=x{CG^NXlIn>mYm}Z9*V-GRJcr4W&rDO(6{#m@DFUez2h!imrWbC?*-jRO748gj z@?E$`H7s~ggCh}Ig*28BZuwx1=RqzZWHhgL9O_Xr`nqCxINN4khJiXGm6Ry0DFfg z8;lK9F+8F6=DFPIpR&nhImXAljP(`r%%n@KGRS;o0?(5`KSiyD^b?thRJpqhm&)V- zc-KG2HF4%Wn(+2W;h7!OALM6{g(`e=!B{zN6E&G4S?(hDo?gbAX3)pxGY<)x5&SSfYI@e`kQuO^OQ48 zUCJoE)Bbg(RCs}CYSpB~^M1q9eVWqI)6>%~NAigI{rCI)XxEZHIchtPbpR3Fo5(PF zuu@Zt(0Ry@ie&qP4G?s9;m2m0K1_-@YAosJDOkids9Z~G9J1CsTQrv^_3Q|=7N%+H&80KhVoPbBx%{Bui zw@s2sF$xY!Vzo9Ic1+6QlHyIz;v%}Op+DJQDrJM8IyBisxTn40ExmMqc13MtNjR#q z%YN9ff+Pil2IR=u!}<>?LSDF+z{MNHD7XO@8VbV885MEvCLl=vt)Sw1qcV+Cn<>0; zm-%C46_@UmyZr;6D5$|AVU!w2V=WN$`uw!{72hFzbNY#+_n>Uwx>+|NdhX!ULHRZ4 z-)j)xQOo^;qyH5L<=qgN@?!UF1x3Q`s(fng@028r(!gWH=e zC$yLfOT=OGJppT{?-PGJSg4@xFknjE3PN+ePG0WoOp4 zd39yn}j5%*63dT2m1HTVPLp}x7SmyGuyhB{DU zd0LC|1V&N~(Yi0>^DTPgsnAUUZBx&(B5$H6WJO0yd%jyg>UX)xl)j+Q^7-N2EA>94 zBnyuqKpH-Dh(YDs4-O09vndj`)P5@rxw%HhZ6Kl$OEZDZ$mMX&vRL(ci$^?>D4a{q zI%Qz+Hd3Jj)eW)(MUtA2ZSeyhLSKaxQ3vB(d5{@Dul>a*%1Nv?WHyYUtc^(`{jw9x zLET>?HKZ`AzBh73_R$w8j}uLfdZK-D{b2=iKOzvk^bK52h4pGBL(E+hX1fx8cY|In zoD6okEq?77HgjIjj(cPQW_f&iNzqYsWj$nxg@sG@;z)Pv*ZgOF2Ika(&AEE^$t-2( zB5JgJcZ~49eik$xdr~>qDAOZNEoEh}_F%y37?|L4jTI>3fpt$+ULF-}TZLM=(wEl( zgJNWQh436g0#9r}U1{*nb9qzz;%_~Ya)%|&J9Dm~SSf_MYp$5}xDX#hDzq?Nqbl3m z&ckEmr4;jE?R!NxiKTvP84kGJ#g@lH@wW=buZ9~1MISOcAo#JPKB#nKG;XNHD>jzj zkC1xcu!D*Av2-3y2t)qCgRPk=8Zg&4IDLP$-+Dpoqeg)x94#CBFbc~ahwK#_fzeY) z#!Xdm3;YT_vl1yuD;HRkjDcJ6Ntu*-VB3}5TMxSM$A+ar#)A5e1c!^|>T8ZvMz7es zS|?#3043o>xgNA0Vn|#gOdtV`RqL2e`CRS$9AAxW#*0nfvHOJ8eT%4_zd9-&%@D*1 zM85fCWku7?ElUc{-`CKjZm-ViwX2wS4&w1qqE4Cc46RZ*7O)dAV!lME3>k`OGPBH` z;Nad=MD#gqwyK5C^RWGGCj(v;J|!OlvbCxiJj3f6A$hYB4`+#Qa}!qC6-)M;bD6UZ zNPEQ)qAYg|Ss>o)572z8`x=V;u{fqpP0xQVb+tU<-2ZN0M#@oQ_G!`3W7CSOm?w5V zOWy~Ucz|u59rCM*Kpln2XQ^^B^H=}ETy!3jDbewsg>GoNVC6};Cbgt6wOczz{?8L# zJ+fxwnZS>N311`>{th<2f6;I5<<;P7kF)@m-`C11zR}Z9+6!|T#Id=T4D>B|^VYiB z(J}OOi>0>-N zPvWeQ+rEG50CJ=EN@hu@NWY?j!lodx+OHwQyir-0l)qA8A4z2m#rzSeW_4%%SIdVq z7pXKtx(RlMRS_^c_5rq{+?gDoo$da>t3MMypYe%B+M9OJ`e8`9Wn%vJj8i*p=#!$L zlnmN9@^xi@PlVpwoaFbtmFX9=g{ND&Kl?9@oN~#K(w`vVV;Z9~&T=2f;oK4w6l_@% zUf$ay{2v4cGNb`Keb_dD2l0RTV%5UGnO$Rb>0WPD2T)_w)0HPv3RZPXrfW^j84z-3 z5r6U)Xy0!S36qeJK+}a43M-R}_xG7j>b$ih?LIe#!SKl*q?g@zS z=QKpv@R2#Bdwjp{85iYwNMQqsF)DLsLJLT|Ndjr$?2C6G$1WwIeZ-rm2||*#1@eq5 z!i?d}@~3PtvV!D*?#I0IOIGpp>13m$l=bX#Xf*0>`S56~ytQg=B{X{y`DhqJacTkc z;!xrqg`!&ufj4_aFOtP{bYqn*F;9t*mVfvFaM&rbu?dmZNIc=U-E)M_RUju;rXrXCl+ynXvy z3%E|hs=N*pgIO-LsLpA2qS#WIsdOwle~L<99ZyPHTKPb13yIB!n*omZV!%60T%|hd22S*@>}#-NlERezyAZmXQ^h8 z@RwvWOxR9HClnCUHH5-3$Ex)1Cfsiajp?lCQgcoO(^pJXln>JNzeZB6DY~bpAKjK! ze*v<|OBgD}+>{%gkfv@Rv9l7!Lv+6b36$$YBcUSIN5r zYVVDh=N+ih9p16jEAxi#{%B6e{YbKMmU4%*IKWFbkatnG@1K^s`nU6lXQW&;6&155 zSzMt&W81lpzHacG=uba)rBdOGmS0R$V>!rU`;K7|G&9mb&1904%m&kPEetNW&EHL_ zr3>9)4pPgFjlIWL+pUBKczI_ht~8bWwdz(77e+=PB{Q;uDCn|KlMxkFvA1GdOKEF; zz0CyNlTM&D!84CDmw2DF>i(R&r4JKlk8a_(HY5}w908$b3J|f8lPqzE^Ih3NL_zW4 z;DN*^0yROZ@t0u_CDv>t_LL`nryonN%Um9yL0S#4q-hhE4xP;n978>kdLvIvL)FP; zb=&jboL@`hRep_ATkfD2Iw~UNv8n%9?c5HA7>AikD(FLzco}daSr;w)?}WXy(Ta39_<1JjJMV#nB?f^B(;u(;0JX znXUM8fU|`Z5FW9x8xTx>ohc#;+UU>9?WZOe0WSylr3XCN_`JqwSY0h2q@(c?_ZCK%6M#vVVU3Ad(F2DidrfK!$m>!+ddO5H|5 zn!n2Fum5KRLQeaZYnJnLkMEMBi7iw6q>N?p+n{JuBinSB%wGkg75dpWhQ^RVmD%Hi z>lQyfJFLh$a10?=g2Egcsg3>k4d$mbUh{V_w~GDQP$`SccFAr}PI;%)|-Ez)N*Ivy6)d-gdj9iq( zdSY+Ck?arOTyDrbSJJqJe6YT~EzV$i2HBmw9N|kbVtIxKFA6dzf4xjy{BIyJH9{xx z$Dz`l)bY=aI9O(XIFRD;;WqBVBKP)^ltHNwQ_8@xaesPx`TI zHEPVK9Q#>zviGd(wjMP5fr<}|NyQHU}2W|#-#V0)IqllDRY#Ya`p&_j@aCs|?Wn>}kUuG3@0T`UOC z!bqIOsLh?CyG5z|^`WTxuo6R1T0+hCQaDl+R8YQ+{mHAO?4I+<$;zL&WA!3dq+L!} zs;6P+apa-6>U@f>CMGdpRbkQV2)u}pup)wwawa_hJ_U6g_^Zt2cBJv6IR zb(4L1D*m4;`=w9!e#Aj%0lO;2_haz8M#!CUnI_B1x4AAPh!{%t@KPsX8!W8Gutm^H z1}d172DzYj@vM^UUXdZZ!$&s-^)?%WK#G_GClmYYEFQDAVC2XP`PhKT5ip|yutjn8 zz2B_3EC&t;H_X0s23|aLL3>hyzWM)4>(R#|5x>c9- z(M%CB{!N4&LK@hNgVFPCf1**91Ie7}uw%!y>u`=<3(ht=-IfYCUH!7(I`osgv>OJZ zWq?Njrb^GiKrAc+JD9V}jUAmYF*`VROMY_lA1b-H?RBiz+TDPHr&dk=ddC6p$%(Df z60LH|%vwH=JQHAuLO#-pEgvk*6@^eZ~u zLon2yDRlrjUP8vde#&1tHG|0$)Fjv_5f8&DR8BNy`!wAU<_!VN5~*g)CA<|>hmH3v zlCXLa;s`xRGMA6*R^Vb!1f`|V$dol1APzd`<}xAuUwD`#5G}Nx>?L|693e#>kp!V5 z%P0u(0G9v$K>IS3s@Q~tCGZ}be(}*rt6IEhe>-z^2>u$tSwtUPfm0eBHC7sx=)xx_^j|J5 z1;KEUc0~`??L2Mc!bTsk%Jf0QP;N9XI`8Hqe<#(_ruaLBIBa-;!5iq&I@P9Pz&~Us zvm~kGgkN&`m$<35Y<&My26vwDE3Qdg>$+VRFE#1;;;NpJ=`C|dVsujU+RZ{$jJMtpz|wa1FbYTqNmYP?$PW? zY;DtYS^oRgXTe8GU7lYs;Vb zD8m&EI2EKRPrssMp8$GQ_w9*$S12VM<_g|f@inwUd5hf5fH4cnrJHAOK??=g?1Jgziid@kU>^cr z!9xxlHRMK+k0K)SX;B(MGAa^-fzMsMEV{xWHMccj?=v@;sEBZKH>`}TVZ z##Du2BE+mcV4DuL5TA3>&B=H3uY?IxOUqk1LltOY`*=eZk!)!$!{FQS2fGi9+WP6) zrAl=zEECnKw3OVKYTq!aq|t@~y{>L`M3?32Z|o`&vA7|B{<2Br7oHzLgcIRP=lWi< z1$Tx9^w5<2R_I_;!YtMywXzsBn!TYaTgjJaPxdF{ND0DAdd}#GCy^6i>vH?2W&QOz zOG}}xv@V=O13X5v@+ZMzao5GX`15EQZ4smiJ%LKPv^gj;{xNBR|5+fcZ4Kh71Tot! z-tY>8&RhrRFj&@*viD2<1?2dU`=((LF1jq7HGoBB9T8EnW{c1E9x#xcWogZDP|WT% z-C&n-HRW17&U|57?fHdf`~wA&HsJru8*Cd$KhqMgvWd~C7L@=>P0cNX8eBa6CmDi) zQ%0cQG6Ws#^p+k9Vi)TU0FbfF=mT@e)yZw>sxOa*c!6>ESd#HLbJN$}uF50`ujRh& zEaOgik^pgYBTJ2Wn=QD=I4)}t?!w*K@TS@A|G64U;@x<6tG3}*gZ#Zl?M%drPs@8g z{QB5=nnKpS=!+|N|7ok9G^}OsYwXegr#em1(jCc31xuQd)@Mjt&J{dP|B*Cc-Qc!F z-)NGcT3i5;MKABkwpYJHDogs>lbd()uVni@^_pqmPyuEq834urah?)1`qPXq&_-oW z{r|iGqvPezNyM-0f=_eqry`dO8-Xe<`2Bjg)O?mDU?0nJG+&$Q*$e5T1V4+ROz!#T z@esFLSzbQqAW$~|ybK2D!oW9>Z!Lws1|&U$<3B>wO@E`c{gvZMPO+uFuV?Rud~JzAQXWE=P8N4UBc^o{iCuTXtopu&XbmeQ?G3acH^+i&sen;T1(7rFx142 z^iCGo`AUT@#SlFAZZr5foY~`I8rU+X4j}ztz*P1N*aYN|CcPS*t{#a$juy?8pY*S4 ze@xJnasKv(|H4epCr^Rp@apfOzFn{fjmBG{d@#R8D6t=~YQA4<6Xh&Y^+_PRy_uqM zaCcs1BLq0Zv^n*bn#lVN`dKXCuOQ6|;HgkNhzTH)i0)c^X63?0-BngEwnJ6OMxp$= zr6c2GK~hI5A9;(CrshU_plmQ^%0GJn#obzFw4S}emOJPRp*(RN9cVX0Uz$Vw2neLe zXO9fjYn@7G>C|NBMBel?Te`eHL+b};qc>Z@x{dP-BZMiPiOo&32LKlp53W*Kf z3E=dvCOcgDV9p1%Gwdzpb2btQ_>keuY#Y4TqCj;Nqo&oR&6WPSLt1YcZp}idsGUVO z`V#MP|NN`+Q&ak~+|yV{D1r{3$xxz>1*#Qb4Uqdr5y)kiu$=1edX}5} zv*cB0vnM1SEDKurCynP1lk`>@+#|kmv6lb4;W0~Gsmop`k$Bb^5pbxuWj1qMcj8Y6 zgB;hwP>HEz=_2;l?>HZID(TZ)HOH^x-u$hk#t3<}N;JeY=261;Bqa;)^FeyLev4pS zE$^=Je=9Bhnw{^mcGrrcac~knkMax5DVh?=PROJ0NBQ=HlI@w%qrRD&U1{ zTV0ShQ|$_8qyF=6-|F*csHx{_T&yiChUBYZq)L9g%&po{_yDVk-J_2urb zaQ6$lL(jgy%gb_b<^yF9q)+lW69arayr>AYfrU z-JN^7&9=r(9YnY;(ivw=b@%PAN_=|j&2@l?>%9E_fM@<8D`g!~YamY0C)uie;80n) z@D#SH3092Z zJZfbyS(C%nh{UiU?fn6#&IN^qI_3JXahXbb>u>|&96x(gsJ6Ug!TT2t zpk^DlKa!lRA>MJJcfDM`qlUtpwDHZ83dh&iH+bnB>(z|P8+W?(0^Ke0g8HZPm+;6S z;ambXg9ngq0vr(1ggghN11M1n0q?o;!p$7J`P}E*#+h|xDXhrnOu(}#*xpiY z+th(KJhJ(N8XxZIsKuZ@pSfkWMD;@CpL@-_XSp%o+M64a9B~4Ai(Zk>dLM8g?Vu36 z=~w^R%8}pVE2bNu zefwEN?=$S}5mQC06ADLT?|bMe|7-h<-hP50ho8IHBIX=T%>Qios`2uHrHEBGHvFy# z7&rs%7$Ep`;B^Jx>=3k*NOu^Vh<5O;zzf_rwFB5v=|u|@i6L91lF;Tx`=DqQo!MnzTzaRda@@g+_=jPH7O!hPGN2OD4bbt zv^Lz<;MtxI1TKZcjLg%gPmx_Il5YY{xO%2lkxr29ZPwHepkyMQvFlG;uTKBdCzoG> zZQAz;gPNmy7Q@VNwZD?!&$;oPAzjQs;pqg(qcKbsdPf=P?(l4$`KWR==n^c;w?y?PcUS{yYj<=pK#Lxp0;%H>(=waz-_NN+0H z86{?Jb$ZG_jeFPLV35=>%Q}UH-aGFCQ8pv-8>K$-5d$iV?9@+rj{J;({(R*)|JH1pmoU=$+rYMpG(H&7076^A@@vK80i-!O#Jg z`e;E>&uR9xNlwcVNeyax7LL@#ZmxsUR9pCL;q>>1h11)kI{`ZAuk2I?lgY(nF`JV| zvcxcLP!DA&`gG|Y{PG@8^GK`D&uS#@p$!^oa7ra6A$b9zg?Fvh142~VX^?sCnwt}2 z|Nc}Tp>hum=+)mQLpI5@**b|_p9|82o&t5m7YCZ0Jn&N*nV1}1oHzv$hza^_;C&Lo z!F?8C<`yHr){W8R=;qGty3i~{&A;Ow__|+G_SllkoBZ}MX~LGE1u-(=U?qh|(a;#? z@mt~4-3wEH2k(br(G6`3=>RlwnP3S9?N#6R)AH2z%`&n3j5hUBU8vt8=C6*9t^?s4 z69Q}8bz^nw!S8|&(AdHrHIY4UTZ{^m&>Qb}uP@$sJfP62x7C1<)a!pXl}*@8#o+nS zXzMKXV{i@mrTFQ{!%XS!=08J}ktM-nbzZ}2+C&DKnJY8M%z*$|^sfaZp9bf-6eKq% z{{a?=iYHi3Lh=G@yOIY|ysoJOiUu=&q+}yOfUP)Ob(>v?`xHyjbV)Y2*gE6IWk)z% zB3ECd-Xgx7OCl>Egq1Sc(Pac5*YzKEg{4;Fj;>D4ej(bos7iJ(rxuNsEs&9E*f8b+ z$qHn6#?UCh2MB6imc5{vc$NC6`UnLth0#tzR&VzAT zAS`=nYHC^@GsFK%Lc$?X;pEi4baW(e=$Y_h%=$ftn**ZC$%XM(C}5yTG?wP3+Hw zU%Xl*tCdv9f-Qo$RL_$a?5bGL zND8{W|7mrR-i}!hn109nxYn24CbLkmn-(SJS|caf%Fw~-4Hd|c=Fpk|hCDj!^)#Yautvl!dM=QS)G-{k3p{@4<1^53!~urkhke_qN5Y1eZje%r>?%_l6y zmW$#3S6!gVKuj!~%sj`@n?YgKWohQG-P_ThTEaOOAsJ>vpwRWaUGr2bJ|8f805JV? zFu|{yOGWgv)#{dZz?;o`^q+|@UkKaF%XEyuKEue5zo3B2~gaNN4|G_wIP;92W z740`pG@RtXh9yj_N0d8Xj34|QE%MH{uqC}74}99h)ZOFCukE7?)fv!sR_h9s}w zK2|?zfY3aK#ir7|WX0dN*QyGHPl^Q_xu$K_+lr@ z@&d6q{(Fh$*}aRzD{?%k$4QeQl!$uS9$=Y#j+!hcnn99T+mgi?ST=2C%PB(39Imh> z;BcqBHgw`%4`FNImxbbAw#20dAsY1&%8TVLa{(+#PrI@aHo>RKIGd=*A$}(RQ%umr z|1kt?&{0fJdmk?0({XZfQ0%^JIinD!*!^(ks$R+e);|8u_^ih6!>6$=XN%+kU17qf zFB!vBb;Q5@y`JsD$5tj$TTDEW{3AM&9kAcr_3g*mZp*0&gW)P+llxCp?`=w{1P~=~ zWnpM&3^$ol&X7`gZg6I9kK*<48yZvg_L2RfkJ@D@*3UX%`6zJzk?~e!>KHj(ne8hv z<{F(*5nsJ~`g-NxFdehvjR>xA=yv!m0(yR=Mr%v&iT$EhU9ncEJ`DQ`V?&DkkuWs@ zQvLSbUj*?ES>eI|(Zin@?y`^O!6Yd#-tPYA^SwJ}AKIQWVAx2gA(}rXdtVn*^7(PV zn9LTM4hMj2lR-reiE%m@B>=FmpTs~TA=?dmMkrhU2;eXSZa3#omtO# zq@gOi;cLv>bk9eyM@alzO|Gb$qET&lb({G5`kz~gR_@5(ap4YXp7XcbXbOx(MR+$- zI&equm^QUTBL`p!W&ovZfJ+Sg-BGH-QL@+KR>JrVb%)FU9oaI-gsxU#_>2%Ar%h03 zL7IgeIyGdlX8(~^{NJkX%6=%-`{4d3*mn|kuQJE%x9U8eWFo5~mYpOOXoavEl7$Es zlBdA6E`PsrFaEYx4q@0k)r-5!AJEgv+*Qion!Mc1YYe9p7yBGY+ng-aU75VZCtmuB zBgg9Gi4*4Z=!@4G%lZQJ3DR^bUBvgEpY099*OXZ^y}pqx6;yp?9ZN1NL~SoZ!@b*c zVUVkfB*KCyUIf^0&>Xt>0-@$`kf_<@P|3Y|q;n}KWKt#o02$o2*3i?6j^gBFH@|nc z*uQKkDpFidcZq(ftE(%>YZg6{n%?}gOmcy+y1qt1Z(mr*hR`4qLImUbVVEzJgNRKj zX57~zJL=}B`1E(Ie(9(#Mpdj|H$t(KR|ha#;P(2vksG4hC;?jr!5E4JV}gfS;OpMX zN|-?fSV$w0t?^mb|D)-;7LqL^BztFuglw|OUfFw( zgv=1i-t)Q6@AZ2A>7V=VE9ZO8`CQj~ej@2JZQW$mjFd}QgNG4|A{qp*h;mcfE+H*# zUe9T=*Lo@&_2~w>%e&Zkhs!dl*1TytrE0PV6Yn_PAlB$s!rG|j0s9Qu=h|KWMb(4< z7`zUn*~vry!1{+olS1nY2sPMTS;_!o%{>-Uz`G7G)uhIF6n%wJL=nChVpQ7DfK_!E z+ps6p^}S~*a~T-)*jQo|LqkI=md48i->gE<;-2dij?gJXsmb*JhO%NWmiVJ@qDrC% zP%b3rQamqkiRt`q#r-GF^lOepTbD|pwAsRMyu4XLO4Y~7?we44CkeB(``G~-LTetZ zKh&8d=U<6^8Z+ZYq0>z|&54COfR|jn+6>AA3fCN&KQdZj056c;t3WZ|EH+E%=JPPg?#wF*Y;X zzj6wR^le*irx{uMl*RgKFz(>FY17!7pR%DAQP|GY^y6kEv%l0PrO|gOqA@FoplpW?^{s3vF8h1ac8p@5~Dcqv!0S(2L*bEg~Ys+{C7l75v`gvN?TMifZN5p=*tv4JFW*7$0y}#UM1FgbRNlo)SDuAJN>jd#)r6* zO@^7c6SY=lgClJwM=TH6b63if)q5{OFj~kbA5)G?68Xwy@?mLtq5O32rU57T;@Z)$ znUHxmduwbT<+}!Y4OQ~+oF9|BeT1z9p!wDR9Jy7UKDM3*sdUYkM^wOcBW_{_+aTda zZ)SrOv9gC3#5R9#7RIM^WiokU@?WeA_&%G zSOOTJ&IxoAR9RcsKR|e*toTptQ(fY1+H6byOX_58?zkLX-V3kMXh-s5A_(S%t@=`P zaOIlNaD%OHn|=D{3%^cH)b71)BF_@q7f?QmC2|NNEg)DGE~&TbTP`R^ZC=`<7m+Eu zx>?KqqsHNNenFo zsmQ3s7$J=CG*U29HNP?cQ3$FNqCq2L4~L+P(1>*aBOX&NhdOir5b|yXwi4-6^YZ58Yrx~er^9PZLVrxxTZmeOa9Ers{ip(ZcF>i5)9tWOZsVQPM?1ql+bQc;&m zV)&}ZS+qSd?JkIBR4G;E%xd~7cXT@UI&k4e#1aI`K|qC#v`fHDeUs8{@G^ArgIu}; z6^GaTk4K{=J1acH_Bi*`7+S6i+#QY%hriJq{X!W0WiwVb2@sWgGeM17OMaJ`5alzIj ze%j@=%t6+_{H}Yh@7Sk=@Vyz)drk_3tc5Z+z|R&Abe=xj78z$*>T`HxRY5pi6kgww zW5`<+%v)pXVLD25MjG7AKN$k=OnE4eoN}Bp@aOpFh?C-Bftx9G6eP8KM`|7aDBEH1 z2ML=7E2DKSejc{FX_*Fp1Xo|Oa201&E4~+36O5liR~ zC`=#$jS|>7YJ|=?cItfIk$=;tYju_O&hlNSsdX z{!Q)d=+>em?@P&)mNAHipb$ayKqa>L!8|cD&*#Lz4_)5UKdvC6L_S|5grsi1Gq!@a zIVVfBpI@@zUDlxKi}-1Q5I;zeMj5^=m>y+8BiRrR0g&KHjip1hkS%Gp4(I)V?R1Lqzo)T`^-z+U>^2f{> zC?oa_p?JE^GBk9-^wf3%t~um%?p;=kv0gco$|s*1Zyr^Ub0sB)IT@E+mMd|N-Bux9 zKd-IPzvB8Cs8Ga&Aa=-Bzbz=KV|h9BU-iFMsWDkaN*fcdojMY`XMDZ0U=9qECcEOH zXJqsT-jUyFRi%mRrBuro0T~Xg(pQCmQKMekE&z1$+m?Y>zUf9@B0wINY;WigrUQh$Z zn$oaKUr^>rAf_TE+oK!PB`ynBIfvxR>yr?A61r^L-`MgGXN6xR1ZPaz+h zIqcs7IE@d%!wIfDvh_=$(Wk)yDZ_4+%&iL>HQL_YMpyS-LUtsDn{V9ly!&DQI`~S1 z6Y8uSAiEY33xKu(Da6C4dhmP4q|wDTPXc8G$M?YEBRp1R@I#<7o2tuXzs`;%{q>~M z>&1N0!ha`=)&d{jWa#4Ao1?i`SeR;3;oh12K%X4(5k-LI4`=v;uY`{ccTj4|RDFXq zZ+4rIyjIx}%@_$j=tglJ=?;zbiTJg6)Fj*nh^P`AB%tm)W2yeFN&r?1YxUwST|R-g zbyHttv6-faom;&jj8VDARCXb1PCjo`D9vT(WC)4BVP^wfLOx*21xN{IPgxoo=tXhV z;g2*Ac15!x`)s+Hp5~tK5N+@jsQL+@{o?m@ipDKPN%=>$YqeQ-w(z~|I1ZmNJ)GQ5 ziWd=3V@u)2f4o3bQ~qD1P-W?;tSqahrY2?{xEk0G7it=W>h+gq<^##j&!N6^rHCrcl6O_A&VOMnp8)G;TxMqG zSLhJNxi}8iAWm6vqk7w;FODH)$R@~_usbU^lfPqRGtrLqMoBg>+cvH5Q;#=+nl{L0 zo&w&eF!yHUiPGzTEc=NuM)^OQ9OhE*Tg9L~g(Wk7OZuJb96BWH2wfOlTRxLn?=+8d z(jEIRKls-2_lo_MLkS#K(mSAn{j7rAaXGM@cFxVE!b$N2Qi5T$eGgtnh!(wo@Ym0e z++*NJ4reJ6`?*+%%%P`l?UgunnB#AQ$^mJ;`^BJ@njpWne9JyyH{O@=L#ldn=ONcU z0is>GtlAlFzgex(Eo!2+fQ~)8(^P+18HzJ%2nSzm(RAN7c<@cP=)Mc-3DGYq30pgA zW$|lb9V{{bg3Y`ee;p%UG*)1e`Bh{(v4gpp8xopgA3D8Q?u8IGGycR^6nsl8DyjoJ zySp&7#sW#U3l%XqB&^>d=RjS_0n+mShE1642}O{9T;`nKOm3HG+A6WSrg(1Qo1rS3 zPPRj+Ra12sdYDTge)qt1c43S)S)B4aXOnndKR0Wy#m4=QJS7nc=KJ(F;qB?*UICfvSF zt<0V!RsJAk`B%{h?_}HikcXtC<^FBi7E8;w{POJcU1~Nl$@a&6s+3!pUrqN*paK_F z4%Ws`TD@vXEH7pJI+Kh4Ukgyzs4oO^ve)E59H3vFd8p;cgnvD_ar36hNQNxZ{HLyejFVxa*6J!}mp|N0KL8#LaGaTy zRS!T?kcf?k!f!@X{hH=b{zJi}5&u}X!L1B!+%%2YRPN(JrFEEM1N3XTIuKU|wnI)0~fUayn5O0!p2VM)~VZ<1Joq zNxt;=_m4wtv}VIgt?`W13l zCZi}{L!+2R2`xqQu^Io@{e5imtH|q%{SP)Le?NK3%gwO4953XGg^(;X+Z%+rCc^}z z2FTh{2wM&VzWp;JWA1T!tpR1eh?nnbQ~c6T(kNWl4s9}r>VeG{NKC||6Q>4$*WT(t-~7Al2&j|- zF)bg#x6=6f<)Z@Q6ZAhdk1g}rDIaOKe%@>4_Sn~t^GCJY&P56+Amy9Ig8-5tkXot0 z`XiU2{ff}}Hw&#^qUl?A(7JBhq~g*%sm-BFlmY3e+i93a;6hlFI;t*jj# z54#ih`rlh`A)H^%pfK)BFG{rgO}Bdl@gAN8KTrXf3&f+40^i?r$XR^yUbAWgQjFHIhj2l zyva!t=f#&r$imypbVpX_+S!>c;Kk|cp7&bw_@skb&hX!PD9*9f%YBYzDZHLJbp4KI9rd@_Vh2ray+E0dr(i5?+KuuT1EE0n z##`5#W(XFWJ`I^1ew9|naLVv~W+oXf&scLtD!14Y0g43@*+Kv}_U!?5DoSj(>X(!H8ywC}csjoi29Du13=it00v4fw{B3RB7kuhm0DZH3N6aoSQ zq=W;)t_c49Y8hdp$@5r$>)*ijz>5)ZWIHnuI+Hy~xFEwe!9>6P~9AD4z$jC0u+?_nvYXzDhT+T~<+ z40=}AxY!6DLtcwslCz_KuT+dIx?67^_rma%gssUvH4nu(AfxA(7l zp4m=3q~(!c9){#+sb+u+A(T@ZlmAw)uK#zV z-Fxty#%bjwE46JgOyV=;nJB&`98N);fBNGg;p3V!Q8$n(gxB zlCVN*Tc)eAjt6s&SSU3kE(3Jm`i&l1tci3ue3#5nVzJ^a!+~EEmh@yvho^St1D>+8 zCU^xLSNj#AybT1@cMfORHS|s%Y+5|vIU@#=9&B>|0pd^t;)kXEnntpFhWpdAA?{si zu}sQ$0AG9QIX^B{Xo~uHFw4N{8KC(Axw&igY>m+-3q?X6eOhd%-+pC96_ih*24Q|* z9z((U(Fe|xZ2ilJsIXT=bLl+*?6Mnh6eKwhG9KX>NOQujF8%82;P6*}?6I0=|EfI6DVYb9Kr4cH6x?_My8E66#UNI5FJYqqQFHxGIDYS=$T@Dns*EO zu~bqAHAG^9sPwY(HuZ1wH`f#1`_Ik57qfC=;wBHv=nFohHVaY$@wj+;A zJWAEo^i7;d@z7SO0zU>~|3>1m@zXoyFNY#w;0LMTQVGG*&C~*Zf9z3qM=F*`YDW1; z>e&YOSWvc8ahfhKp1nY+nw`k-0nokhvs@+5%Y<21m_zwygWz1$c=m{iF{^D zwD;N3st#^jCHNjLA1P)t44B-Y2ROB@uP+R?$ufumgHb~nI-91xS;gLcmI9fqpTt>= z%Kz1OG5PnsG7c%2ihI%9C1oIbRZ9{Q5RmNX{ z@WZGSq7S(+jbYM0GC)`{ZI89|Fs`^C!SnngK4?YK@5!-H{`o8oC~B3Tf|1z zbR8$@inNpMQ>0$q(=|qUd7Wbx%Y%49A>AP4-TUzOO?MBcXx>d%+NJFzj%NgmN4UHa zVhw=Ay5|*20@jXpoZFC42ar~tZY4X^6R|+BQ}9^08|Y$eKTr43;r}~bGL=wy;C$PO zGuy90PZaU-mwYiMWFjyx9 z11BDhNE|R^_8`*6xx=Xdn!28725jgiaX;1&qq(`f;yg&Q`sP3|km}MsXfbFG z-SJ2FB12klNfzS-P@bG`pMIllyz@`emG#%nk%mOvuqKT8WQPYIYB!Je!z>DiruE-&tV z>c3Zb$euoOc7==ks*Nd=#Z84yxnbzxJFaDGlObMC!@2w8bnpq%uo+Q^zA5~@dTC2p z#U~`R7RJ-0;MqhOp+o-ao4pxFrQ<88bLWPW9VyG1+fh)fEj2m{d7w0wOKR$2gHrq& zB}**_aLJwwO30f?fj4k8$1`q_kF;&9C|j)&MNFJk@fPv^rMy@8faG@pQ)NWDPwVqmx5-MPg>{xZksVChU>zKQn_h1!?5~?n~Ml zDTb4hF{CN@KrX4$?;mpbw>+!NbRre{KL5-$iXt1$)%aLxCC{t`Ct95Nj~17E3EVxH zB30*^s1rdxYwlJ{v%^}Sgo^mfyw2YYri%5!&4I{xDy%UwP~#c}dX%!ve;fyXHo^$% z+B;9=gD60L?`gGMVq#AE@usNs?vxzX2}2LAV!J>rVjwhMlnX^X52&rFiJDmw>_6|F zQotGA(f!Ne&X~!Z7YEkZJ0Q!Z*S*nrWo%heLNW)jn3iK*Fw&Y z$GMrHpQ@>^r@~k@%>=KKdH)IO{>JqyH~Xh(@1J8SK4A=a8)R(8Q~RpQDKPTYQWAS5 zWU|5Xt`1kcW@ZC7m9N|KPKWt3y)zr9m%VXpz%y=$sWIQ7rEVL%kCP@O!dY-%GIwkj zntLd=;$Q|;jJ_u;?6iuPLrEj^CxFzfND>SR9q)y;U{`w)$>~oHWM(4h> zGuUidIqm-pU$+S32(ywNga%&-Uaf-=8~`$;py;8~>Q1Ao;a;-zd>XTQZZkTKh_iyn zpb;K%_FV2-zTv(gSi^~!R;Sz!Q3Oc;Q^?A&9Jv43sN;(yP5v>)dCzf;`W}-c7?tsF zB&$|eN=!c^WR%s)Zk|=hF8!$mDT7t7_28OzfOK!E04*(%SqKGgMqAms(XB3-aMno( z=YDEw`6qXH*~8AWD#PrRNU+aLar!oG?iibkb(IF6IM(%j^^L>*-*js$=-F4CB+s(c zt}UNu=GDO%be_^RGxlpgRwMJ@_(jgg4LIn(f&&-}wH^|yp3BP17r;ejm&E@wIZf|O zc84+pK-#a+1C;zl9+JQhm#DjXd)ep60U6Z-kAWaehgmEhX32AYS)L8m-lr>MZC4NM z<~Vt->f7i?PyQUoSf3oD&o#c=?o)~wxYs3ol)JbB1}=8!x^4)ZW(6c8zOPsdY}g7O zO?<+_x^}yj+B2X|NZ+_FLZjY%JzmZ*4<{K2v!4)-!~oqPVteFl3E<- zxO+b62zqz!2FZkB5`V6qEN`!lekGw>cItfj)*uX18b1rZW*yy5F5T>9v4v}e&^-FB zmmzogNvb><`2Q+lThvP()3C)FyHc^B`92R*q!qjKpt@3_$Cf+P|lYH79(usD%J z$t+y94C{%nkWN5MN*VyXFL*9P1m1v00iob*)1I?gma7OAZS-%sv%iosn&rAKP`<&1cZj zU8o2jKYtfppRqDPOt*Y3lYc505%c@y8VlP#*d~gB*UtxA<4VA@4{>L|{yW-jH!!TP zWZ6>sJ&2ker!iu+SWb2^S~_1yaUVw=HslR}2^|7cB;EmjCa#ZfrDwoHY^cGOJr1v? zaabG2_t)5TOxA&fABXdO9PC%|$;ru!hX4jsXtTnYr3p|i?;L8$c!|$ZM0j;G^hpU? z4%4?)0e24n_p`l+kwe@w|EOaQ+TY-PEL*N%TUohVvTktOPd=1m2|iQfO}RWXMUw=4 zjha5a$wDQC7zd*#32R3xKgBge^Axg~f2&)6OW7F7^FT=+$XK945Rzky!>NFEckWettytYxe3DVr&M(QZ_=5 zii!$c$6R@eX@{gg<4pYYi66Wr0Ga;>w|yQoy$jjSMh%r6-jihD4l8p`Cz4r~xciPK z81FWk%$I~mC_|Do0A50@6iKLlXB0PW>KB6w5A)u*5RmhfLCD~JkAU~1f|_4ulPMDu zaVp7KZ5a-JVR%i>zt494`|$WaC9c7Z=&+5pG1pBiWb8%|4CsLb(P7d9u4vzy867uI zoc`C@TP8=TBG&5)q@$Ro;uyuRN!WtJYg;-5ugqmNBTwFR}*|7UMg|0+-{30$cu={swt6`$z!`@y7SFO@MT00$}1!4U_cui_?&qVl3 zkO-;m>FG(%>qKSHN!HHXPxe?v-s@DkA;UR>QVKBPqSbY@i}-;y6-2RPFq$+VAc(@zd_x!MaPKIa_x3 zY{`|qnM6cB!H7(0K6QSu-UiPc(F?-4DV$sxqwtc|c9%?*E_vBA9LA#bxDkyiQ@VBj zNc>~j(xwWG4`?o$j4fLr{d$}$4XwxTx<7ho>norU5$kf94}S2=WRSSN5I_Ox@#D(W z5jb{kHgLKwr^sIpfNN$c0s%Y0pUm{?Kwz@E!sPv{LM<7Uozfw$U!Aha$^*GJWIfgO z_v0j^?}mlr5|T7;k5!mxswEoA6h8ZKeRIgJT`wKTiLtyV3?Dh4w?cHzPY^LQdc2E} z6=)P{U;o*EdifTjN{|RUywrao8I$& zXiF(b7?1a*V3OhH=>Z<^kWnzIi^RKgRw#bQ0XMt$~Jbtlcb7$|MNX!I0A zpLMD@omaSDryzX7QE1KN%^dtd8~hr0Ey$7Z67c1l*o5=RrLTP+l{{dz7^q!Wcn*M9Wgp-?*35BM$0y$h__hpgwxamxA62#J3^ zfDX-{KYy}G{)4$hwrgVD*&3!O_E%UDCRdABbGx0Vr>FTE-0tJ^s+?K}c2&F2O^!dX zk}jn+_{sURu6W7jhxKI>@HOYa7_hu$XG`iXaqs5Q7x=-UcM#f=?94)&nKIuU9{U1- zRSn$T-I<#H{ls)Ed~QMXLZ%UaXkRI!&pL5A;t3O;9Xydk>UK$w+#N^H>zZVbD!zOi zU3X@Oo%L&8rgr|w8+J?oqPhf)^OSL^SM!TAe>J}|vKaiV=w&dd5^(wT zrK)OA?)X11Ky}ea^pS(!=R@Fj=HtIg!7=1=>6_E%q z-J8xP?Cgadopk|}yi0-m$z1s#NEYB+mMlCVy)o9E9+mijs}TKqOTk`GR8-WDKr>uL z&Jh~Q$wi!5kv6e-$6jkC3pQW(&cC~zF!zLN88v;e!*u#aiT|otwtV%Ic!&1a#(u%t zGyNCZF-`10@IO6Hc+p5_+qbqlsvchJc^$vnOwqB}Efd|NaDx*6elq5rH*rIh9jR%} z?I4!|{utRr_kQ;y+N2iCA4p2JT7x)Z=j$Uh9oN@SG$2c!Z%BCgTx1`Z!&Iacd*PlY{&pvoJ!WXsQsd)-hi!SedI z0wKLs$d{M*B=F@niZx2NUuMdw`Q221EAv%mjtGyQIcKRep)ve~$>tBc^2N@N-6}fp zG34arKvrcqJZ3EJ4LdvbA}$-|f23&Vq(4p0>8z#0F6ZEQF4JJ*P0FJrl61>z9YySo zz@I!)!i&T8avj6F`GG~maoYqblWiYdzg!8|Ci*wry4{$>1b1nSqX!j*6O~9DRpQ$P z7h5V|TQk6o1^7>y`~C~?1L~*IQGk=hWMgLaA>Cg*qw8J}!;KhiBHn*PP@rU*c zk|3ViiQJzU)AqZh7YPL-NPYZ?clifju9$iC)6^R-tOSzD?AvQ^o&y{Ynbr}m{`m7X zWDB8{O%#(}sN4yi>iIT3?Ly*LL2hx0I+Ew{QHx@q$;P5z{O@8Zb4Ze5)_#?&BHEjd z4zb^|bDuM(e5%|iFx?hp+E1buHN;(i;`@Uf$8uqhJ<$j~^>dg2C-jfN-gy&AnPYNq z09plUeg;xcr_n=DFiaSAXPTV_z-D6r-2=;}y(D54kI_<8-}E=R08C^5=1u4QRjM4- zbk)}yrM;}QbMpot>qkD5(zC0WOTI`5D7yT<{do2@NMeXyOUjxxIiaNJ39f<|Q@_?R z006O$UE*fwr$$n?;Lupe63WF93Z=7N#SjUfkqze?N5|ODqlUD zot-6`i>~yuG)t%djR~02Qu4>qfPc9fmhaAKyEWvd3=hK^u2m(|#J!N(V9}$$xfk8& zkG?*TRY}{T@fG~H%(sG4(?}S(aoL|d7$x#tL>w1LjBirTB>MWyLmb{**M{@=Tp!c3 z#U=jGL?U?jAQH@n^B~^zQWChh6V%{fwlHOuz7f2xP6nQB%XUy>GtE%Bdmg%P6M&# z2A+s2`sTEQ7cE0L>!^%H_AhxFj_zE3F&)TmHcP&WtlE$)0q87XI6j5uRaT8G1>fW#e}D2+GESW+u!m}tq#9zg zX>1V`35Zb4&QE(yL`A83X!nyzNEtHFO#b{y5u2!zvWot0;y$Gbm&*)+QT=;m28VJ{ zA-b!tD6|DkA8g}qixkJ>PG%C9uDs&A>wycg4G0AR6bR=Bhf6Oeo%&fyMh~ z#JG{={)BIpvIXWFGmgU7go}1yi!y(P0~_*yy%keqrrMLAUV;y43kqSqcp9#V zo89s<%9P}U=q%+UitR_#)VeVD@ha4)qPRjCm7;~Y|8(??Mw!ZP)5wm@IPp%fwx;xs zl%9V8cWB2=dL=f$c5ghSJl(z@hmkqgXhC^IxS|)skj&VM;RgQ|S7v5Mb2gwVyM8wm zbhiS=owpjsN6KB;XSp=rCnn!?Qr>*J-8MOSCz}Kq#1)X2VTD}4tj}xzWgG(rVQKr$ zdoh8~HZ_-U(9D)K_UIS&Mum(AiXv{ibH^Q93?bKE%${+LrV}f3j(WR!aj-JV0Whvv zWs>@J_}G6cPEI~paiWkP!~cq1+a%`E3Rsk%vRcP@$cXM zh-^QHZDFY+Ymab}A(X z1_nYmqwwqeVXNrT$3y}KQbFgG2s`v147**#HYxDq!SLGwVlD8#gh*P{+B&$d{)st@ zRp`Q&^+0hq!tiK`ciDSnrz%|dEbg`N&Cj8^KTQTxNmcWw0_M!yL@I~Fd^8VUa!+~ZGcYwoiyTP0l3f8t^F;LyLPc45d@s%P?(BEIy{SMUMC9q>n} z45H5va1jJFFaEHgmiDuTS5|A9nRB5v9xH#4Um(_*qc%K`0-PE$A%OOv5Qgeh*ly*? zE|l_qq9pB6ki52Q8V(u#husN>EfUTFnZrw)Xq|Do_kzJ;2$v@p&gH=PIJwM_?ZxyU z$iDBz^n**J5Bw2y zOQp+})9lvDtBAh4C*;D)$o9Q8B=!!_9&K=!vl=!CgDwn9Y3pCty|Mq?qDZ#Q7|d*U zF9#Flr;It8d>0as4o27z%&e_@0X0t)QBr$c>JZ~iBF1&P8fJ+Ylvn8nW~Km+_t9DH zyoIkqv@HhA#RGVQyaWpt!bT#C;ifRCINK&B;)w`G%pdWpdrLFvO3!Ob?Rwd_D=e#a zy$l$-=YvS>paKt>x4}9o1KuqM7Z<@B*xpsaIAq7dQ5ViCzcNq%J{81a4urYfaeGee zo9=7Rk>)t5%-iYTy>p+xl`E;Exa zHf-z#xoufFkr%r(4lb!s1SxtwwFYsB;>#i%)O6IEy1H`H4xIax_z48BW6F~D`{q{y z_yS1Bh!4_lQBuOaE@fmpmV+-7c1K%^jWgwO7wB4%QxIS_02V8(C)nZciT%5*dTv4g zR`lg}C8`K+J5|fw>cX>6L(!-#Iq#3V?h<4%oStz0&$EeS4}r`Rsk?))b2XC4OLO2uNUB{rJJ{P^Hb z{;9wEm*OW4x3h|4N?x>@9kS}nS<{c$84^)`Y7h_ofQ3tycV2)IYRct*^tX&?(ls`x zg=7}PvQifb5rNtv2zbbHK2?%=bx=^dLl5$IJS8+N^Inc`X0POTYH?mo|93)#@V+qZ z^_Vkty({9pdxGhImZ=#!!{Y)QYVJr-6fekizQZ(w*!KWl{&+^wuJ;~ET?9dW)A^Pt zxanZI5(hM4IaB)bolJw1g$53 zE6LD?UL1aUl|+fdu-;>3!v6Y-a_*$#*ZU-<`^juBsJTQ7B78k&tL%(>BotgENSd+f z0gF`5BPrs4P0HLG|EZbCI$24D-%xbipMnV!G2y`rB4gmzSljLI$m;-hJQj)LM*dpMQB%NZ$0#zkfy-1UtL zlD!}@pc5P?0KAk#mVev;*9Cr|6^E`Fg_CrGs<9QBt4bT2s)DMI{-)_)DiZT*>2O0PS z^#6)SERksLQ=Ei_H-lBYf9}O?VOX}0nVY;`7mtis;xdUNJP?iNr0|GH^-h{G?AwUn zwoE*yjw;Fd{fpxu<~l8z5Vt96F2ekcvE57+K19C&6)@ahDAR_9^xnas1TPCe5XkV^ zO!1n9KG0LN$`Yu4AJkO8aOBM9L=JYM@_tff-4X}6nCIy zUPyoTk);;^Z>#BVY~a?*for08{<&Swf6k|GM%r4K3r!1#>U3Q=uNY{n5GD6v+$ul=Ro#LVw$riM9l=$dC1yXg8pYw z*GPak_7U|mDLaY$z7)v#4N#1;n;KE$G;^;y`>0f_JwMrXq&l8-|`PvP-1(x+t?LvU)2v-;zvECQ{$#V z^KZqyssDQnWNno9Ex$vUN(2X^7yJHmbw=101p##Z4RW!32?g`S@flj`cr5TC%7~#n zK`AXQT>#WNkolP;+S?WHy^Ha}%x%T3+fA1dn!;l zL2l~OBXRcC_Kgm5$2Ogv^Zrr*L7?E}KTAtifQ(zAG@bK#Iiv6cVPS}yo+NikE##N# zI#kaIEAw&pwBGQp!DJ*I%P6IQK@i+R%w;Vv(Kh>sE%`my?&6?R5}R0a6>?>~v&*NE z@M4z=3Z(R@G<1A)5?~SzkQ0n;K=M|=R}LYl-yvWXZ@alyKXPYve_5&7yjR(Q<@w>S zgV^RF1YJ5Y$Aq(pTEsaRhQ9O(Yxont;EodfN3y#*dU{BP*Z5cu!=Vu4F~LpQ>V3Jg zfr+-k!ND(wRmjho(f-SYx_0XFQ=BG^I_;4U3L-NBLK^X)0F9&w@CA~i`Euynzib8K z*;y-d!xc`#Bf8?mb*PJM3&ckd0!_~@kd!EU9Q{><0!fIGGllyyB7%zAnrK=NG#-;u9B+fT=ZXEE5JkVqxsC=??%EeGF1+Goo~(3R zFbtfWHp)6Gpoh~*(E31Sr30vNLP^+KL%fm?*J9(rQVIfi2}T>CWRg~+J{)dlH)ma* zg5v61W8t-CU3#mQlSvU7Su8JeE>6}JoILNKX2EWv0?D9ILKOk#Jp0o<3wX52N=mPK zcF$@#8_kAIudu~tVWdLdHvl{}+>1tO{C57Ue}D3BAV7`u;uQ zdG*f+kVW*UN7J|e^sXM;eWjq)kGy3dnU6VQyq;Z9N73bpxr%oD#W-4?Wti>H`A;9DtIAt#JLJ$jA2j)WStNtH(ZuciW+P9nlpRCdVs5 z{pn{2cQY|HZH1M#8#t=ny}bry6v!c0IC@aFG6h*dLm-!nWqQl!wqvZKqGIplw7k@TaVGioz^~JTW0rw< zK?>)sv+1|;Vmss$0n`C*HR1ZP2*(3z90k9bg+BG#5|XC0)Li%P64YBSRG-UVKI~98 zoTy)!H!}ub1Xx*}+n71-e`>81;ixfrLK~ocQEz5$JGYgsh{cH}tJ~!8fv$$u;&1iy zxz^AiZ2y#%)zv_7bS*ZWiuLNPVY&xZ1h9eJyyS&Hyx|h}IPeq^MJRS(tDq{4C z&!qNrV*H7g37hx}cr9^4Ec{jS^DxPlGauiA%~*+C=d6c-yg1sM-)o3ul77;FnV36A zclY5`lb0y{dO_9(9jGL}fSLhtH6+FY(p)rL`XRt{v>@UB$l><9#Nt7W9J*=_)yksK zab$^bGWkY$+>6@Wt^0#};V?gHRtPfq?4d+$srsekQFQ7JH)>axBkrjcpSl>@#qT^M zL*#)$LD-jPH=Ex92ZwkACY-Kq7Ibb+bH0C35m91bh*{CsvPF0I&-0}jUuWITc-J0X z479AF{OeQCzjeeR@kxOOG(|s~FVsNs*bTK`{%89B-TN%Ds zfbteViiFf;i~n5OLcNLhnCUw=#e+IPvmMZDnx2RLipXt!<|K>7!u6yk+HI?$frW@= z{e%(71;xd|rW(ULACIDhOpX+E7a^S`j!W+j3rnu+*KI?<@?nQWh;L|HK*B-hINVU6 zdL#gjl2YJETyceTr=<&IHGb685fr~xnnPv3qI>(2mTv6uYWG;>NK7h9OFJVyeNuxd zPM0J7+c#2@W_I1|i8E`iB5gh0aYHTVC(35|UeCUgFipzD=t}v^5QP-R_Rr4Ku?X}i zNPX<-^lCOd78E$1t396OJg!~)ymsm-cjM>5Ea%DVTiO(5@Bk*lVgh*`-*eMeXRg62 zm2hxy;Ao&`;dr>AML;Ls|L%I_A=QKRph1O#;^wGeiCXHWSIi9?V_`|>icRd}cB-5m z_EyEW((!(|`r?O*Q#YlCrPTViwb{5$GbfcaU+I$FM`T8G9-CZ@ic*;)$Z8`OPM)5N zf*|R0-si6&rC$obH|WK9zDwrvP%U8LZp@L$l_>qH=$1YThdlXSP@)irS@dhTy?~CM z9O(ID@`52$?7w1_5~<%Pd#r;J>iy%T@&RuJU|&oF<0iyC?hkvO6N;bs#Kn=MzTJ8_ zS!|$JHG6T7HBmezCB>kSnPThpKFdUPBX$oHtF0z``ZeKF;HNk8I`y3?*&vpKZ9Nda zyUjPyXCnd~U69bpcb%gjff$a!G7d`E1`>S%s=GJQhg|}9OdVb^_^!?48hfKqC$h~F z;$~D%7X3?+aJGI&LXn4IjPgVNLEZxAahQeoS)tR5{$o4p9rgy-o> z0wR)>9ojxQCN3fSZBqDEih!Pwf#GJx(MHLu(UQ@}cGhP*l9eWHSV&qh47D!eB!P?^ z9AQwPlM15arN*hWYsp!X3Qd!~#MV_sSrc0h+nmP({)3}m#c%C@nA86tm$|sze7y>{ zhbQP{keY39R>6oAplcxZYyBIlzTH-LWxQLXqr$it-aMCc)n_!Bp`#s}#OrTv1B09E z%qy6;uz3tnqHWrDqCu{l|FcvV$CsJM%s&t_#cAr`zcs0Uh;A0%@8CT9e090MW)951 z92_t%vN@RXrH8`j$(Hac78d03NK4K&w!#)}(($zA`!>E$(*f}b94e}+07AVPxnjXL zB5C~g_D4Waok}(Xc2v;qt03|>!=^8=4d0V`^uk)x+H||a_~pwk7%s}Hg~GQzp1g*} zC>D11Q0Vb0*00rYV_`76VaR?JT|)CdRwC~2f_9~>n9p0$?#J&Z8aq^u=k9Lb;pqU(4Qju!{?bb`8VPwj}EVClaJjE&QFU3e&Gb@3Gqru0SW|d@hsJG748@mIZTE3))UC21Prm_IB!z8U({$+y ze#HP+-b&xVUmfSTd%W6O^l(8Ow%#umbT)E$o>;?{i717j@AqDH^YPsOzFku0oM*RS zAR(ZA6bw@{h=IX?6$p|4By%GzxOJ-o27fQJ+@!x^^Hux(klq)lBk1>Ed4G#VA1_{s z30|<~aIV7Y!Vgb3q!2=Ke~w|5Hoy;+-E*S^m+LqE&YW+@_Jlk+mDZ$3Q(P98y3;&Q zxb!kH`bIqqt|rH={2}*!yWR%-avC3I;jK~ z-#F2?c8<~bTIQU;+)A~X8Zeen=9)%v1TR;H>u}@^{aO9;xsvezqR|x`vf5h@GtV|t z+1+K`o{wx?L*`K4a1}7uA#fb>IV{PvwkjFvsow#KFbLk8twu61A$^RAmp2LkJF>^S zuTOK_DEkL|=dr@lj1+k*Nz|5F=EK-mX4V$ZCHZnv<0NbrH#hqLBMJ!%GlR7VdFZQO zL+=5Su!tO;kdn-f%RGH{vvE<}Nz^h*h|J#o!n}UGSBc_i$96V=$Wm$o@^Yf^!Rc~Sx-~D3QJTiTK*R(g~ zQ_bx1+RfKF1Fu{$CKge@e4<|C?IqwfPV4g*`|0?4kP{M13Kx7Jl!TNr@SdTPwSthS z5eUM88XEe~UBx1&qut#r^kQNLO~Id2{N7J%uZr7NB!jx}&UtBE|I1%X2aEr9@8XxW z##9A2fT@Xq!0O`cLd`3HoO|j2;S-gV*In?K)=u8yfrFs!(?8ph zh0~uLW`bu)3`BJ3P5YEesOoF`l2$7RV#eGvgn6;np7d>4M5NB!8yvqV%k?7j$jCG- z-vw&%=jG)A{}mM-ZANADDx7**#6Omb|0_9ZYoBp&y6o?JhYyaSOt>LvaSdt~AyC(k z7QxW0Y~TP8{WCbDkrBmCpElw#6{7X3>~DhG0P)xYxr4UA`gwRtv5}YC@%G=ajJ((P zC~w{KB~w3@K|3jtcCC%diwyMTl%I~|*6NFq_7{ zbV-d=@ioutL`hU=Ty@RCDZhnz^B&RtY?5k381LgVF*ym4e?#V5Tc*mE$?uuGYctN| z>wTI@RA-Gk=$+`8*eDR3Lf&Gid@$LSiI!VD_NQEiian(!x0Yz;Ty zoV7Qu+=-gr-r`qEAft3vYTz4yDq?vPmzI~;Z;J7KjFj&~P$ zKI;WfQ$D^GcsuEGuk3%d02c~uy_}J8O_T!6@hNicneX*-<(vhK`>=`8?Pfd^0ef1* zKZUUwWVcu)@8VtbY8u^vCAH=*%zk`8vG+J9>b3wHEdHe>3n;zAe62Mszl|Gb7QMI` z_)jJ5S4j{9cBEqS+`U!&2ePlKjY-wXEbR&DWL63abl^XuhOnsUm>6KHKJz}a0)FP* zElFw+lYN65D z&aLm~4Mc~^#N)RegooPI*?$xdhL2t3fz zs;Y4XeGCgLD>FO0UWl*DH`+#h7_cBa_?pg8c6Qv*1X>;1xqb4-*b`gH95DDA z&lWQBoICzomzna#kQK2SNps+|+{mp7Tkhq&RNN~~#!uGL@oxFqUs%CWf+T}L*2-Jt zZ?H|n!|8{3^&cQMb(t0Q{wIWhpYZOWB65HjU&+Dm$jOnd3)4^`fj%)Yac*rb6pa6n zh6#yhi+}!vf33S=CvlZn+w`t_)CH-e!PaClHe<~%iVEXcr;Q8Rb;lg%JgDC^u zN_-8i)u|U=l#fjk++(AdN>{VP7Q4rklLZWq*B<}Ee1;vWHAQLl&6#n>v?u?BR{w&* zxt5~R%=nc+!UWd&4bkUO#@j`TQYTBKz`h^?1MrUUczh~%OB^POoNG{evZ9gqyzrVW zickichBEheM2*hA6lU*37rrZ8YP%6G-Dg(dtiUsMMdfH9ahRZnc2K&@ECJ(Cy)@b; zZt6=MKYaS)ML!f2$gxGA-40QEhM<#!Q5f(w&tz)kQ3+avJYw5~yaTV}`QQ-^wr#IJ z%pO9WxuJ^~_r%{C%$-Qg=l^q|6Aw;|&Ai-fI$5Sc2C_q)dk}Eb#QQ)S3D}yh*?T~K z1?X0IKdl`dUjhFDli2p0xJY#gm_Z9D7}lT%+7T~a#S*z7zVg0^Ypmpx;Ab3knOn^sL`8>@ zI;%gvKFGn2fKmf48=2+;c;@F3XBu4CG_PRnyxoPLo~2IMwOjPI+m^vHbTezxlo5WlH=c1MVJ{<7wlFSt zow_mtfXokYLlAY_3oiBYpBOJjG_OYXh||4A(;$t+==5J&vP`k=$ZQbP zKIR|<-~kXMg!Bg1#0&^G1dIkMsSFMV+R8sSRx& ztTTMCYthVuAUA;K7h&hN>h}m>R6C>=DX~fJOb~k-WEizes6ipyiR=)9VWga^jF=sjA(StibGI#HZ z=U9yY`Ki7d`5V9A9-OwI3C_^STZQid0(!pn_9~BGATj}%G5Rh%JW0rg1X5%i1KFi1 z15;9NLYo2eS(Cu0FXi?0&&NSOZPaKw7GNQY&FS}6O|U~^)rj6Z@u0eAzXcOP5{#y* zBw|SiR&b@Dq!A2Y{!l@cJ!KueILmK#P9u55HG(fAGvQH8i~ z!_d`wG29fsS$nmD?fQqv-LKidgm792tV2g>kF9;H8+jxq`|+qCyTUuoz>0d)+1~uj z`L(TMkC-erE)n^k_u&CdX($Gbe$p&y&2K-(I<<}~++GpOCUlJl2s@+PE~I#QOk1Ul zlK%orb`2MoQC$23^g$%l)cL10KtZu0EfAoqeqZhxgGet$oH9NN7|X5M@pIK#=nMz< z1e)-JdZq&ZI2DL+l|LsBrzkt@O3SFO%3loq=xDNh!_W#hJ%lhE1Qn+5J^L^%m`y#JP{tZUj_ojkY3;t^@IaVbPh7-7y z*D7RMABGrfEZvHlXOetkWogIz82gzg9*wR7iTU=?Vy8mwYey@Iu+39hx>M5;-{cLP zBb#*IW_gYXTD*tK5>uh`>}kA=-(mw|^%75GFKS=kyT6zqoiPUiv55T|I$>tGc_Wx_v|YK5%qHws>Hp97aEF- zL*GuZ?I@sAjKv7RCbSAsadEPGdQ`Bdwa(0(XGpC^2rKA9?8;nkNi!*JD^c{yUgl6W z*#miU)IXzYBF>T51HzGIc2kuqpQf-DtV&b@i%H5W?x6cKxOHV6m9&oppfP^hp~z03kI%tsP!wPDygYg09CgnWg?(Bt^rLiHUX~xE+MlZ&Q4fEIy z#s(o>%)C+uJ~?gz})|`x+<%VCY zbtE+X2-ur$sDIOYoQy%d78)p$@iz$FvQU6cvHrx`bYc z%O#A^E06&H%*f0vQzF&?27eEIbw@`>03Y82^_vJS5KT6v(fS*M#rj{-wbm+vH(D66 zBi~r3%%vaWC}Rv2>feR~z8ZF^7-5S8_CnhSQ&p|eL>xhpyjx@^=Xs@O_6ugO746OO zzPSD{;kFG8v(x0_@1ki+5HcHF3R8HhEw+@6N4IkUeHm+*-N?o0b8TdYHM ze`W%oRv$K~oTHo>k&XybOoVI}+Si8b+DL2V@ZTD|?d4139k3GeN`*b^8A0OI&f|wq zwBLNe{n3};HQwEtVEt&$l$|WoR$N4>SN64h$uDv3YR5()y2l3m&nJbXPB(A+ocb9fsPV>=)+0vVL@k^LnGS&pkVX36pHTy|nWz`8pn&P&W09tYF3FU}%{1%oxQnMk zt&eha=8@7+{in8Cn@Wwde4?(r_bFH9;il?i_0uunYdm=Xso}K9}vzdon^dWLq=b7OxC?y z=Ih&N^bAZv*Z;m}(>zC77U&T{hai3x8#^XGp0%t;LOiVStMf+ddtHL46b237uOsf4 znV3OeAg4?TDknOx?boI>t8~}V-FLTW9=?9|jLKVirQ)xfE9s?*Qw?ChWQ zUbr$bF(DEPq;7Nm zf?5>H@PlfaS3~n7caRgzoU&zFt6_l%7Saz<(BR@SCck6cjOyr@D}%DNEeGp?2_EK#hhBDv!>TKjRsEBm0frY6 zPWCMw9l_A5Y?Ob4esk7qFFcj-%)ijE>ODl+QvyIL1wok6Rp%Ga1I*->ilU{q@(-xLqMxA74RjpUQcmC(92B z&%b;xz2Cff(+RrHaw9M#K?i~c*Yv=sSvqteEPc#|`KhTki4$6v_Wf3!onQCl>uo*h zLv=ZqVhy%%i4==RE9B*K&8&xW!&3!@0P~S|T)TR6FRhYi*!-G}Rr8-#t^PUUCUcz@TF-NV?$sv$V zbMx>3(()?GECWa~Sc$hG`fG@A(8fPWsc(NEFSHYVshc6H!rVx;n&`^N9_7s3$OqKF zsc&Rjw%&{3BG-Mql9F3MnX?8l$M9+w!%n#dHic&@HB7xx&&dmN5S%qJyc|(evditdc}$Sva@1(b8S`P6Mh%OyrUr| z5cpBS;~h&|g08MEKzb3)dcj!H&y3Cd6~<%zC%;sLB%8iy=V>kc{*9@&gg-%__;ZP{ zAmuTEZp7+~D%YU&Huj4x)xY}gnmwrRGUNR3&r5`dn1ZH|F9|?)&<=wj@0uTkQJ2E* zSXL#%V?1%yk0>TKk1TZ)ExLf@hlARLczR`on@WS__AnAU53y^h-iP}BbcVTBgK!Q% zf}A_}U&$*fX6nxRcu}wEx^)P78{MI!+c~;%^QMuT$%FZu?DY!LpQkCvsXku$lD17a zU*VY^#hm&zgmwOHuEUC1RIpZ_me>B^!?V+p?P-wYv+(jFIq>|D%>aNwM_Gli9X@^N zJeT38vYQWbMP><_r}?TpfKs}+qakd)B1rScXV=M z+&|V{W_~$1yLS3Ml66U`96cN5Nl#x^R^CW`=@r4M+XnY?{I_mv|0N_;l42L<TBR_f3bj@M; z<=kwEgf5q+BE03yKUQ^>ob`QcHapa>ex!eb8y(5pzGFMmncfkfcY>75AnXQXCoATE1iIm@k1JCmEP z>Q#)IHWEL5=uJFB8S*d1qv`m|EttQLyEjBenC;^=bl(T_k*K?da_lovcmYy-wo(E2`-BIUS#4R3^)%|F$ ztt-DFvPKy0@g|R@rl!Wi($X}=8~e`tfC=Bg5~U`~f$V!bJ3DZl4lqa%)Du6!w3eD` zIZ|Bfiq*KqT*lgw>QTr!V0kZc{gHj@zO#CFN<2X(qX>(f#L10s1>zzi2|ycfNcHTp z2u7gtw47#2@$gA@b6$|iPdqGMS;i*FzH{px<6<#U05{hS1&34G))d(=@wW>)RLtkW zOmm;FhG~$LI+NyqU)yQ!SlT7vuL!d87qAy5*$``d@(2GxWn^t3TcyIv+<-1zD-d>; zAT31#C16iWm?6-OescMA!Fw1zLVNo&2Yfj)A1VvFcs%NchZ+4^Q*O&6Q_Y5A96lS> z9X>dWk0KVb9wdJmik3MhPsJhYT3f@2y%#cS&FDjs${1dYSMqYhVdmO|w8^(H}*6uQ+e5jCtGa4LKBEeB`CQQDN_!?^5lI zllczbOw-EqQIjwHLIp_e$X>ag=Jg=FmftG{B28tLgJ{(6cX z%(?$BK2LOnvIXYd-?mb^!gZQ#{*h9~OjEdef^qt4*3r7Jstx0ridLIv*)xoGUj^z% z9eFj+)|*#vD1FPpWTmKZ^R{@MGS$d)r897LK5#8_d~r;X`?aQw&f-oEQG@E$!nYq* zuehvn+3Np&s-&lg`;JJmpv)~`wNp7L#r=L(%c;{=R@moV1(!I*Ha~O>DoGEQ-)Yko zIc^Q^nX7*$-J_<0lH{9URQInH&V%=Gv3D{3P@z0FE_COZlD<9j_Cbj;`~r8(3d-uf zpdYSE-^o3h9bQ_(CNy{c{5y2%f_tj?!(LyhUHeuyql2s1!LpUWopsS@<3y!_k1d%* z{h2!RFRLrbaM*0gKVB&Ken6rBN|~=XkdJxcAU5ZGr?sX`Tr44x41Z;)oN^Rf@*h@NwQ|1sHClSyNkvmYMK9)@1pNtuHgxyEnw zY;KFEPh(P2icUW!CmU2^*s%3~9S-|tzi~ajVs9FUFU~NVM^KQ&4{($yM3lCnC#Xur z+b?}4TkT4H$=je`>PS~}KNe?_^s%lk9miExz>x zs0n~N^c%fI!4R|vHh$3P#!mB6$n=d=;xtR$Jv52tZcr;26&sxfr5GS8{(*s*pop`C zA@5{bnv)4P}`V7 zYrQYCii<3h(&=}4qCDSIG#p&q=HX#dU*Aion-7<9T5~Wzp6F+{E}Pof^hXEiY=%id z4$YXvEE)m6@N(^B)Yq`w*2yYXBlBjkUx&g#&8{vSD4W6Fk7f-{3i4CT#kGala)E1mAtmIj*b4Yc`_`JcqK%3Ldi+PTwO0e$nqbUvTIKI5?m zrPTQ84=}8-fY*cM<~=ShB}D~=K^}nH**_dC&RCoJp6DAXbZe70^uJdyOOw=8dbJr0 z@mMU#JW34>jp*<1Irb8rHwur%&ze=DM{H--0oPab6FLm1SD3tWUvF_)e?T#9EGoOA zL}4hWC^|NV#YTvF=E%(4oQ0G$#_aN*zrVlhX}%U`!*le5*l3|Xo$m8ixm{N^#gh76 z#ZX=b9v&6kYu6$XADKc9=kjII-Gv_tLsb_GK#fIZzgrseZo<+a<$lhUjV%Zg9?0+d zH{jj<*flKDoBd!|NquCOEG96iYoV){{f711dgVOs7Rz9KDt^B&U-%(ukN1N@SM0mm z@b42S>nfIWY*#OIM9&Q61joip2=mBSi|to^v$rw7X;AHq-dq*dHbNb!O1b?9>()(& zm-f;g9%3M>LTp8#fp-KPAMr~7+k1F;SgT1xLt}1d2d)8EB%}ejR~bP)>X`r40$68m zYZ^1z{WR2Ttp6;N@Wj%x4XiMVA{Ox<@GrT^g_%Xy=H~EAo}=NNKJ?YiZO)5CTUcGy z6JsmQN9A2Dk&aUJvG*QCZ|#+TX`Up^IgWr{NT);Aw{+;r- znj5XOq`a@)(X#;%0!v6tWaKxKr4+$2G>TpjrO&Mm8aRym&mNb%$5u|LamsaP z1R&!G?uv>c_OTSK_&Z!ma=9|r-n^NIt2#-^$&d&Y5*n(IA>_C&5=eP3_=xv=C&u;} zHY2{SDYJbyfV#_7PrANtyL%rOix#?L9(rA2(+%->UpE-}!RT0S>nD0_JBsCQsf!2r z4-sq<1~~%0g+68NO7L-teo4WHj&;(;i0&Wn8<9I*-?Ng{f5)tXB+wG}nc9AEa9|_Y zCPawjEzr#E&{kLZCpOLZm!$XCW54V??cjKdR^zUzJW^L(-H9%fYbUfxfGtJJo1A|= z#bFLqdmz&KHd)KwM=YZ{l@q8Z=F441@Pd|-Rek(2DBxP>qrhw~v(V{-Z|G#1tCcz! zUtUCB=4(4tyXKArdLg_%@UckFMc`~-@H5}gC_g1%X{+dou2z!CCN2+6*)IGpEm7@T z(qQG+78a(*T-#?j8=<@~;`n&YkdnQr?}rlc9gbPLFL(UF=-Q23;K*M8aC$Ann~=1` zd(N+3@y$5)7RtVmo63q}maoHj#U$G|Jj2cqk?LhszihFjkUmZFz?zWcA1iI5{@rgQ zyF?{AuKVkMtpa?2Ay6o@{bSC-2|tjr;2`W&GyfF-o#kio=eyeXYy3 zDs+RO@6AoR5PPTLgtp473=NNpuzrildU;8p!80DljGUOz)6mo`C>qLD7JiUHs#yl|L*jpDx1CCNs0l zk3+^+%jo1)9^{ezyrqiSaE_WUhXr!L!i5JpV(A*=MoH^59n-o9;_ znUTErtY_l-`fUhtPv7V{eU*|h&y$II8U&B?i z{We4b>L<_?$^uLf8kdWWPu&W@Fxc9P=i0lqt~#N)Q({Pg-4xQycCBESjAnhl^MRm zc~KZcKWKHX&0d>YbCtT{>}dBY!1IdqaL-VdIbAk3(kf0>qQriKhf8~qJ1O}cD#?V& z@!lh5KR;duCJv6!>1ngVWc;64fnyY6pL&C%m_s2Ys^w`!m)2b;w7jdJ7(^_g!^4^{ zyulzupa0h~)ed4W15g?4DLG%`vQ`5>Ye({W(2k9bf&KvC5ADCog%MK!Miwi5kL92PC-O2(@oekp zzy_}+AgK?*sDVsX26j$+rd}`upEr<#$(-zwih8v~ONQi>bc#PJBOOdmV6IPaljq># z!h@)oVk1Ju#8|(FNo8?phK7bI4}XBDpyz*o*YBkubo`nx8lav?JxowOLFhl&xj}a+ zi3}S@h#nx61z;*MG7|8059RV_#yb&q(N90A0H3({B8%G@2dAxP-;Vw zO9aN%D;OA{zc(lyx3slY1oforTd0F!`uM`v7}5ipiq?_dcM-Y1_ov2q^y}ROKAix@)I)dK;{_Q5HEq=Kz;tvfE?};QY zX-6cO6I@M)VWMb(eznhMtOL6l=k?KAAIqq z+YBYIGO>|YRK^ZqBmzS46JVceNp2MEQ0H9dYMfcHhwaXfb=i#O)sJ0Q92RxHIV62XB zC~AYDr{-utsN?(CC51hJweFXblT(~5E-I@3!Vo4u-vu8a)HvFMAzV5CEAzivBb z&?6xDJt${kCIaM4U2i;D{-B{$i+FS4+n8TmY=NmS_W^%_FeWs_a01G{y*`my2&7^% z_WV=vP|Qt=1W%m56jd~~y(dDqryL_EaWw7h_qoSS@3dn11)O!6!18%$Z{h~Nf#!@D zzGqlFH-xN-Kpn&9MWjHYbYtg`!f9JTK!E(-CaXFB5}F1M$R?5g1s7jiPhTG}u#lP> zck=ShofXJsho=s_tm?~`mA@)M*Rk$RKuEaq^J&`XMjkT0zPwy0h1OTW{omRr*R7($ z!Y>sSqoY;7rsL#LuzBsn$nIwOs3>UA%lBUw67BHn-zw@L4R z!U}`1jDz}Gkl=)chlf8h?1m7->T0izMWE7)jd|L!7a3OE9W-Vf)(UVPwn>)N@?B{A zRG`A7my${aZ2?U1mDA85fg@?ayJcd6DiDf0ft_Qrt_%<?{L5T=)0#glvc@DPfz+x6Scco5^5ICIepfB!xL zRt(BPR(g6r5Q!n|X6#z>+qP+)YP2h9jijg#@qO+`Gp}G89UU+VoY`X#sqz>ZNCqFt zEhFy>`u0gQ4XM3SB!U+51E9+7afQS3!JXKAW@d$E7_9_~IwzP23BUfi${Sb`WG)4K ziXcQ%lPw|x(9{u(3=)!(zq`(pf1KZ~_BE`pawYC=2$D;|c*PqT$K@zIliBMl0zD@% zRq&?N*+2YM$Yz}$U%DmFlA*@#B8%jh@|GLXsDZdduc#o?(w1uM;CpSVTN*W<4Ni7$ zE=7JD2PNjlv+iRF1AfiIa*k<1?O<5MQNW;6`hgSN0W9VX&oQ4rueewf6#OlhfkyM` z%KatQu2S`&3ND>zbZ*_eD^QWTkYBADu8a;nJb4@YpwRI2M9ByJPZbVZZ4DCl)1)F9U)a zflQErll1w4h7ex^EA(xleqtx|FNs ztlTaB4%_1~$TDe0ooLI!6`)0BuxdI-KJX?7#|s9M6c5@K7qc+>{2H(#7JRW3jF5D{ zFM~owrTV=Me^XeO&{g#3b!m=wS8zJBf`wboZw`Wq+NCMX9>c5{BI978a5ks^O`Vzw@V3k4%m+gz7`sQ8KN% zO==8|wWe#_lP%o%ik=x-s4i0YLY4dO6VM9^s`4*W=scO{@}SV?uojF_|2(87Z>u&F zoEg>=$NEH@hI?blGqXn`sxxL)FalH7BZyKDR}3pYF!S+wx000=>&urf18E5=z^{P` zbLos4^mIaATM*cf0_*6QRsmF&rjf^d`*sYxFvp|6Mu=_}LdFr77W^aPh=YkA zyS=yjV+$m~xnN;o0r1xj3d&t~+=paCWtU13DBS8EAuH$JnX!LLc zQ7=*;NDNw4q!HdAQfv>=23K(n^VDmcwW!rD8dfI;r zfHb6RKtlphAm$V)TaalcZuSAv!b%kV*9#tt6hc!5g-jJE7vqhNlD}|0^tv$7a1xl zf#LDM#*P+*=)g8KIk{e_d*6b9oYo_m-}DMx{2USv2fSYG0hHhf{*8uI*U-8kDd~uu zCB(QB;v-Jrz=U}#Y@(t`AnX1D$zjsd7LY}NLqNd0TT3lse_a|@PzIVNMPX6V&fXpq zWV(ZJ87fEMy7Gu*CqR0T03E!Um6e>DTIBZ#KFw0Vjg|+OEWS}{Yt0=u88!=!O7}w4 zI>Ks#Tc)h641m4BGd@^7ip-y)puc~b=G_j$wHntA3eGstMQ@_o(lO5mGrp7@BfgMq zg&5>5!m?fl8$%mpMgUyC;awt_LJ7UL&2+T@%t2tdefw*(#W@_-gwmH6=TJm^j&$zS zqD3AkX$wTKBOU|f07r6pP&-9jkPy&ad8Q4d}eEF(5bKs za_)LarbP}-B4=)>HAae!{x#Q%%zDNA*JP&y-BusCJPszAI-pm~(I`2J`uMRIl67&4uL~WL>Pxf_y6v zv(%_usPgi+4-Qy_gknJ&vADe44&y=Y`d-xA6U>{sxw$#Op$-x=f!nvUpv6R(7YOf! zpQp34vqKcmAcN%9oPr8441NF(N{9(9R8#y5=sc2?z6$0$W9lvBMZ*)l3+9@nABF~C zHyX4Sg1#s^F)^f|pn!Lys2s_Igw={`ouh2YKxo<}A@GhyI7PlLSgZ%1L{OR)Mq$ zH?ZOz&-oL=1mFxX#X{u|XI7}wxL+(8Oz;H9Eab>Cz+MgUkcf~1j>^z5v=XDbcCeZk zpKdNK1;oT?%HGk>y%HrkXo<^!oFZYc-GCli#mlRn*8z69n3x!UxH#AXpypY#RYZT(fAWQ{w9iXkx%U|xMO5{vI z+Gpw)jVG)i^MOfINC++*61X|{yE{9zUX*9X8Gw)A0d!t#Yime(21YNR<9TdRHwh~( z8$xDA#w+1+Eucb!hcyqy{X1IG=>2^cIBGQGRAQo{IIyArXgv@T6i(p8N75@l!3S2` z53L_kBC{yP!)^c%Avam`&ybs@hK7ZLziqR5WICH>Xs0iq>a9^*5=k+!WK28?iL#@p z6iBK@zx+KiG7@G#Ng5axwe1I+1zfh4<1-6e+{qfHKeG|Ni>iTFBLTw+0UO17#wpTr zDexifHK=NWBgcDtOTFr}6S3 z8p}KBC|n#;5)x?Qy;h~*>cw7HLI;9Oii5%BJ+Ob=a&O_x$6i=o)+xfXx21-S3QFB> ziY!4EIgr(?t?8Q*yjP`GwPVNt%OG%^ER!O4?!<#}A2BijEv2+y{>;iMC@D$b{R77y z5yS%Q92~@H=36Sh16lmEp?CA=p++lUTYzE7gq|3ozXAfT&Q!i>mlV`)@mDN_l_H3l zH-uIOBxhz;7UY4pkB(};`0#O%0cbeQhP+wdwN$Rp*O~ugL`V@0p=%4fExtr9Y1~)=YLRVjtI$-3lqt^Niz?J2yl#JA&c?R%F3*kA3q&45*6(%c^f- z!?5nO5MQatk^{%z3bi`?X9qgtsloBL!5xdx5Fr>bz(}CS zNP-w9^JlyJuyYI-8;OG&47`pd>&sLh!A%9$fY%WJ0N>3#bpF~i*|_r%zXk^+HUxiz z(;u3q;&oQ-Yrv;w!qy2-M6Jr+2*hq+2zJsIDbN6%SD5wxK9*{?9Y!d~Ey0+1w&iTgiI}B&N2`0QJ$nYL1?_}ukkOpvJaj~G*28&HnG6nvGg2zB> zR3%UC;%rY9G5Y{Uh=@u=MMV+64aA}3+Z+65=o(>fy!iL5Yk2r8ytWKDsx->Jel1wH zqKbugr)1v#ZqQq&U^E(HX^~Bt(@wh$Lmu{t{B|zXCkK(=hxvu7>gh}sf|2FhjYR|@j5V4^&yt@|2BPepgFDWEI=X;czKVr41TPp-dEwfpm~#B7ka`a_6gGS$Q1NC}UBG?{AqGuh z1}x_6;9BT`0}8_Ow#{w0b`Veq69I~WoXqrwjTYzn^=w!l@Knntse8yC+7ur+w!z>% zcsF05l7bb0Ca{FmRPaACY%7Z4;EHAz07L;6TPqwjAo?nVbt48(sU6v&U_U|P{s6(1 zmzN)S?n#^W7^p?i#4-LKwTK4A1(2G$jvL(_0XU>EXFUUa_J|J&i1Db@)E{3=Tk?@b z!ow2|C)CUeVq&A92mVQP zw@<#$@z>WG;yJWu$`v2PJ16}23l@GR{ofCCk{$|*ONhHg{S05c>(}%!XeiM#W@(Q8 zCvSQ7Qg*eP#x9%f1(_@XW7q4?M)FRM0t8BV95r`OzNYf9#ADP%`M-SfJf1rApsr|k z*lyiDb#`m#RB~(l&xut3N?rfa{@=Q%8%i?FI2ZvTAf_06USfLq>;a^bCZtXWVXKZ5X)Sypf=i>|RSiJA; z-B4J=%Em?~2-e~$YQBG-H9iIPpdT|M~^rj}dsi~=J!7aEha@kT?*K82s z1XMcnE@GtSpFVvW*f@Yiqo`l?^{YR4_XZPN=A{h{X+Az;Ndz4{?)te|maa-k+?@3Nd9ej8WO1`uh5r&r%*8 z{nnGXMHwF0V%kTyqjX6KZ=?P6RNTYUbMWWS(6%<&>-hLAe~5fOjc=%HYX^S#K-1RMs8N1PW5k6A!m{H?W67<9SHs;XI;nE(`H*gQ*y31CO3IZ13n893IY6dn&WOKoGD>qokzN+0zpv{E(dt o<>@J2TUSSpEKXQ@u%?^P1WhqJxV0atp}}7YvX5knQBU6d5BeXj8vp7Q_dYlDg^~;&4jB#-5)z*5bIF%TNXVZMUsxFM9ls{t zUic51lZ31q7X0zTdKChH$F_g2?SzDcZ;bdt&K1jf4c`=SmeO)owKI2iGj=pXvN3kH zx3+V(er@u=)y&c9wVmw)E_N>VC#(-Fot^CkIXM20A7Hn0wBUF?z?g}I^Z-d#@~PU} zq^((ZFNN`o=KTQ$UhP+O`Djw|tQEYW*@O~0Dr#HuOvg5C`Y*OMHOt$TU(4(2k7|5B z9m*go9VN8N`$=Z?j@I(k9c^>2lao#}XEOO$kK(V-3Rgv3^a`BJIPrvK zFk;aJ65v0#+Cd5=kkF!+eIS8F6DCO*LLd?H@H5)OK!S|twEpljjD-Jx`=__L<^w4a z(wQ`jjJeH~$fy`;zb$tzJQjmUkSu3wkM%csEC&}FOTErk5wE>UDsfo}Nx2=#0h3#}{>e=gu9tR&!Q? zc9}W8GnE8U8rJ@&BmpOBC0bH;DWXtA5iVJ%`3k{rtloz+>l z`6sdK&VuMK47`s=B|2Fojb%w<-&(@b2PP(xfByU#0${mFpC4cTcw_XI`oQGmeK)t0 zhrUYE(il5CI}=k=WIfi_)_bt~b8~Zu>vncTkh?EO@Yy>#JrWWkPgZj4G-WqzOj=kl zO5k~I!kTZ`Bnpefs$Y8)dGX4^A}T6Mb>$E?oz_1j*!*{fl=JQ!rLL~-`M+&>FE8PX zf7>i$j}H$IYdntM_-krtXkbg}d%*=RkH-xazH<6Q(2&>txjx_IfE!yBkWfE_y#f|9bd zsw&6l>iqKZa3I^cG6Qjjsls5V?JrLq&X3knbNQO{Vav8Op6lsR!2huAdBAayf4D{X z*tiwVW-vd#9+PE=0kzb_~#D70#wnN+_i7{h@H z3=WP;PR45<&DZ?B?tFTBN_5IfO-)TC^>}Xhw4r@{)>Gx7u;WPfSLZHBmzS4X4IWQ) z3eT_lJ3E8@Q85n=2gJDF?irarEG;Wz+0%|;R!89+EB*0csPak@fhgnk4-ypd2Oa7;TV2!wq{^pXl-kgXC8U^ z*z45(HkI(NM(>Mo*>uPaBgKZP;|87)$wF=@q`SdKJG0YTyJHtm129Uh#@R9OsjLg) z5)*Y7%4}zsPuCh^e9OwpOjmw=4kvpO7J!LQNI{{;#lXx=vEE9UZF~5qkCu+E6dq(_ zB+t|f5yZ_~e8cjpuCBaJYyH{qMK9aZ-yazgg7t4_78V7wd3>A%36?d=bYfy+;m@BA z*iWR~m)SVHyu5A{9!b&Bfzp{ZrYB=!vv1O~zkMUVT9FK5U?Wi3K%5!~Jwr$w{x&Qc z1xBmgFXO@i!Gmo8!AF7Z9AqKRY^5HoOy_1>fF>`=bmN>hdi+Glpf5 zrn)w%`?kD8x1O!NSE$jWYu8{VY~JK^HPPT%RjS(!t5j;*$pt4*LPCO+-~NGMa-@LM zAN%zoI?=P0yUUIL{{2%(h->dJNfC1xSSuJv5QVy@ni8$f zat{b+s(n|J?dtBXwMuRYz+{0S>4qb%*nR7eR?xmPE+%Hw+jMij=|=zLX3b*GBcYBn z6$(l|iWx@0Q|)T|^q~x?TkY-bQjmT$-vtE3KxLSDTqN~@m3~uj_{zJl)zSC$;nRYJLo5%ag1gtq;??j1}tUKvH2bFfa&@WE2GO1oOd(IA9i{P+9_jFj5b(C9!BEKR-vgBY~wt`{loX zk}V~C4)@=wR{Qho^CRSA?5WR>WR?~e{iCAps;H=BWo3P(cmy%_>(_HgYkNmWuV$(p zIvyVZ2I?*{5qVy1H!m8+M7FfF^mi~lU|)9Pcc#oCl*v--NiID-J<=y{h@b%TDN)6x zrXn&l6pyW`iVs;?v?-oD0#H%D3cEX|FLRROA{M_ph9&d2Wtfv3JRm(|m;}T*RATzW z+!!Xhvlm_Y#f{%bzN^bWCdHN0(Md2dHO*wzt?aG7nkY5JN&ETpC&UvYgr9o3PT`lN zB*r6&q~v7zjp#svR%sI9pOl|s; z1ca}ShC80%$qk?GFUu+`^EDFQy(@pk4cq;d`7`mav%|H}$Vl_{uzMX`5KjjO2hZi@ zxnBptMlNh`+Z2?!?HWXx&XQ%jSfHSy%0J|R=*rHTU?T`< zX$CNJpU0A5Y^(}@ZE2}>F#XwmZgX6K5d17xIe)8$WWsI7a)$L#|H#R>!H z>c0_p5+>E>)e}Zqb89(Ew%>oS@{Qz;W?@Drui;0w1xYdky?0lg#!a;iu`Qv=o;QD@ znw%-*c#$?}3jo|bU}g?uNcH-mFo382`xmDH&CiDWxSyN}l!}7Od~>@V&6f+wmHv3t z*Z=WRp2imcJ|9O!YM9kAhLL9c&BZJFs2uNi8mJ#n-Cx$#a*PV=@0V-tm5%?;)K{e# zT3#HY8MGk(ShFfzU%er?pNC;O2~iGbx$T*di_?$5%>=~4JPkt$^;|4&w_kFrzAm0D zO|I|ye!ySH{`$;)T$@;inpQ~DVy514Rj$@$6Qg;3IH$(zj0=y9r`pX;Z4QsW41MVu zQ^p6Gj=Fs+#b#8d%%}$&0jHJ4uGEZm9>m(~M?oJ|tr&-g`KQgl#(wp5+fkPxcl7p# zv)@MH>FX=1^W$B+A69({PeMaN9taC3m6UMK%+7wG>a1|u>v_)Kgi7(fxukDFW42mb zg$RPa`#4$#aam7j);L$%48>YvyFNLnu$5H?pASg1Q6=>ru1Fh*LRG^^v&j`18yhQs zJ^UUj;oUoTo^DT7$QQXRXrP{R1W`YHAVBQ1aqHQ5fW8?3haM=Bug41Rmzno5#}C|< zddNmV!^|b+e~L#Sg3L~>-lKP!KAJz6OM)4hWCG{7K&$i}JZ#itg{rFRhw*O4@S|IM z`a;zyC?8$k&3%|CH@mgCxCjT)VPk{|%7sSlLMQzW70zdh(; z=<4e;gXhSm4ya~%?T@AMJBzOM5B|d5z=kJ_5SGWCsc_?-ooC_HVo>(~sH&?SgdM}(&Fx}UE_ot;z_g6A4*Dnjw*6h z_nzBwJ+K@hH<-hx6hrdlgUke_7$0Dy$=z{t>GA!fMbi7Uj!)D%?&@^L zLu&;a24&!fyJ>zi;%e@3#Q~^?Mw>*{`&Bv`4NnBpceyOKk!NOR{*D(@BLM(-J^XFI z^%lp%>Z)1e*WI5+eyNzvq4Ujje)G0QzsbL2nL2^Eu zKZR9uOPL=WR+EDaPlRn4sX`;F`>QPT(+%^N6I9h2D&l*z0&VEC03>h&BwqBi}znTTfW#nct=h zP*1?~pY>Vo@0mX?)sBQFabK!(IVgQz<{nF;K}2%9y}I{)Mv|m;=&#c#Hl}G~U^G7x zQMq-KMo^rOU{5K_nV%ruIRK2oH$D57-ujW}oGU>MN!1C;JvEbCqRvTzE*oEkewdU6 zZt4hJ_Yh_z)qKYBRR|s+YvE|4p}U>j5sS`1k^6)@xw1^jVM|UFnm<-(IiUi??XDmj zsbZhAqLBDf<(sq*sKlJwFJ1hJ{NDPBot37$wn@2dr+8uTp-YgMU$-d1(L>d7{e=d) zR0L=Sj0gexC|9#M#eLa(B1t%Xm++wJ7Q^LdYo%?&uFuu{8;KW-ojBqUMP{Ef#3jO~ z6kRU)#J69I#%qU?f5cCBXbLs5=~>taRm;;z1foT4E8DPv+-TH_{e8Rl+q@b!v0gHX zE4z~fq3@2$J8%qRSF)aMak(f)uC#S59a}8iR9cj->WM-xWDdQHIqr`wIfH%Px!|S; z^J(^#t2}SSj=$7AW9E{tE|R?^iRDyRaXz1VxcE!XluzAOv{x*;GpFv5-)B@Da^%@U z01Yms;7BiWoc`Q^&#y7cCc=%R=M}TN62mX{3aoZYy4irL`q~qrc4~!vS%XwWQKxTE z!9HB2XWTvI^y1W4xSbk{<5v`51ZKxf$Rr+NLlfNX( zx+NbHEUU6G<67}yW8%#(%^aexF{_d{L_s!tzRfq-*HtFyva+&AyYtk*lW=3&`2V2HxaNayrRyYfEDkl99gdk$<$Sx+Cw#57o!3RV*cqtd(ztZ8G`44X~& z0Pqh@gkNwlCUh1E0_p1FguIF+tkrY3A^77*eE2S)@4M90c8=k|9-W`;ek?2FE-EU5 zC6C@5FDBvRq3L~e_0T%;Jy+SCOH%Ys4gaUgDHf037xuSUc+gW*A3k!N5K0pDPUuVI z8*cLT-P+#nqjaws`e7!|n-Vb2w~~uaKKK6AvaCaGjwm19aeL|sbX-zeTBMs}g_&UJCDB_+{hK2l}B%$7rfMNb8k&1*XoqLi}?-TRu@ z%^Cg&5)SscN$mZSl~>K{eWbV9C7hVa@GyA9zs-epvl;rC2b3ItSI)c~xIdMF{`Be7 zSdsX2bbvBu(04=M6fo$K;*9spZ*`#UR$|&l=AYZedW>U=M>p3eOIIORZmxxr1zna}gKoj^ z%<1{sBAxnhk^D>*aIT$epRZ7XY9(# zD$n`H`IRH;KG~W>)?LQ zCrFKU_=)r;arM+}7)pA57E}FtI@hmyylm`Jyl)u#Y4w=PZcbU=!L1LbtcpL!;j4&Q zq*tHj2av|%y=+1YF=2uSi|4jD-N-K{1!!#7a7+y3*D`c|El^y6{`j1fg!{tC#tgWL zZR`^Hl^`&>DD#BefYeL;@bL_^1>E%$&O-3 z63wHsuyif#pGKU6_3lpe$|<Wj>hpl#XyASs|V)DD*Bv?9{##x+!O_ z)q94Y;;mHAXKc7e{%J5*e>GnCcz9;5Ja~BYfqJj^lSA6*5SgV&2kYk#5-;`BUe6n+6x7_*BqWA0cjS2UE9T!J`UPzc^9BSO{ z@1YNk`Dl0ix2)*ZiFkf~`#Tx`bs!Q=M20)r{V4RG^V`}-c7egFnbLTNKiR`pD#i^= zCrXT~Jf8{rAd%1cN9=wtI}>HM`c5JRO)~H;{0>WjvXem8MdYW97HHpv{tAe$R|=%} z@85@pBzUnc7?pq!#0MQR%-a-ca5j;w=j!hVw1~fWF-R#k-rs*)NT_Zpke&Gpq`I1K zgeSSh@|ZMY16kd8$r51|Voy@HP?1|+@r!kAq8g@oU;GQ-9`pwsAzu}Z?&Rp$+SRr0 z`m`sGhWoxrqo1M7JJWl)ls+e@AwsZr_eDH-*mNsj9jtU6ZH#_s@H{!#u9`=Dp#bau zcDrKybgvCRPcz|B$w)MQ%!s1;@n84wLx8MrzgDL9Yl2+Qy z_XCagcjyeYIwhmu=km~r^DW-#lP7L(iL)o1j0?5P-tRAWLiSXKLWSrI+uq}G+iDU8 z0Y{T+*K`$IUe2RaW!neq>3;NkdbtE(^L-!@@->U4^G6Bq-D?MuU7_jmOaL9O+udy1 zN7(FJs&}Q9M4t$arh;LajZRrFHQ8{Hp&60e}5b=y0oR$6*#E>YH$ zI*WlgH#Wthz5lT0r{18G;CO(P?#J}J6_jSTd2bm2xt7zFY&$z<7XnBs0B8?#f&T{5 zY3b@@-l8=S`%@zJ;lt52kC`{kpYUExZu$f>yZle%(_K`MzajELm#>zClB?gqD(m-` zPrC8*%h%=>?;>YO4g}7s&czL(DS16!M9FQ@&(rVm;OD_=&-!E;Lu6zm6oY(JuOh?u z0+b_@o(<$JhgL29^(?|V|Dj$+aw7Dij(LjvE>4Ww^Eo(bb^aoygVm6&*J01mJv zg(=W$GjVQbs~51O?^|J9KfQG145HcfZm;m2!FK}zf`=y>WTQLx?wK7}e4 zPDL2Ie(fHluemvUN7Ty^%xEu5ZsMsXi`Y{H=GgQP`J(x2htZqPjeP;=2$2tNDd{&8 zc}KoG?no#zHX_5s+WFc~3@t5~IsXM#7H;hvw7;`{dk^^x7>WZXF^mO64j8H2# zxA7?BgeWTWMf2UZ9q$qxIl>S|QT<3kFW$veWml4|$nKN3(cJFp6Rx~*LDNfTk9H{R z`>SUyrf-{~yq>9koR^n3G4Zt+UnklQmSTCOE6VNq<&g7(SM)8hAC0#8bGPu0Q`}FV z#yWfv{~6GuP;)lZK3C@|W2_%4Jn;TiHQLK;Sz0x#mQe-DkJqLiWL8#IKr=@0H2`Xl zm4_%Rz$a4IWi#pgS`&}2M&#-GW}Z0FS8J&~9?dv{Ec z|7C49I%;yqnm?t#^{>|LcH0bZ&ydIzbiX*%qwQ$~H3pAz3NlN%EgQ!0 zY@82Wvo(u_Xg6({wIpm)2*1S&Xfb+uI5x$>B`6oIuC1*-lBXIBhz7w08F+3#8OCwv zGkQvLJRcyBggcF^q%JSQjzGsKdA}g!lN;Q3m;R{z(NrcXuvkMGO~^caEvHwDD%5X& zc(7?l&gZr<5(-Tb@{1~4{bj}7N}K7I6>rvWp54u;ZUmhONRan+bwWAHsU1Mll}n7x zZv?#0%V`lK#VADC97-M>g(mQeIP({;WWjsC3KM6s>u5F|TRhaM&~F$9FL)mD_NC1K zOENi(Wdpvmr~1=)&@Ga^!$VY~tMg;M29FpZ1>%uZwP+g*lryCx_+7V1fyQ5HIN9NJ zKIxV{6{T<-PTxoR`_C+|Y*kz7y~q5L#*b=Mx9AwQQ(k{RqvOOFUjlv)POCB2 zIgd@YA3uI5dAbj@aN73`#nE`^;mmpDK;o`0UO9Dw{v%m1u)b?T*pV741sSPU{ zn!ieyZp-YV1!g&2Oss5XB&zKDq&3Gtf_QxCQrlU}9 zxqU9*B4DI|@3kch{e5&4a4~;*1v|Y4{{_5i_%q&GomF@_9D$eQdijX)_N-R!nB_tF& zONIFP2frzjL*eM;9+>fY(G4Ubbcr$Nud!8PC8eYuoBYHA>Cfrpeo|pU`bE{A3psz& zUDy6VUeg`Ds-!65=i2|)Q23kV6)7~8kZ#Tm%{I|Sb;QL(5;!jtj7uC4@^c5VG~o3z zivbMroZ-dgN6hq4QBe`>v_qXiap#l{S&9TvVn*|jzrFR7 zw>l>vQ}we?}YAb=g|n0m-gf)bR!Z}MF5u#YgmCX0AaV(``6(y`@atn!3?!&O^-gpV7%B1D?Ae!Y!k7D{ljb{5NPt?R`Pnq1!|`)+GCn#w+Oycw z-TKL;u=sZO`2g>p?Td$x5j4#Eam0^-=7}RFCI$?-76?5JEaRRS8?G1uRAcquTy4|| z5X!`oA@IE-p5O7Y*>x+ou7#WvZu3TN{QXsZ6XWP?77V0hV0D1)Y%MYZdZ0uF5-)6_ z7TPJbl8W3ps>!C%pL~E2J9ZxY4>1gCRx6;hTcvG`F2}7$Xf7dk=>PKr%>cO(r3v~Z ztq@9zwBtTZoGRa!G&(f@Jq5d<^Ivh$M{sURY=+lHG@f^$^H-NR2e6>NA}uD6mZ^E zP-6u6kBp48s#oSYdpfo|`f&W`Dw%16;togEY;U0@XntLTh4zq;;w*c_gq!cbU&HtD z@p)x#{sWkN9PgfqsoOfZD!%h4-s|WV=Kno36&asxIJiFO=z@T%C-Lc|AMhWO*4GeR zFCMxz7#|N|U-Zj-L(j(-H#0MBnh*U=m=hTUjwYz6X3#U%@3r2-Z#+Cplz%z@ zCN!G6UG4!;>gD?*!%a7o`d5f!15?TCMKp1PkNB>(5200J$!R6 zn5z)PF{mrcERP?T(keg0Qt@A1UETkaXvbyVOKLh0eki5b# zHjh2Bp(mFEJ3|aCI}tb@Y1zP{crKuIHs?y@!UI9s#W04EIz zuC0!6{|HY!?cddi9!O;AzUbeuI<}Phy>?H49+1jC7Ju+O=t9%0f>3|qNM(b7j#%^X zX%PNm?mUuaw6(Pj1N?TdRW`s3F+<6yJ z#~PGDxj1(H@X%-Zqs$ylmp{HFBL=bKZK=|~-oU_B(&q{WMTs*#93Rm=sk*1{JG%CvN zqIExjJQm`}_T))SapQT|fY{9pf436^tMm5MJ-=VSeqB&Q|1RUJVlmcGvg_(DE^jG9 z22v2F{@d>qpFk;MjO$Mo8^}rZ=|(8~8XCk%Al`>liA?b~40-DdVP5$9iIGVB>qE~j z=Ovi9mvV}ah8Cl=M=SySZN`j%#}Ol>^oL?%)PCTINOD;2_zmslg>r}`XY;yZ$%#?f` zy^R={Bzd!HIy#TM&B*meL z1?(D7Vt=JQ4M56;--S+}7tnV$*nqTj=a&g%Jt=Q<_&3bA#h6z05h%qkiVYfCx4pK7w^HzeiJ$HCwg0iE7=0p;LW*H< zEYGn=h=9$A8r&T|Goy#_iilqBJp4ckN@^#4>>T#$;ds?grAr70N zzf7yRZblDPs4pTsIqLvEfwe~lh#*Lo3aO&W;5VDSS!`NvYS|dK{g~@<#PrsYLe0wH z{OK*kz8*Tcx|)M=33~a%InUjDMFV2yyam+7*9NO9AxX$jQdwukgRl{&hHDXakkxDT zZqvLHm2y262yIq%L)Z#4F$hRB3E3@pVnU0I$5Pzh-hR<-hDY{l(uCAGK|`=5^x{jM zJk&pgCI?V+IXljPt3OGXQCo8)HR2*h$tdFmB1U^5wnVF|tM|qYeIG-xx9Q~ts2ofj+$S0WB}Op^3FGKgm=03#n{d~mfr49~6o{QbI|idQtcwqXH1Lo6gUMpPDTrQku*vrZQ>?lD>QmzF z%9xg6uGn0*kB9}Mss+v5l#|qQzEK2z(0dQ{C%dNa*fyF57x6DWIUaun=rX~YVpZH= z&I%vS80h%7Z{IGgtVpV<5kXm|zo4U~CAfb-G#~&Kdb4nHzS|83hF{XLX}UvzX5j|a z4yofK_00n2F9rVqvF}ZMTiWkFhhnOmV85Dg^!5USBhQl z0LKjx)MOwMnRN;^WR;Y7$IgH)Cj!3-9UouSi`3MVlp-WK4-XI7q)38{Xs{$b15rL6 zVF06JVcBfKw>R?7sNXGU?B8KLL+T-bY8&(X)+<;wu(uFW*`C`hH2b6ebry^|0LKC$ z0Re*hM*?>)=sg5LyPGD1O%U1>e#ezxlwuqJz~Dqj#Svs!gX0Pwfdt9Z(-VASJwOw{ zIb*zhdT?B_NU8Ni&YPMG=S?|tkY#%SqbrK`k5|~f*Jli11!XE>6A-u$epfwxeZ}sE z`ugYpeJqQE>WZteN+E=a8Kj7gxTYpw2Lz64b#!!md$C>hdMFD!ib0t-*3-ko#L7zd z6g8W|UtqCh)9Khdv2<`TfG|>n2tiPrm^_4PitynvPpP3v@j%lIJ#$1c*rI~}O-h7# zsuBfd%f}Id`m)j$)ip4{AS!y@lFC26)-rYzU^ms89q^(H-J?I?->$y~#-~{HcCs7S zg=S>%^ePO0Q;aY>J3E82MePMOq`<3_;0-!=xm+S52b-MI{Ljj|os5{S6>%6O!0u1%Y7}`ja0xf ztDGy4ahXW!sgu*gHUOE29prX{Rd$A=rwgcF-rl!-(>CLbFK{PrP*>LcJ8<3^1P#M&0kKBd^#38&Eoh6i>Ec9rPe zqJ#8_oU5;v$Y*B`O(F~cd;wI9L;x}XST@$dsRHS!;fC8V45h0S=nV>8bj`^5IrBAK zfBm#cg50qJq5)}P+ysjhcWJ~yf>sSNL@={Y6iRn=4@X4<@=;ig)7lTC78G{9Y9#Rh z3_O0X(-MckQSbY>8)TH78hN41Q#I4m<-9NIM0hp|T~#M1;x1*Qp8cRKG7_neP?n%dg3_BmT65xv;r1{aMxI6?X-5(qMAuMXq! z`~YjmKvK^feX~AM`Uv2&uzsy`jT=dfC`rF{fN4|fe#NI`56?s!vnSeUt|~d&RW7XU zWp~V4D1-N}L5_gR@%2&4!_vTSDFlBU7hBPn1%&_r^A;ghdtbP^ZcVf}4TuD%rq0je zr}g*`CocXiwl_(xjoxDWx3lrx@3^-0kxh#Z)ioOvEJEF~qO-gll|;xpNLZ)P{UUsX zlX|Dpo z1r$I8n0XPVchEmv){+l@Jn(7T&T_C4yn{sI`{Xs6D|*wPFFaHT--R~F#$z*&p<2K2 z@eu`kVsAWmaHh;hLUQsC(wXTXx_iMhf{Z=X=(zExt>Cnxfy8$4IOb~38 zrj*JasA=dce4oI%;f9*p0l)oO>*Iayj;w_!Wzol~j1nQbL{b2#2de2Km2ymhrm^H9 z1J0}Y6V0<7;lk$~bo|$e=aQ#2$!RO|bAL1rUFF->9AwEdCJOMWge|>P|GvHj-p?g) zC$k#Ve+7;kJR{w(FvtisjN7~y;a%Jq%}?BMJ|?0t#OoZ(9S*&W(nQUj)~0maR5$$c zo>2wSg__64#30TzIHhS|X-RQ05CaO&pFbDB*!`^x$2-_gNuwI0h=O}|huWF@wKK+v z4Aqc!$QN@2bB*~h@P5O72YGLb2sqeSO|=2xBfR2Z0IN+Fb{4Sr2^RF&___OSIK!$i zU7EZiMuqR?*liO02*^uRgi{oka8Vr>b+bzh_v)=QY+kzw+ZD5&ZB`~%e5AI|G9 zl~P6f0Asw}$jd=;sc4dqW4}X4_)c2o!TP6jqxr7+#i6Ie0qXz!1t~|dZ&72T>SA&y zeSWJ20+spp(vryzX&|E}Y!N$q|5qNEWO+SfZf7?DXfa~f>QpUV+LfZfLtBwzTvY-8 z&p0lXx11u`T*L}}HKXbZeJueU!qX3P7W1cbF!})L9U5H@K{pSaoTDgv^ZY3`7h?|6 zqbj#bmv=hGZ-#Pbk(oV3F7FbUy+c?KVOyl4qoUfNK4=5_1&V4W;cGc)^8gh?z#=@9 zZ-HN1S@2;wCcxhOiPzctb?3inqN)3qfrvx>O_GGTEeriie0&#lB@T{`CIG+wgm3z5 zNqi$-Z372H2pE+?4FNDQ$M5kS$}i|5_jIjTo`<&Cy9!MOlJYn8IRB>elPh|0C|i-e z|D3dXoTn{5V}kw{;#qdUOUB?mo&m=oLZg0NyK4R(pG+G5jx? z!pd@r7RNSzsOJMd$|wfDg6)=@&}rGWoX3{CoL%Vz#2tbUAHHjD7JvBgAp-gX6T$7K zAn~;iNUF(3Zy~r7LX!CV*K!%f>KGOE^@7>6c?Rli(=>Abe(ed16sb(fHZiK6=1ML! zv}X|-Z{nhrO-m}D3;>4|Rsh0%xam+(uBEderRT|x8DJ?%8JRNA6I=KOl0hVyQo(t6 z>?li1`&GSZ*~b%uADD!rnjL)s{1Rfn}Qqk8&y(`jOWzL?c-<7T)eo-jEf03~5 z70AhOmO$Ix06JPmX69tI!z1``^;dtiq(!I6*so+cHn)Y(!ni9GsaD2jy;sF>T2ohVR}S65B!I$fK%WYvPOBHtyChCRl=#3X?9IpYJ)D` zUPC;qSK@colxYExqthUyp6a45O(qrgm6erTD^o_C^PYWH-y9(tpFI;@7OD^5FN>#e z_}$~_Z_U#${56i92r5yVy3nktLr_G(XD)7Sg@ezEhK2^(^8Wuj()z2?=%-Jg#9_$b z_U+qmJv_Krq zjdmRLh^gZdFGk5e|KBo3TiAcA(54!ZU0Uhfu~g97-}obn1(0(uVYG@!${64X&{Z)o zi1f0_#~X%8`he5u_+i##@8DnzNDQXik`a?lpZ;Iw9zv7S7{!h}M5Zfk%`U#5tx!z= zTJFD(n{OPXJe@cn5Luw+`^IJ@R!W=`tz7ah0d3hRjtUMB3A^44$c=Jae&DJ{FiC*D z0>Ezc14<>#^B^}vXPu{6Oa<)>f)KZz6@=NLUPwoK2QSwy5kfv&HIn=E z?OT2zL$iSplJcRa6%$JZqzztDsprqJ!1@Au)*UJ;+X7Y4R$*8(9Gmukh9}6PFvUUg z0=woK44d!(BAZ}fWF6j5whA%4x=;CrQLWYs3)e$}1=aF5lMYuBb$g8pEw9Uz@%A`{ zRifO9P!>T(p!P0s9Dvynvja&IV2*QpIWF+A zHpWla7lW#z%QuTsuF&3^>UBVHK@c!4+Vf-^mf&0fi$@6bgwPIvDfuz1{{_`TX(!b( z+%+pFr_Afj5iykj^0M5Mzc3QW>9F+kxv~nQ$s%vhzHM;KZl_L=luA@KU1J zrr`7#aehinlm{n#NolDuBCSbDA>037yED**LqLOCUSG#PpYaxmT15ondft zazVV2in9QzNnBLrvHT2osHyCK^+0k3Nd}z5q>`alzW)^sfUT1z`#HPiUI>#LD#M4 zMn(^SsCYG1{+gD7;jmw5m(y|Oxh%nI`*F|8&gqv+k@=;xnPy5(Mx60{o|c+p&fM{! z^O&SO-+5HvQ4&l?X3k}FNZ*Ef#PtfPz{by1hQYCGpf^a`O5fi*Qd4l_8Rb{bub1p635?? zkERGfR=U1jXVF%(-La$}>Jdw)k?r&GW~k~$99XbE(kz157O03^B(aQ*Gn@97cizt$ zrZ;?Z^=2kx8B3}#?^E|paew`gThK)!pKYvH09Zt6FsIa(qfK0}z4tyG+~E3+B1cEU z(}$7iz9d#YGJO~x-20eL(jEFQVNxmopA99RyxpavmeF42&7t{cy)#iVIs5a!Yo2i+ z(Yj!%Gy)Ax0hnu@)V5*k>Bu*?&cg~ zlbx~IDj#7K-g8Q92yAFjh+~(OV!+ONIK0-9XBndZjUL~-(qY(;34^%vPbsZZrwa?8 z57mlnwMKIPi!Z?hD75}+!iWhN#MA_i58tj8Qqn-V`E{!HB~i}usX8i*ZF+H9@k4k< zXTf^_#0j5EIXqHtxYOu+TTjTXZl>!N*%4q-nGIfVvcj>j>#J1L{k_E>X>kNgDYX94 zZe0!~C*=I~y%SPqC9Xyn^E(BC7Mk}%>buwi47U;jz$lU z#>$vam_VsUxVMu4{6T^d&Y&B+-Tvk8xpSD2zB^`yCJxAGlQYc<4l-O#uT64S4Qf6a zj`!*f^}b}j=cMR#7O(q3PTM>_LHjSC)NeHjIz>D>zL}PLFD4f+ud5vnnQgK3iiCH^ ztqiy<`g^_qNS+wO1nFHWsv>1739S7RT7Ti&(a;07R(@R2ODgK^#UVSUnXAF;n|5P> zgyjdLwVdAP&hEa?u=ZhZzj9?ipm`a`&wiQ5!d>Oxaka3{2R^+gPL2rb7!+Q_=qEV8 zU~D>^yoz9{^a1uyqSdvw&&MS;^t99?G1?OuWcUj?ETXJmuS7O=)thljN=l4iRza;$ zNBzAji3Aag?1OKAPKhUk@33#d#NX7j;ip@@#RDNH^mj;d>Vhg@r1(AVeH6dAxVX}c zdlJGO@Kj-C4g~j#HuceKfBxRWQ>w09-o~dtT>iL-1P&B#k0VQulO3D#7eNH80koff z>>Q|sBwz)PZ;th`rgw=u21pa|x)a}=_&$X~Wn^yN0T#7>AgCavJhtrxW$Y=~JYqg) zY(~~ysQwy2k03_zkmxC0SP2ra-&=SJ?JEeR#{ae^h0j)^IwEzjR3e|FFj*ZOIzNk) z^u}6`b1|!!lCbB;{NlK$ro3>eJPMuWr>|e1gIpeduaF>vBFa|4tZRLK@ld1WT2cQX zSM8R8eqW!Gy!*+r8N%`o<|OZ9=#RnrAwe3U=O2y!n#5?Bf3{=;N#k~{uDT*-se>v} zah1;(n94`B2PZZd9yz(WxlNj3FckY|b@UKke&eG4F9md-!4f`Uz7+BaPLIF#2=5jW zi1_hhzM>qBrx^~W#1bLC&ru%7CdL_GVeuaTT4_M8=f|8Ow+HI6)_J`Z?8ZoM0k6ah zx-f(KD~+p#MT0Ag^7wt!wDGZ({Uhvh;@WBTKACs%J7U54`7EzrzXt4wm=OdL!(zoR zh+s+Si@2PsPm1l#cN=ab^q8ykX_5tvIG|WqZ`=zOLFxvT^j&HyHQ3ms@wCA;BJE)u z6B|x+`o~Nk<>}LaxxFb3`+Ru`2^56S0KU#QfX|3ofde)S$M=0t=fVdgeyVJ8wyMpw z!PlZ%QwL2qS0ACF04~8mh2);dSER>V;5#2f$no&Pa3}r4hbVs6 zR~Lw>Dxe#}$;${Ngac)2Q4or_Vgk=1$PtL)M<61jK7BHJ!2m z^0k4~9Dt4I+c0#C@GrodA+fB6kh z>f7|<9uyQ7B4+QDl$5L|O8kKd{Dtc;fi;{J_8Z<=axV=)*0<=F%ye{8+FDwziXS$C&n zbO^FW&@g9z{Jo#ePXBiqUS%?(+1J&j0u(9F%QOir)fe=Q<2#vJ)EPP7zM;HGmq15? z`R89(qc^bh*QaT4zII^ zdY88flGCm_YuRgKtnPp%1{le|F!TkhgY-2qad~;!bfg4gSmoaIvm@Yar6Va2vw!Xg zI^nsTTTo?=C>n($R7Jx1|lIQ(jC1LL0d~R{Z^K%5Df57_XLb zpgbsoQQeN8p?Bpkopv^U@`iX}vfm6FH*>#m8&%1sl4H{Fz7atPi$Dg!J4fJ2yFf85 zsi=5j&@ zYp#GZ;gu#EaX{h`b-tc4?0$WE-L$7Jqkm9Rh?Yz&(G>9_n+j~Rh&~KlMNXhGgNE7$ zbm7-0RrM1%$| zeF98;sueI$oD0I}b1S@zp$I5>ZS6&Pr%6e4?w0d}Al@H7|5F#pIEn@Vi=OFE87*D< zEG;ZLfzIIM<3kv|5gG}MHpg09!(cTnS#~t@Mn4d9#xRl%o$GC|d3e`kW?^i@_2XNNG&CLR^EbQuUc;g4gZHixDfTd=P1SbxlKFAep z*RLD}iO1?Om~xyqMcLA}o$ZH3)&yKOh#(lic7{p-E_-lTfuP7X#~(h9hdWLtOOHx2chy|3XQFz6G3(&y<%h0cVhpNg1z8v+umvqPfrtR{f z*TRg zi6u-#)lfcg6m@ZnYSyEHYS0HmYg4*YUG6b7=-(9LQJUfH3eTLK%N4j;0vUO~*`q%U zV4B-G)i^E4W_Q;Tkf@>?JXZBS_yv=!Ab*^%JcjNC_VQsD$YeXejKa_l4vjmlCj_PV zd}3rCy%j)7sy|YPf`oXH3cQ^I@)e>rMtFvo+gSq%q-n9yoVn49?xO|!3>J?2-ZS`$ zPCSM&iueH_^89OR1mN{6$t_#Q|I*i&M|0i%+v`b#DMXnPq9RH(C`1`5l4J-W zNl9cVbEZT^=2v!*3cilf)t)9o{C~tP`?c`(f0R zQ}Zw9#LiCG*Ao^8*F&aQs4SKbd4>9_#Xk#GMFVCz`{TUBn(SsCbF~ttPdRcurQ1?i z3bYfNvjBayc%RwKqjdIf$-~eWg(n^+=<0zCTCuN>%ER?X%f0)@bIds#h(m?L1#a`T zIvtnq;f0sjkUn?r+zB#qYRH4F2=*!^OlRFSZPr#xHfO{Ly?p{j9#YE9$?kkiffJbB znZSWcciJ1!8C|x-_9>rAdQ08?N4>e`zybI5N#QpAdaDxymdwZ)DzXe%G?wUQVgQO%?6>x(`up>|lOv%?&Bj`o1EH|^*<1V!par{t3Ld8fpBsho z;imqzvhIyrUEQUpq9kj2dZPWMS6ShJ0@Tr$AraeZKYP;7Z@WE35A5Gh2X_NiH8n1? zUO!GNYqjo9_4@{n{X89|48u=`!s;^u7v;TCi6#=!~26* zqs3N^60`PDCZK0A(Q&l$pB zfj5{^mDP7+rz`Cw9rqx+Q`=}?pyOKq=x8;_nC_<&`a$p5y=&L|W3Q=sJm5)^&p~54 zlD{>|nP({EfETmU$$9^P00v+No60b%|BIyI%lHb_=tth&0T_O@#>;Mk0|2N~#JOW* zSEwpsBJR^jf!~cRX0(t&9!UnLOhZOi_Ku}xS#`A+WVs>Hr)Xj=-KC`6+&Ag2a)iCj zA3Q$~V(2fh3xdMKt7?Ty>wuy7GN)nrGtMY-i&^yYadY3_K(n2>z!}jPG*y4p8cZ1Z zL`QQ1YT8I2Eh{Vg7ZrTR+gnWV+&YAT-%W%m|E-s%@6J4s8ZWQb5p(Y!ZY&QxyJCdL zi|jbs6u%yfwa*!PUH16;a<^1JQmUXRYRd#KRuEFzBcNzGYa=UyjG_u7pLA8lSAYK4 zZ%9UqIWmso=hUsk>^9i*n^u29gSsIZG~#Q=f(!Fv(mvlz4~hI1r?abyKQ#DNUlf=U z#LMSytS|-%ibIYQjG-Ne0>CH;3JH<3w9G2OxH}M~>i?@(%CS&b^zm^(hZrz=`T7=* zzkZXQOxFCR|tZ>Q%T?;Ac^Xg6hqlMTr&dF0@&T^66F!hBV<`ijp`9 zcciGldMJ`uh4I46YVeXbf-McnG5{D!CPgpMn+V&c#m(X7%go zY4&j~R>bUPkPO6&n&VEbzjAMMw;z{u1F~5KR)eV4jL_Wq>V-srD}k=fhx5_Fb=$XZ z-?OHta*gT(?5FUk;Yl|~#k+sMFNh4i_Jed3U)4`s@_tQ)o4!M7u{hF48b z!u55M7leLBZIUpmcom(+$7({UCjEd+MdkLuz{m2N6JG5PvEGR0I+F z239_=u&@=}9tt?jokyAP041RoKsTTV@cjen^4_<}$yMWGf+3TUR|R; z_KwZZtn#(${!9LxA7&QJSXURca1?zx)A`qJ0O#uC1{55@D>4j8vI6oT(XMW(OSikF zRFh!c-&tUj`p={mhUy6+EjB}(V&+kIZEQ5)+?0Y+W*-kv`8QV04Bd-33+l*Hq>e|( zyr2guLHq!}RZmaG4o#B^t)v(B%Uu(8CK{n7*`+noug||Kl1vIwMM0nfrHwiYtwVRq z28f|d3XYZykUhi4yOip{2i9$?tnLiG&YulCbVc2(EaeaG{M(;H%u;ZI8sD!9;ai-<77 zbP62|-Mi4QQ#m>j*M)_G4dy8+OSV)D#98niUKU2FGsY%lIQ%BvanG64>eqj%u?ekR z7X_b-mi@3N;xLEA-HViWyA&mb)YhT{DOK6uUjB7!3#YVOvui~yqe?2Las9MajlsRF zBYV$CmVZ$>l(x1UG#vTG0FjH}1U!=pThHElll4ekFRopY)tOnmZhhZcToc3hTMb3F zU!t6AW6F;PGO(;0)y%h@ULb}Cd{lX7QqWi2uG$SJ$ z%puSrlOZo*ild&e{@L-m$r+%o-tZ$&RLjo5(aW% zVPQ#I2M14PoUGY(lgn6yy0>GU?6qoBsV5viwpnI>IT%;MHg&0ka+YIusEp#8So#s$ zx9>erSyNhBSrOA1!OS8Vh_POQFM|GV00LBWRa+Jdz)*kzSTouym}f?S0!D!omViNm zmbNw#S5^9Po`c_`i!=-ae>6m!{>sNr-wQFqw+?-$=?$QL5Xm@3u`~GmY(I&l0+VaN z@$u-cP{jAn7YXg(4{=nhF!~L=DO-s4<;!Ch$M@^zp*!G0P@w4HXM-!i(PJ-4OQlg8 zwZ}3MySOIf!+-h~s=5(8q27n`*b8~l3XjWiS@WPCP)KnW*Sb!nven|jSeRiNb)BN=5O6PH@G(pV_BFq#; zk%ezgoo?kQ91li50ery680{;S9&U(E01pg9A`fKMU@Q|c_d{q}Zki_22|~;zv_o($ z5Lf2c2gZO;jn=OPSprOoMidQf61G2OT~8Yj&&Z>Wpnyd4nhF``fLEKJUgYw!V+Hi#jHIe`jj3QSFFUCWEz|g z;zQmyHa5l;fhw|S=m#3cRUMF+iKz{!*cF&fVFwPNLISgD8rEUphLCRx9r=kl^^JsC zNn8^_^1_xT;oEkqm#*x&ym#`IVsT7i@ZSC?bK$4C)HJM1a!#1AzVgYF6ogS4=SFfO#yH2O5JN|Di(QJ&Hp`oPref5 z(P8p@(E+nlZ_@UQyJ&2k%h)?5DhWq>S3o1qR9 z&IZsu;r;qk*4Z3vj5+D9uV2wl$8n7fg8gOZ+Ljt#AH3wc&zo zOK~^9Vm*G_WWmHjpw`s)pWber8W8#L>v%X0LRhRz}s`9%81UqU16Jz@a6Qd zu1!V!w?7PYaeXp99I5&=AU(_KUQ+~(VcP7$jrspLC`IUKiP|r=dkBd)yzO2`yS&@~ ze3ezTCUrd$usOezF3lI(2ZK6L@ptfq(*U8g(=+EP7`S3%u_h{<)=-h6^?DZ=P-I># z@A65f(AEr<7H!FGyUFfqrVEm%@Z{I^OvLCo$|WTw-GO@l@oLnAF6|92Yb(EZeO%@? z_y3Ef**Lr9>9c3>#`{z&*tf=|@Q*_s8F$^N-0?y_hOfr(SdMhQ*eD6dted zE1zjNn0w&%mdEE@IV7$d$kDJI;KN)B@pKjr7OOZk_dV@{R#TYZ{_YpNkM$uAeJFMSHK3J z$1FIXfNe711s_oJ?f}F^9ye?%Ztw1nA~R~>n|Dw6l=1~sslzn$sg$$01pS_YCaE2T zBGU&CQnS-@chzlaX(;zQo)zb1ZvML`R<=N?Sf`ip>u>@XckEDt9vj6ok#=2>`s)F| z!9y4%J5EmZ_n*S-9~*KHDt5x^x>`m-n3vAcfU{$q7qqW9P0L@g@83YIG=buB?NbI$ zM@W!pyw2jBAPf=`zP$MGCK0e_Q9CLk921Tmj>l*Hi`ya&-P{72CKEF9(AdPRPPK8- zkP`BP&9aF~pG7eZ4+REDF`!)#Z8FX{%$9V2A8e}IVRE7|Z+(nX?L?LDrQq^I4C+!l zx+qgOl~uVg{N2LGDY_uAna4+N=W}lvIRNMT=Pb zqFA>tgXMz1CO0|xRLfdlRG(qclMLIZo?M13sQ^A^p2O@Os~>gcFAYp9m#4%9oO3Hu zO|327nb!Az-lDZA>C{D|+Q=qhjh+BbzSK8Ra-)q?f;^u?%>4V)n=w3sg5GeNP$@or z-sME#rc9>|ysMw<=QEmR-V0|P-0UaEF5!e1L%A`jkkCv#4;Ci6V2Q1ttoCvX%G@=- zZ(~{-V(m*DBHx-fXRG!v^;%lLxwD={Cghj`_kbG$OJ}Y{BanDP7J}g8(KeXCt!4iD zd@dk1^_id8RQbkOCYcC0hY!R9(^UgsWMvU_cNk53n18I>Azr_!OEJK9yR!Kq)sTTx z-4+eMbZ*iLJ$Y|5@2C!10vz6YMJf#3z%S*xaN)wrNG{sa?;vu%B!v{<$$;6o*a@C%RYCD0dSr`dlrX8qpaak*gE1Mtc2TNzi^+Z%&)fmG$4 zn=6LWN-V+{8}!ev2EaS+i5U@*MoiH!;w*Mmw8ACoyfbsQQ8*rXCCYScbp0pJ9i zSr(xz1^dF7OdCk61Mn1c{>2F}_z2biXHQ}K)lx#7MN)0f)R(4!eR4Uz84O?6_Y~Mv zbag$$JG=&21^_tQG0Uq8hfVV#?T`$5z*9J%$uu-H@`GdDuYIw+AyUe);31`)>6bJf zDXADlmtL18Gnd8Dz3%r)muF~Dx)3HM(NVxQb)RNN-5Duy`c5&_&Y95L**VS1rz5aM`jh}N|sD0y9 zqP2M>qvUSOxizc(xBJ6JZ*YYI$pDhrp1HKRI0Ng}Y3!_4l%&qEA3cPaSlPYYm&puq zA24d@5f?>KI0D>%rO$;97vEwTA9rKp7ZNTJnkm3nzYaz#$RHT9(44f}wsq&u1~358 zga5!tk%+2xp9`ZXkTyp9c^XPZ>Jypx@9TeId-nxi{ooES$R~tS1bTf?baXu|tk1!T zh858M``HMh1qf0g{t@Aa_O-d~HPG$SnOC2gNSCP ze>QPQ$X%qxG|L`2oK4dHAchIoP$a>ZXWVbo5WRTPWQc$od6ffxfXqTj|Bb_Cw`0m> z_K9YiRv_3+qg*ct^9P?`G&Tn@#^iHyInl8DCd3tC570B`@<-{qdG4a3qa&&~1GMUY z^0g}HSNb!L6o|D*G^`hNG<N-OwbCJ$`tG&b_h+yd1s76mTm7uY)t79v% z8dfIY1q{QfMq*wQR^^jzf>PGEad?Oe5#hKY5Q}Sy(c}f<;s)kzney4q@mj&G=EGK>tQ^wI+5+n1+g$@qgJcS z4nVY?OZTFh0Y0@GM-b4SCHkvfAHTq~K~hqZAphu;USjaGv8&35O%~Z5pdl#cM~Es7 zPz#&}<)D~B7bPDkrMaA{#1}ACvg8Lw4=H@$%TEvD8piA*dBXxerg(U7%{XKx`NSf$ z>9&hi&4l+Cu+eHrshd)*7dth$TDe7oIROu+72QaI?SvvGNr>C@-77Y*yTS~T6|Fx$ z7DdFdJG;(DNwuM;`;)aIhn_jlAlH2 ziBUpA0wurmnfHwJnM$<7J6T!J;$TEzmL9ist{rYh_ymVQ-(Q-vpsv{YEC`b#2)Hn? z+e>V`p!6_8WTJ@LIdp%R>Asn~<-)qYwUa&Jx2T+1M11pOXUUXE^Y|D~a(+zB&d===~7K<1iy7Hu#7K z=zebfYy#-++01nIBCb3TG5O3-eq*Fl{ z=)2uFm&C?cBxX?rGQ^h7cbI+QqJEx7=@i>Y6TgzrtF?v@FG}LbP1Y3k69CTVK>px^ zJngq>TqZ<*LxnjQe}H@pzZ-i9C|qbq>9W+c|HX5qqD?c&O7W#{?ThsCEZyK|24`%{ zMdj7%EIhocyj7n-L4V*%ktaO2HB!{`6G(j+>Ltj)qojB0F+JOfQzUh20*&MA?+(G`@ODU+*5|3+jmDvML3GGLT2}LIs5?wea%RZJ+X!UpEs5`2*tQD z&&h>dba=?%@BLuvP4@DOkA{IKGxSThaIfD-&9hUYJyX95wBQZ{=CRlIfd>(ap(>jF zz;vN|c0qL&;N>~a$S|E+T3iUYzlJZ5N zF6WG`Z@06w4A3823i!{@;w7byITy8yXZTf)wnoCLS@Z%Vow!X!ga*POFz5D4mo{u<*QALjIFA+0P5{1h-bz^m7xbFAD_Z46VusXx(ZzuPSup{s(fTRlyS z5pqAE2k@!RX5>BK0Equ3@Eahb=*a$H-b?pRFbUKJNjyF1P9NdKz=Og>Wf+~C$D>CB z-@e_)qa~#XLROLk`|dFpv(LE}eG)F2o$t&{RjSlGlkth~LmL%IFDi$LvTJAA2&)Z)p;_8XZ)|hN}#>Xw!peg&@PEt!|>FPC{T5?;) z?Y@#|SRsUd5eUg!%3&n8!O*#6maHu3xKHe9J)IH-uZT-1)$_*}Q0(l3S~D~>G)b7_ zkdY70oS^To8V@iCQUHC8wa?DXgcKGQ;;=Ezv*+uv1@*&%f}R7``<&b7k_z63l+=}VCh%-r6o>ps z1&Af+*BNsUgm>rW2C6E~kG7t{4GW_gOA)FZp{ara&`_v>3InNh8T2Z!Np7?7_VVhN zhD#>W;$k+YPw0{JY$qZ`-tX7=PeerfnI_z7l7rz06BCo+hfhA^5LjRzsHI;%0vL)| zT2Mfi3|<%OTSz&j!B87|R}9^Tf~soJsb{F+zg9C=Z9Tckm zU$wx>$Lq@h<%sp#y8|X0$$hHI@$|>Izx*$_YP4h-$dcX&Sz|K|%^++uA$j4r4>~`l zn{*3sjcK!hmi)kc#JN@=+10hRt+7_?G&ME-b{xN!nCv46o-)X(ppWNS_Wy&fE)k~! z_t<#i9SBkg>yeJCwzg3GlUM$>?uKE#jwzM$clakl7VW!d=w9Mw9^P#=$BconzoB-z zyZq-4gjy%?c+NmYi;>5kw$po}PXfEFMcr%ND2@STWnW(`;_qlJPQ>G+q}|w6;$#3+ zQou#g&;x5a1ivWN$0K>Got}W?1M5+kY%6rk zX-4(ehNG#Wq~!DOM=El7W73fopQ8QdMGZn5R|P_@E?)pH3fhJP2|`V1PEJmWUg5h) zahsHK*MmtRi(s&|k$XQ7VnX1N9Vz8p5V-4T3_vG2u(Jftojcct>zC%2rb;;^_!8jM zU6`Vp^aPcLItC0WsNKfEn_8SeA!za`fTsrcczo^bOhNUKj2O=e%2KGBOX!MM$NKy8IOwd!aCb8EemsEpS;WU~G7Cy*t$x0`E3_ z%uH;(G$A3OklftddzjBn{^6}x?>zg+isVVYJu9?eRd`JQk9$A~; zW&biS=ODOZgx~?%>9r?{n+Jo%njhvpuB%f5s#l3W@Y(&#%V~=KUANHI7abn6nzamT zxUSpgJ4kE4)@e1^k%!zPFoJ_Re-F{l`LhjH3lL9sN_Ni(r z16*<CBPr64Ek|T zG{CSXpxr4M0S3g1-_4yMHx41)2rkSry=VQ-=E<)~C~`nqh=U`*(d)=RcF`@zKxIby zgBz+c6rFQJXreGgi$uJQYa3hLIEyRiK+ME1TOSY}{urPL`jCg^%rD>scnu^9xWVL5 zHmZ8I7__K$Qcq_|t^P5Lxi=<&2q&+r+pPx~4L}46+*)9FI~9(uQVta07|wiFyD-{b zUsso`^?HC)Ex5CzBOoSbHTfm{SGaStGCyUg+^xwi(_MvJj~jSg6Ag7s qoSx#Fx4?k!KN}kLHZIATS>w8_*KQ=4$%4xYDHP*pVrBqZu5bEA*3V3!ong^Re1)*!uk(`g@u!fe+N7wWf;H; zzTtW)s=mMnUqSe`ao}fKZzUsdJ$HL=KPyi=EC)AtS36!W8&5ksH!nwb@5BH4WU;Uw zVyQk;c;R2LcVp(}8*YUCPU;V}E zCE{vH=gNGOP*pK7S6a`WuEv7R7Pgp(ISsu{-F&QouY1$cX4&h?jQjlgbK=;iYrVna z-jb`{ry*()4}bpogI`IBL?SDk2y0U^H_#Bp>D{x7{SJhB# zQ1k;O-J|uvyR8dSZcDqRy%rrNyjt4Yw8_dz%H<60J3gl)OrbwvjF`(}%=W?t$;|GV zxTNH-t*w|*+mm^(_>JYa4Wo+q=jZ4D9xldQSMP!sIST)Kw+|mayp%1rNm}yBupn75 ziGuhSjjXRTD?na{glJ{i%{%OPtsP58L1=9LcuQXIyNB8c(;cr5#=gf`>S4yr#a`wc zIoA|7%)Dv?&zo6V8b)B8=`PG|>XbN#*47w{kRCohZOv&C3$blk<>jpQEx8oeV)C7Q z!ugtTXwryHLfLnZ8jJgiacWp35m-~Fab=Dpb)MqAsnS#T6n~;`>+?_Ezb&4xZR4RP zfS8+ z%|{E9I_e4gj3t-$-Kvk0I}hBtSF1P@sQNK&t~7Eul`JKH$vwp_xRi8XFeEe3)9WGh&pvFe|qov@w(@>VPl!2 zM}Mp{C^&dxX69ax#o;`xS$rLX4eonTkVanB%Ia!Q7dGY|L=h6hd=pa4GoGXI2n(^7 zx$aMQ_wHTCy28Z2ciy^pS<$4kjjH`gSPoiDgeE-1=SqAxc$_|ZTEM2NqgD#XSqTrO zaIDMKs?MaEYLeY?XlGLeHwA3Q3h!S-U2luoqaa_AUg>OB0yN+who_ceyWRN9+95KF zxH~#Jz*Ccxla6gBQf{jOm+y)vJxg{I7yJ9Mt!RW8Q&rPH6O=ob)$2yu1$_r=eR^5I zk+3q*hCSB1w!FNt+U>`8C-^BoGk!#vZ?|S%m1Eti^cn=JCO!4kd4Iuvq~_tc(0~9N zeuTN$=Dc-X9h}Ffrq#5%kBRwnLOuqp4wdNc!k*^}+A^v-b8@j9WYO34uyKm_~`*u%&b9H+8arUqH!t-q$gI8Rpb=29}*_2AhT#OY= z@tzjkmEsZ->-) z)5Pf0uQ`9G33;K`f#Dfn>1wh%ksdkyXfC#)eCo7(M{irBvZ`5~k~R zn-#OE!F0UjExUs4c|GKfQl6WYC=$W%_KZdsZ;D7ezh`pNJUck~ai$%L4x&`lp~Um^ z^P^{ClEVx$P^FHt*%^0jdz)~YjKK~(GwWiT0*R zMC#@gZ^1)7S=Oomhte}LrdM$;E-v!*Bkl+ezxMYxGQKX9?~=H>k?lQvl0Wg~bY)_j z1WJfGc-;b9VfK`Qvwx&ZzSDcyeHQQ^+}ShB4($4K6v}U<%zdN$k1KZM=aO1;#+5@V ztO35MrXP+`c$Fe|mBv)5XXa_g=xV8q*r;_0PKxGReH6IWo$gD7&)_@1p~hX|CLzvB zRSS1la-Nu&An84v+dbo&((VwGO^q#5JX@@q<7`<<>VJ7u1~=gkzX}o=7GO-JO&y_U zU=XAsw(wRRFSfYg-?(n5uQ%eM?sl83sY=St)p(TIHt2dMfBpCGDDe~+`keRY6)XeZ z=9?_Y@5}1X31?3&Fu*Jlg!~j{Pzl=kg}C^{2YR zpksh!xw)-(ZK;iLu<+_-)WJo}t+kpZ5_bW9U$K$WD9`AQv7)=+`orWu+c;BM#U>%p z7YKjMm|<6KFWDAsa(|!q@#Dw({?+-*QyW%&nK4hCc}<-8`1wbhlQJ?W1_Zn_sTWjM zy(Fei$E2?R{E2&rZ!sx(5?1URgU|fuEC7@t`xaVIXC_xeBU=HcX=!os+QlyuFQg)2 zQC4vaKa9&dxu-(^0a@w8Fm~3l~4W zHOt_QU{0!dZpx*Ns9jDKE(%eN7xs*f%t}UHmy@hlK!zzxjk^vL+5aiJ#RcC+gQ|ID z+uMNLL~`M&gnK1C6RNJJ+J^{j3ci`U^S8}}ckLtWX*wII-33N$fa?OW7f7f`WCra~cujv~YUI_8u`c}gYj zgPD|xH+Hm2y3>cK(AVx$o~{)5JkT%)o^Zj71qh2{>fs;FgFnLmB}g;lORLzBR#ZCk zP1s{0eCYP&eb3-vb63Lpsl|~&yxt`jA#mcFzw+KbsAy%RwUOmC z-Zqlk>?*8!mp_+cIAq;)QL$2NsxJC8uj-lZvySDPaMXxhQqMj0*iZuea;FM{Kx5@` z6Gfu6pwGF@MulaG#BYeC3GNQeW(kx(T+Heb9=KpuDsg-;-Y`?J<}!dyhj>*Hv*7YI z1pY8pO9h@vP0c!S(!Jlz(6z@+WFXy(kSXXE6BDDSrx&0h29PS}7}^&U1^F0?DY9=F zJ?z6wVy>q!;u}+UIFRT5(vR?Qz*SG1JOTJY&UgD~7p48q9@J59Nrr!HZgq8)OiqPA zQ|Qq)6XxRX+%}wyN%li@=zrht`&UweGW9VKHOYJZV3;NnN{B#NdjHDKRy5vfU@Y2P zpcrv3S>X=svCtR&)+90Z`U6w__CQL|zBx7b? zVwL5oF$pw`Qab^`zgxk?#3VJ9MZy~O6F`(($N0?58`I~aU(e1&Krw1*dGcfbJWs(jzdC=)-@%A8}B4MO&%#Asi$N4Q{T}8Pl>A-+4%ji@$wu03Urx zpRa%)j)Z-+e*!q3>GSreU5628HdXT01-B6QaE^p8r`NHmOH^S4vkQ4vlpX?%$6{6& z`9jw+kOKb%#@DkuO^0}`(ekf!@PxyvUidFqCo7i`XsQj`auk*)DOU)jB~WY%5(hoY zdg&8RIsFZ9-%%@6)GDVcYN4dlP&KaMF^0QoL5MC{M{VX1CAMIgVrQxSh@!rsK|)f} zGvPBYsICAGUcWvn^K8Fhi4I5{+x4uB7b4+)5c58iK=%tzH>c zBhhD}){i)q2G9YJDf8%1cz?IDRd!Ga&W?|>b=tYR%d5j>3OHkk-`)I)V{)_mmP89C zzr=@6rKJz66NgtMjkEMssZHw^hLN2Ye|Rmq^H9ef?+c1KLc9G?9n;e>y_1)C6LN~h z6rA5X^1@Y}UL}*|h?g!Wo4%MJHX?q(&Z% z9VI*P%EU>-!Si{jx?~dNA$9*lE)0LKd!`PKul&2R|?m&t3snq;bWgih7X=Uh&AjR|7O#bH}Ob~laG(j zcjf(Js$h&|=uM_p^mg_3pI94aN*ij{L2AG$=&0T%ov@ zjcvxo$#W+h_IiW~{en}8QfY60A3!db^S0>ak0+-x8@H@7sg*xrAt95PTLdN_u*qhg zz}CLL>eX&?YxP_=y#epeJ3+imDytC65kWxV{*eykWkR)=YEQwg-trCmQ=g@UlOKpz zaRKuKq2}mWw~i$Q0y!8sK%$|Dxv|%j{EL_YIox#?rC? z)t^Fg6E)cM!1HsVgj1&>N5re7Bc~ixW(_k!SLMu6Z_O~v`{!!k7bGdMDoumTk78r3 zJ?dn5ysn6x3A|Grhz(Q}9}3gH|AOxwK1-)(RJ)+!4qN>!ZyKPonZc17e?Ps-izniR z|FeO|>9X;Eu~co@H)1MGD{_ou;Ec*D2?mL(E$WUU)k3^NHt#SMAqn?2O zwG^4nUMXkgZS|rWmERu!@ao7Cw~*YtdQ-)z7{?XXNJdlK)GFg-1t1yLw{>Gl#qG-J?&pPzJ{ zrlOXl^Lv2R;SzBtUOrtV{8;*YkXphfDb1+n%Zo4H+)qq}HYcpro@j0}e@9Ufs%VB! zT9*m4oCSGqTk&w<8sN8PsvX^Tev;LW1>SqTcgmt``>tLlRWGAC;{?)x0 zW>Eg-*H-}`C7s&A*8zw~Ph1h-!qmx}x68b>e7pX_>!6^(VR5`Nmk^bFn& zPc_BVQ8h)xr$Jn7r<&+RN5MDDkMMO3{eI)H5w3HyK$Frg7OdeFj$#5CX)Am^cPmZ^ zOnFTv&S&)zglXwICOU?WY|&}9_}9MKGImZDz12=UMKMLy_?fopTev23_>@%$g&M3x z#fRB2!l+I%tG6}c2Z!ho5>6^p2L}gyW?5C0T6jRa0IJR5xAW*>uR}0F#LuNrG`rfk z?>qc!>ci+Oq}96@*PGdvfU`Z*ZJpIV3r4;RoX-9Mr5w7Sp&5D@V336lp6vZwIhD=G zwb@oIc|TcjWn~4l@WebB*pF19$opo*vP zbezBMwV&UJi)f(k-S+HfH`wm~qf~%H7asLlsV&w)rOX}`2gc)!sVm|Grl|iB<4hjY z%ijC?evsy$T5i0B)mu%j*&V_1{Dk|#T9)|CfT9Tyzk#~3cPK4Q3RT$a)ptS1+K9ey znq0438k+n9@(1XH=#phShfzk}<3=IaD&6qTd+LiJRy=j~|G5&T{WP9Xr5B_@kbj5w zU@4ZyCnSxpuOJYm6$<%^?Qcrm6E0mLk@61}i=t2^~6+lIs)K z;q5R_T&2mN2`qFmH8u7S?cHr2gm4hb4H9}Zb#T~_6l%P7+!=~tw{KZ$!JMnZ2OK-8 zrT2>6_3bqtQIL|60WpkC6^931PFW`BSLl9EvUsrmyi2oiigAlMt}IUO_97Axyom`- zs;&?5=n(&jk=~6abcp@{W-ycz<_>E>n(IkrI@r>r!OZY{v^Nq$SYErUm2ql}_Q_JI&J1Xnl z|NM%!!;)iY)%G*SmQ$f-kRU=Jmvw*E^d+5e+{ZgYlcQ_BHhbvb7XD1oPdBTcp=VQ| z(l!~rh|pbCG`sIzJXjSqe|WiO4wdygy`)E=2nN%-yQPu@xz}*XlJ8rZpmrBS;$6yD z?Y^7>jV3lW7MzP0H#Y^HCq41BOlY(r`}HDF<*u)G8vywZVegEyd1B(ulX;*1} zty^c(5N+S0N)rQG{?-M4Uxg4=Tm_x8OB*ZYlryOIg<;q4;PG|a!YHc`O-Jm^xC)RU zudKD|BlE0r^u^F@^gRPIt;$Uwicvl$!h~HKWb8rxt^p6+0y5<@$DhdvL?Ykr9+sqR z3+myVWaHE^nZUxus8lM+1qMm$I&%;HkXL>1VoM(CzX37;;}VCgD+`sf%88OovwFxl zo}BW}UC9+qy61j&Ka+754ji6M7W(@;t7n?^l-;64NA(%234|)|iy|U2rfDxXVkv0& z;wnJ}N$joQQLL$R$yk1jE2l#_EHpuMp!|eXGMMj?O+Dct$LNR7e1Q|nt6p}-tX;OU zL}md2)hBD(!)6cS>MEBH<^;3WT*4vb+-!QAEk`&%S|qF`huk|BOON!hTut zOQ#6N3=Te(o~o(EB>z--eHagF zaMU&en$XhH!bSh{d0u3L+C{^N3&^&rmZ*;N}BYsj~QNFEo|$3lO`mpSg^j4g7E zG$s+P;evXU>Cau93C#&i@M+@vnN2+-JtZL{6a3;L^iTVB&xUR&^)78#@rfTo(W!7L z>ZHCGDcxqiiD);ed%j%N_D_o?3-_s89?sz(P72{S*-a)WKl=}*$FWR~i#@mPJrr0^ zdAqAxNRQB#uvdVTz*#isGGUKv<&EMg)hiS0Mz5`5;hX%Zr`DJLjHgMDrX>tGg*KUe z!VP~DZ|SXlCZdz9rXu>Ks8CO1qWO}Lg7!Z=hc@e}9}QV`rn-enO@Qg(12E*H=tb;MPC3A(foNG{Y!rw1)rJ%n}{KvDbK? z_@Q(#EwO~7@ab2>!>{M4c`DeSGe>{a_CDH_$gAS?pa+U|?i8~4_auz8;mqaKj40^l zP|ZDY#_{v*t*i&Vq4TJh%m<4d$<}wia#b2Yajvs1AF}SZZt~AUV;*gt*O1>@Ni+g& z#>n~dX#KxNw5?h`Wf!AtYbwFg)Xf1u!5$g9b#A)^ZY|Ad=(EM-H4<3M&zLgt$V_H& zv}!|Xw=Z0z!9D$lK32nDLm9~`m5bB^| zZ5|ewAb|RIdn(;PPPe#pSo!kwsIB_?=Jqzk?q0CQ#Z8liX(!Oo|#U-w*Os?c)4>1rpVrz_SJ`OpXqDq-P5jT(Sx*(~E86LBV8X>_GDk%P_qN+8nNtnIytD_BG-pG5@iq_YV z&FF^@sma5QxWsjWD1Y;ktIyHgQGP<1l@(Rhn#04KO#Qu`g-k~1zqp2x>p^HI)d-OI zDG;btX@tOLuWX@~gsd!}1E4OFF~{{9jCF>1c=XHN9+Lt2@?y845A@6Ipn}SYi-TqJ zgu#r5TCX{POjZGZ(3BEm6?ceEwa2|Fl1+ow<4;$Xm41vpDe39!)9zlaAM*%Kl(O5# zF&nOsHM{6rJaf*7t%3^pf3;cfgcH3kLRxAPTi3A@KLx$H2Ymy6ZmMyUI&(*nx9zG6 z7q!oW#SpdP)@4`VE&@N`GU!&ddxx;@(#dFKc3Q4*<1}V{a)gUeTIVVtC}MhfX{w0sD1Fs&tW}LCclB|B0UM?#BTHC!D>>%i< z>XLG$iLsQvmdO+vZuIU6;gNFeULB?x1QaHdr`l{q4z;@JGX`bN=LkQZjhgY)3aX*% zTHXg31>__kG6m1?kiDoMN~zXGy>JrE2R@y~Bg;A)bb)wR^-22hso>_&A_uy6#t|}d zyl{XL#M`MFIkxiu=4DiUw}0^X%7iA}M&>sx1v+M|*dc$pLTkg35D^*qA9bRVe%FLz z=AO1u{|J6qguF?B@iU{}&)&!D%ktLIQWI1!MFeNe+^0@_G|3XxgllbVz)wZ)Bs?5p zkU;anNwm|oUBFn2n>#KesS3ie&aCqgHy*x%PsU71qfpP5OO85+B{rAr&CXg*GFsK- z-*Ds*$@8qDxs&C$86JMJ{?f!oBm0#ChdD=mnx_pn92a9D0mYA}_Jp~bcCQ&;_59^X z*vPSH0Hr0>;KS=6xwAGi=ZV!-1}mE8zP>3m>acLS51X-wnK}^Hry;%rHq(hT=GVtyRq9LElY;Z?ETk(FamQtC?OdYc>a~h1tnM4?5S+RA z?4NvO@eR3Mp3btxb8a1Suwc%qkRgy=L4I!(Twu$VjSGS(#FP5#5=z=EQ>8~wM@)40)H zf?Z?c2VXB&;BuyR{M|z=)F=t7w%~5-%)rCeM;YYoUxils30u=DppE#7)KFccECPb! zu(ozC^x~_wf}=irwV^ENt0D42J6eE4;06LjR=)lNF!(9M~Qeq_eFJ8*7euyH6M@QsYE z_*)-UL`a`@?sQqLAchxZXh_(ZGgD20iw&s6<_&#* zmy~#iFT!Q(u#1I=aE^Q4GV0}=*qUsV6zeUH?W%daKm48~Q9e^)k$V|soA4={u@}iK z9ldbJnC(Jsom0u4N}2D;4pElDja|(LKlJ?^E`!kc8`~YDw|IimL8~|>1Fq90f0#<( zpD3~n-2O~Z>)6sTtJuoZ3FmeMe9cT%=Ih&w*Aq!#IgzeL97^qC?z|lr_Q4Jn$_4H{ z=zZ8!e_aI=!SC#CdyfGVSeH`YLV4L@qepWH?z*94MtB?9AC{O%R5iElXX#Gy!1X4t zxMf-{JHWJUq1X%^I4rMr>DVm7jJxWVE#|)VIxx^QlPy5)>-3{nPcc03c(j|lyWc9j zI6^3@Qsdmu%d3T)@aK2pvtE(mAUz57kpK@x642MU>ZnjwS*q)C z!yQ3P4Q9dez7g&d{)et;8lLd5;5X~>@ULMCW%qb~(eVEFG3L`#U5++l5`Uaw8esB* zjK<_upZyLJ9*Z$?29;5mj^yg*R;zAW?g6k2aTPv|juPln?z4R!Uw&a-9ebR(EBy@4 zFu(5$1b>!cvS6d=HB_Mi_vxpePo-&p2E z*UW8$@J)_ZHDb?c{UQVo1t2<$&ikTugpl?*Oi(WGcNG5Nkr*OdFb|WG{<`D|`Y7=3 z8^_<-Zwt zoQOO4oVn4wYrd$s;NtI&=gSOb!u|KtMX8M)H6Rex)O`7$@37c$J9=48s5&7u&bpal zq~{h#7^AGiwE)b|H|A$}9F~`V=ea)hD?XykZTy0^jg8k~gF>+u9O0vm!<^4m70VZq z?Q^VIB-Y2<`hCjuKnLt1M_bDIb&34BlzzduFvY8yE>Jv0OB(wdW+2Ux@^&h9Lyh`Gsi!JiLrk1O2M-!# zzyg8T$c@Uw|B_HBxc*mEvsmT{QjwDRg{>+CL^??Wfgd;$q2 zdo|M8#?ul*+;hEW=qjppB&(f;CwR*1NPuTK_QY2ArHKE+FPoWR2*K!wCF_O1@wm1e zQTKI(P0cuqA8^Ng#L9Cm)3EUgcPH6d%aqGZXu5yI=XjFMY5?^*5jBC-f6w2NpC2%{!sr82=M?5t%ek-;X!DU~2uXL|oL+j}x!x-`3* z!{(g?(+h<=XT`BJHeg=>i5>{jlX;tTzt5K^bhgZk9)lhEbo3fcpJw#5Ah8Y59ycJ&(GW6 zSJ^}>5j|~DS<2U1;wGfCr=2S%Qm}qF$y;t_QtR;C(v6k_=Jl09? zb#bSm5Dj*Gm`0dGNewT$>!)GiamQtjrMK3nksw?$QFcnL272o-b4M(bDoIk!zcTGoqr#!1Tc3JHmM{*C>7Jxl(sG%HzQx*XN`piT;EpN z4?UK^$)hO3#BJG(&{4W)pToGC0)Wpod_aS z)t@KMR(0fZq&9~CsRtEKV=o0B7Hcm}36WCk#i&t?;m{^K`C|{8njFuGE1Nz&h&5}w z^N~!F4LU1Ha!12vszrjYTAK&GoBuQ)cH9uvoe=4 z?Y~MwmDTV-{;?8q2+Rr9^e8q}1FrZ^uUmVNPB}gO7c>J|iF(g>nRik(3nfDR-*pz` z*wu~Aij-;iZ&63?Kdh{naZIanvODv0N%g!}G+}=r-)lEEoxn40hH%fF-Pyw}SzSN> zz6z`-z!bXOhP6TF@Yw$=h^C>*Cx6jC2BDpYv}F=6@~S3}u;HIBaFT~!s=}YY4+4e_ zn?j9JDO(HAQ=;%T)NT$$<6~F{*Y84NiTko%-5M)~Zi3tqA?BQok5IS#=L(m+ZO`Q> zAZSL_@}U8Dp|V zvM2T5uD$9Ue0SHmwhiQ%>Y}Iu=Y@BfNHU1OkCUrHc|lY0Gxs#6SqO=$ksi@ z=~rzK#SckHsS=)JKOdh>9*n8-KSuzF276tca=i7mn{II%Igyc(Ad^-76iX>GtmChTR(q>-P{EK68F7SZvWyhT~9u}37d2g1qndg zIuhN(MWNzvuf;3Co}f#9-?*d6VQCR1`5a%NVbMmM9%M(j*5@?8{9F3@SNc8*49idP z6(G1ktOp3ZOZwBaq_-aKoH~Be_h9U#tbS$b{9U#Q$k%ooIgg&M3`sV`Pq7!8s>(ay z%@PLL%(T!Bt@2h++%ebt>GYKH0h~%WN}lGamGHatisUew`1bTqijKSkCf4ko`1#lK zE~l1tvSP`i(J#IS`h~FKny3kU+hh8Q#=W)>C(4c%#p z6MByZI4K(85`6Uk?g~&326$Hr5Pavdli&2cml*019oo6bGHDEa?D@zXC&gayHpKuT zZu%!jIwh?VqTl-@kyUpU(`e&}X^2QFb1ouOU|%D{R321yR@vY>23j^x382_QDI?7CygTzs;#!A1pQWf%rH-R>tavI;0 zIhT9r+i9*pb`uZ9ReWZa3{p#UeB;#}Y!0F#&Ld5&xPFR~IweAdu>OtH+}q+=-#QTx z4gg8#yos$-x4~oEoh3~59OvNrv@ym{o^zLxf#Du-NP9P8sc$Rcf6>99W-!SHy|!y_ z*VsNOKuY{O{S8v3yvJwye zJNf0U-h9+Vh5^n*95qf$@Eew2j$($W+@&%n1)>JQ8t2b92jkyiYP~ z$Wy`AHvT!V6T%bq^5E`DwC0+K)JJC@nrP;x>gl%H8~!&YJJ>ICl^+UB&*h034;UBC zQd2WOoVg=6Hg; zziIm(-|J($_q1GM_-NQs%O$*E&AOS=#MRnnln3AWo(YBeP%`p(?G$#1PO4^vS6y!Ql^r-^tGeLACpeJbjNFXCw8Ef>(_ba1-v_DTZaRU%A$kcLPVJ zl);>V#m@`bXZk#cJ1z;)Ol7`j`k8xRZYXQ=@1jmxmQu5{vnAkp4#Kdrc-<7 z66>g0Z{I7QMlHBS4xM;XIWXacn%*3khP(3)&=H!aQQhH*Dtcy|w(zp9*D&ZC*S&@M zOL`OrblD&f4p?dT;rOv|ZQIJ)8cWpAy*=XB4kfO-Tv#BL3u5dW8yoL&K1p7zM}_`x zcmu@!zy-x`_%CW+IdM>oWg37CG~o7~`G;7Ql!aOVvt`BmL&xE#J&41G57$zMiTiV} z+GvuM-AFvIU%;J{+p@|y3{Lny45H@zbDTon;RLqSAdO6sZe#6Kx+KJ+e}u#rvmecFAo zJIm#JyCHp3E~2IcejXc*#*AHJcNOHb?211kUw`x+69F_IBvlJh<4>9zp?-{620PQ# zxCW7Jj+`77m1${4;mXWW&wqw`S7Dk=OO-TC3Wo3blvW8BfLMGc#Q9Aj-+eb{$)2U8b)3U z$m8oq-;okkhpokz#evXP2<8TrxfuRRdS%J6=NnpN$_u2~RMP)NXo82HUUcr6U4(wW z0Ls@tXaB-Ix6AYt77%R-xxfdK(y z;M@b7^f%){>6&z9nwPKdFbKeE0{8vE_`8saGYB>h0s?34R`|1zVP`i96es`CPLJ2u z#PEUSf5Qks!sfo~HqyabCr=yRI*uDk;=D~eVI{ojBD2zAgppL#UWe$0TKfhST58$> zd~4SDCyfT=9IER0Ka>;@r)dwwxnI>?0@DRFU4TmOh>V5C8*{+wdo48lNW@}tHK^BLC=-${C@;fQ;O98t$LSSwXsrL7M zZ2(B!?E>==x7VlINrLmgc7*EO$T-;n3=IyEzIC?;HoAC5>1f#V{|9IWW(kc(u2N^xo;muvWbYAR=0TJ}{+?*b0wt$-$tUuQogfI>eeZJkSr&SBmoi3tiwvdtJp)F1_Z?KK5nv6=?d~q-- z5JfOZ@ufKQ*0@gJji-HZP-M7Hq8rdoT}roo1oI}%Gu_W?YZh(%;=P4-Yd4#@k6N?j zn&Ftoi4x<`7^VLBY5IJ4xwlrR;N}+!+&d>_pE_dxW5)OCpC6KN=(|mzPVY+M#%*wM zPYa7ce~u$hgrunzt6Z@yq)|&4H4dknjz8nz%X4+B7u4mar@6>DY-(Ws#K2R&8BN(87 z7|^i5^_##}lL!9|%Yod-Cr(RW)t05-|3(ofE}S^YDBNzAWahS8p#$Q6$ZFO`VHf2^ zwkV|pULmMW?gRCd;W4|QZmNifE;tDTgr8@1K~YgX{LVGCuk~eYwGqU(8n-u9Mim> z`c%&$Gf3ZESs&*ymNTWd@U|oMRz)~n#s6!RH8Wd0woNG{z4L?y#w=zL`R8Za?j+-V zF5BOilnVbjuU}tBtgq{Cp18}!pYrc-jTdK+kGNm}%xh?k*a~aJEaWM@=Oj=3hN{PO z-eC*se_+i(V*`c@3blX|3&d`Ky!y9q0CEK(klB_Y9?i?70{Vghj|1w+vI z2%B+iEvLR&`8L>J)ci(5G%`^TBM2x;t4SRf<#6&S*FZ#V=Z|c`OX@}x?XDNUEf1a9 zU0%24;3}bqqBu5qox~qVe_VIZY|1@gxb0I;#dLUm2}Py&FYX9IWvTleg;*WEkFO!z zxWnHTtDD<{Ij{RPa8Xp`Joq*QnhN7v!qIo~pYRE}ofhDvsj*a~Le_#E+Ui>Tf z6d*6^+w2ND!DYq<1f{fP0qQxt;lX~fx<;x}&oZ|_;_uFp@52yY`cFc@ zn*?)68s;}UIW_+cu7M$<{d-a+NjD%^2GsVZjt&r{aijNrMn3{V8DN18DFrQ|l>b%x-5n_n4{b}sGC z{&xUo<-){iXSeRXNBa2Xt&y#93=-yMCL0-TXC9Ds*K~CDfxK~~JE5ephL<3_rj4@l z6KHxa^4^2QthB(07mAM_8VDRSXVqlxCJ6#|?CI~X0>NGG8|8iY(&??G7X=Z!m!=E5B>g;NF7MnVd9O&Qi90VchNWd$d@+8%fq#R6R z;7(M{Ic;j$)zuB~t@yiS1*B6VP#|*z#-Crg6sWJCbMj(5=(~NkF;i=SqGHXpck{IE zvm)95EEjrByg5*#$je>56u$SMsR<+Zh%(PS+EL3h)wmi3hREuvL3WrrqEF zipv>_L)0m*=yqWm1944)6|WDoFazmMNnivSTzGePHvq9`BV}tGm4L5;Jq_|Yew~G4 zE~NLsD?n=o><52;kR&;S+$IZxVJ1MjK>)VWr_Rxg^+JxAMG=Dg(f>H&GRT7PHd(|< z3WT$|SM9~=>xUMpZDxP>`-=nFNj1GT^TPS+cAewO#5ws8UFrG3s$2N`PX;Bz!ddx!!IXhZ3X%a;NMXL|Zy{}xpeR)rR za(U2aFSJ$1ytTt{;xP|+AY>`d~wXLrZ8T;S%5ZyYvnspXhT3C?B zSd~*QlMhKa$rb}L3j{80UyEmU;~K{C^f;NT`uB zP}DAs|Bt$sBW2uEiT+w^^qVs?9R1oh;@H8*`7ZS;>3`ya%$mTNC`_RU62WfjvK4*RGn=%m8Lc!0ZK^>Vl``i_ko2 z8k9Ek&*!?IZH1gZ^0uoqF`7^GOdlOl1`b#^m8`nCcZ!fG5v*|}w6DT{H2DS?6YRgC zxYOBKY_~UI!}6HNQ$U%*@i`kUFYEVD4qKPDy{USLde7eltSL50f*o{;&pWe$P;beR zAWz#m%jP)T`84d4m{Hvq_yAWlN85|6m0vY(WpW9py1+=Zu=s@zvAIDAf!XO%Tg8S& z5FGm7BHaTQ3!)ZMQc?hQoGtwtc4#Xp6(I04acynwMN)75aeJH1kD+kr-oZhZ#C^h= z(0kA4|6&G#gSNbHU1ujum&u1o7W+D=_c`bOu`|iC5~mVPO!AQ>MM85T$#Nyc7yM%Y zX-4;M36Zk5s(pX;4e?2dCf7^x*&lmnc^u@}DRyigVK)s(A6-D&B+j13gnZHo{M~W! z%$XO6N+679E7W=HV>o!hNVLFr`p_r}PtltAl!w(Xg@LTAGZPpSvC!_I>j?5&$q;en5*!+-Ib|$4S9A z>|rLmaCF2`3E&TeVPY(WT~av`#**J#1-_6Opj!_`iz9O;?7bxmUBxP6@FNtcy<8QYN+o;S6|R!#T}mrXu0Z z3jyWm(W>a}_mBTnAq|du4sE`^FB(wlK9zO=|Be6{@*0nv*M}b5zpbI*!^Z*n6tG6y z-d)?NuP#Wz<_Gw0=c2{>(3j{-5Wi`ew$t zu5&^@kq!y2RvJck9|`p#c}KeK>rOY@4#ZL``ltHm z3jcAFJdeK(I;fw|zgT&1gP{zQNn~r>myxE;{=L$SLr=pSK2h2IN`hY7r-0||QPa8! zjI)pG5b`44Y<90R}VZ*vR~zs?wyv@pHN*J?i0KF-4sZjQF4x%&#WTnjQ8(fD(D(_6^P8~xJ2ZjVv@iM`WY(AHcI39Bz`w@>!>QDwQVdCebP zD8EZAuXjy?n6E`P|7@Z-?bJH$S>Z9LvtEH?Bv&THKBXfCKe z^d;>M*sA&PjD^3*@$mAp4Kq2e*?`>qeAdHp5snSzpGCAw7Qf=E6#Z1i;8^qZEfkMI<*I5VA+p9}naXIyQ zLGDWnk%=PlCoe@SaSKncE_x*@X6i_K*?lr|`afAK+K2U) znK#=!A&kPuNG%IMLo)SI0m&GIkN}_iFfOL|%PSP1qCx*&G=by}JXc~kn+6FXaVT%U zi=!wAVp=HMl3ok~-x&v9dUfnP)&oL~7x zbn01T53<1LI)DHfXH1_IyVJ9OJz(qna{qVBz~Q-=fz~q%J-Hk!T`Qd_U+6!Myy1;# zV&%fDhuohFd1rPBg$$RopsRV>r=A%_f9s1s2OpSMZ%54Mw~se~6C6MZKxCQvlxg@R zK{{P8t6etq8E)H8lwa9i$@Eg~ivAr1Qn@s`0~D_-8UBmftkDP0)GD2nnEKpaBIjQ| z;=aSHly(4VuDU*bvZBj!=MZ8gK(nxArPZW_nLfDkq%2U7`d`!VbHTy8f-?FGU6WOb zH|^#htA;gk1jRJ#dd%@UXqZ`|y^c4@1JB{cyIfZ~{P=8jL%W!jUi{n7W-3NgFGB_e z;`WNjjWo$b>~J@Ds)3OQ4u|(`8sCl9ZIR}`&hm~_K7KdtIYI&@0oLK`-L32Ibt{Ei z4#nKb8Wz?AS_vi1kDy~2k9Q1b4Qe@~^XojGK7C4059U3Albe`2gvSWzMV0P$GS6%N zw~jvV3&m_AT_)u4QM7>Lzq*v)3+8|WGiU#)KL~@+ODzjKSg7X|R@YUFsdGx&>SW$M zhjDJuH>T7XKi{@`u)qOD6uN!F!9>y4yjI%_|2#uW9@1+{$-6p1%B+~UvEs{yUFl(w zts~6d{N5Ww?r<9ByW{?x7urrSNK_^WCW;Ycsng!p_P;X-z3|rabe>58f;mwvdtp!woml3c}=CtwS4fuZ@_czNH> zSP92g54?sa&t4`(Wjc-A<~P-S9#pQhQB5hfut`#+X%wG3KW%9c;duuGZB{t3Qc-O@zcNPL{qX>G}|qqR9VRaPLYR3y`u6Ng#ZKvuPg{s zf~}QqxzI`6k8T@5XMs~1{GY#`sD1lU5JKCluQ`<9xwm-Gymam0%8Tivy3OPu#=bg8 z2;@l0?^v((n|$b z?o};&4~*Ou7Jj3&E-Bj}x{H(gfHIt!n**^qyxA&yet}vj>FlP>;-()k5P$(Ii)^?i z_#eo{Lolv`wzSv~b`s&lj&wOj@%0&~DM~)b8=h(C!q0RS$Q`X_^Awj79r~t4 z$d#M^6pNO9ObeUUMU2e&GIgnaZl}7r84gBSQ%~DzOq*Cg{5kbm^gEwjF-|#oV9i9k z{-9#rEFd-6gXU{2JxQcy1SPhCEa&2-_=}ZDu@5q-ApyrZiJMkG1bh4a)k~2;v|7^x z2(-lOsDr*pS26l7Yk}JtDTucMT^W-1A(4C)1(QP8#>R$aXdsFfV6s3oI8enLsT%jh z*l&&+Po^$L=tv!BNU*8RyDcc=6$=|y{7a*6a|#U11v36&ke?QA^F?+sUP`mAO?#@& za(OE2nTBgy)a9~m){s`-g>Qcu@f8FCz$;Kp4%#)`UWY89ZKoGug6>INgC|NZ-ZrD(xLN4mRCJ|i0GI0A_@KG zJC#SLD!li>l>vF`>gFcfyuhWzH&ukmrKIlyKQC~@W@kSE7r?GygIf3Wn7*Uj8Mjc* z(#=T&xPNVid#xr?+qPCBo(^VIZ|u2DpBhioX(>4oV~3jjy48rE&POZ%n6yP^U3QfT z;bMVSwQX-n^us?bWMEQxPjB6;?2$f7k}^Scva%h&bg=Q0lREx7V<33xV-yb$_#w!^c zD2krzMC;imlD)Z;9;6-phSijN#h&UwJo>X&#+C}vVYdHIT@FBZf@Tw-M!UT*>m*zn zlA1@?>~)WM&H%!xmSK&N(YsF{poLvI7>jFqw(9a2mpuxJ1DqV zfW&NEdtRT~SG*sX?b(&!LPybB^7KI_gxK(S{457XX=W3v7n9zGs9&7!G}D~sg!q@c z*0jTn4T@@8qon_E^JNCcTsjRexoNcZD+&tB$@sI7owgcP40Z2kspHP-z0~!n!KOAQ z_9EVqyfc)P%(G8@|2btDS8hloDdHnHbjiZyr%Socbn%>b8im6S)Mah+JZ}Uyq)Yv; z@aPH;t~k8T(S$RJqnj1lY+)T`S^n$*i=yx2%b3HK6e1~qX`+e=O{j_5sy zSmf;w+O~)0#vF2cZYDK{zl3-=49+;c!)pjEAOj|&va2C2{MCd-%1mMnA?g*El*=}v zwrP!bbuOnqtu7-=X~JXvPltpzJ{gl=?8$t&d0Jj>L!`{G&Go}a8shn1jS5-HUA(nF zu5@&&v~A|J-&_M;<&H5GmEbsoulp>LV&u&)V|_!e*nVl&dBuNPem~Ayl>@aO-gTzs zhFR$(r}cVQ1emRAhqOP_O`Ro@VTor^a_TT%#qmxxN&Z4EVx`Aol21UH*Z+f;BRNQe zojmGUzGTTeltLp>ar8RiFYkSjvbhf2o%E|$aBe#Tu2Jy70djA#JurcHUEvpA!b23T zk=Er(*6PYi{?(~6*@xo^Rf$B#2bk5sE28(J9l&=}^{2o_@e`wjLBbI%#_HH7lUTb# zzi9W<**Y`wK)&4lSWJh=qIU_zK*S=Cj@%fKI1eS{#ys_5pqmFZGaRn8>_IUaewoL% z%~n8_(2vl+YuMn+L(mNqGpp})r7We{lsAd|Q;S+P>vfgx7xm~FLulxmIuq803*eC2 zW@+>&@(P7FX^WKo*P5(3X{CBhr_R{T7d2(hcN=iHb-c?NYe&i=N$zli8(x5A!L7I7 z$4qPf;95J<_VTY@bV@8O)DAKtmW#j2FLJrxc~hcGd3pg` z%jAL!D=?*Gs;8NSt(=Xa99=o8kG?p*%}YB!+L*}Z3vvwU7ta%RuJE}Hgy|L4!4o_+ zF$~!DzaHJ*-u|D7xp2=`mKYnn{j)uwm8@0X!GHMBvr`}LCvFAeFcIjSR_FxfzrWGX zJXvT(qxJBzooqrq2zh+Se>TOcdUB9na>h;LCDNUquueq^DD(CaLrGQ-8vV+(e~nK| zahpAH!h=|CM6IFhIx&gE2NR+ssj}>r`B9Y1_oEZ(_6I^^lj$dE)baF~PNvz3qV4;y zjMokiKP@a6-uuv5HrOvT&)r7_-m-4wM<8$=^aEF<6q}TQ-vE(?W^{fe=&!-Gb9Q#H zIu$k)(u@b2>|QV=CpU&667-YsaJrPs&Htx;oizkrHt=zL^+E_SPn+eAW;PbZ5EOMI zi5o?mW(#*0!W}hZVW}2~n`MI+c+(v}n-+|Z@q8Wrdbb@YK6&W*_1764lq6~3Z+Znr ziM?$+yhnfK+*Vl!k4bu$Oq*R}Cy9oRJ*2T<@?DCE-oW_moi1FfWy3D)4l8D8HnKo2oH|(wIkl}I zGa}Lyl>Ym{5?4qfFq^v_Ixio<@e|@S&f4w!L13#tZk!pJWMF8G4$8jRkN6Gf^p?HXq1$rBbfkoVdC%fZL6t35mdsKY+3 zM(OF)yA+EP`>SuKyHtua*R_6pm~1yupzQ~2tV1*PL-H)wI1NiEvcn*|gHu=0LtIdXC(xwYgSG{008*u}`Rp7s_SeH0(QK;06*JKP)<^0g`8| z`_Cb(kT63!`q0sc4jqCN=6yf4_c}W7Q$)XvGX5%#d~Zlh0;rllOH07`1X9xA`>S$) z<_W{z9Bxd!2)H@70@JvSo%>6<9ZksoGt1N}Q{w3DQ|Q&uWaCf-O=(0%WoG5o()z^` z8eIpwKAKPkvuR+)?3gOMd8m|z0fovs+I!=kZUJ@L4oCso_iwMg5LT?-QQvVzpcP93 zYa9dx=HH}RFe(6*+4ls^=oWuBb8LVgVzwWbUqJrEcueS{NdMc%8i*IrRrB;*BZWj% zfNRdCGws(pV7L11V*uLzQ8;I_P1mBSBD+%MNS@ztSFlLL3qtOr*KZ`Z?*k~-;IV^7 z+V7oL>;;umE-o(8C6mQASbeAgaH@bX-1Xtd`7BtQo*0OQL$;{_E3|#-MKt|wgFSDR zA%i|)sZM=t1`gD2O6rWvfm*TXZ!S=kShnFtJEEo2s;SiDznN9v@85!s-WyzVqoYn@ zBci2s79QuQH*;$(gO5DM$s*{LJ3OU@dAx9A=J_0z%q%nLLt&D7^`UukDfL04$<)ow}X6<@r>$3BWqFjKD zh=Hm4+G-pV8u{a-fj2y$-8j|UPAKyN941q<)mO~(?M15H4K|^e@bEcg7K6egza>mQ z1nnvlvphraLORyeq?2^ix`TmSCLc1-_DYNl=O)!=Q>ba&TC@f zM0YV=ISwQ*S@Lqnj%ucQG#++nyiYMfo?p>~ULmw28jL!^_{=wV*NW+)Ek5;I_(pU; z2Qq71SLr=6GkW@4G_3Qz8grk+$xQ^ZPmhDX0N)abPLm}%j0#=n=jXG?QtIzJdC6>o z=|DMr=b$V@zH|zDwza>1&F7SDzJsrngCgm7UOh494|(=Xc|z`TX>|Xg?6;#fzum5O z&5t(9Aw0t_rMQE^q%xLR6h^;>u)p;_PLTBSXL72y?I3NJAF`>=TN}8k6Qo zT%de|+Yy{0dUK*^vL>w|4B*{B+7rxlI&8(MrKYAE=n4Rtu;&yULd2O8bn%!2tpY@e z4O_+u)!ZYyHl|IEaW735KJG+AfUkCx@d{>rMiI7!siC}4AIf4F;FnIDK&PdbQmRm4 zebw$!_{*>P{laK^R>AeJNQR0T~zLzm1uD&TZ6UeR55M%vwD)K5zIBgjg646V^QR zKam^QV+KFyb)S6KXCWdY0wI3cDsU7{z5E#H+&w%!&%s!PpII>Pk6OsH4$*!;apRJ< zvBqo12;1DpW{MTn#qZwB$aKF{WCiLoyqZsMYC^7DsiJ&m;n!HD)bK27T9HuE>;~NAkQn)hNgLBa<7NKy8RN z3q@@9YmAC4;z_O~cSYs)iA7{6McrYRm!EHeMzm_K_^pus=+i7ne2*oxYNvm87MIDSO<_%tJl$By^zotBT3gop; z(Bo7XwfbnI*LiP!NeC3+j!42yT*aHM99k|x>N5COdW0)L7^Xj&3EENqZyF0|I>1I} zc&%lqdBFiU{E2bK!<9yxjO#BnJ=c=6gpytw;PCtw!oL$N+kVI7hw5b%BItwl)YSvd z`!({OvizHk^{9XLnv`+)HD9N`)ZJh!wW&{Q6l3Bl)CTGaMx3rVBE8vAjP1CtE}JEA zy{CV4ekHw*`W>$Sg(+Sv^RO9$JQYHQnQwdJ5k+?0F(adZGIxdX`E9#-Pj8@Mzb(Fr zmAZ;JTjMB#s0RsVoS>-;kb#-y3cj4Zq3A@VtSlIL0xI@@^GJtg1=SpwPC>q3)>H=4 zsgVM;M2l6A0G2lI9Dwk^53C7?kHO$a$3k={`~s9~(e$-bU>IXBTx0@0UY=*+-5LN^ zmq}au+xt2C+_bEh3jM|a!yfVzgevseIN@0dP)pxihGhjqbCOu={92B*m+U++)uJh- zhhe7cD=Q%m4b4o`7_HBtxWTU57We`6_yM{7w9Nc15GX9n`oqcHEEc{4T`$hX2H&fO zFTE1?Id7=ysWP;(+BK9?x)=<<#}n~WQqd)t?P)>KVp%-G3Mg@eIIp6Z2>IW=mJBVr?jQenubzGDa#Tgck& z)oD&q6N$oB*-!3_LQ3Di8gM)qNf1H%QS`~Mw$|>#ExQ=&qoy)IO9R+ozw>GZu6Mv4 z!OqV6gqBtyhx+u_Y`jsU@l%ihOH0_)(!xRKSjso|)%FQ{>5WZ>Y1wtxS}79w{lpuo z-PX|15Bl`XCii$cha<ZoXP%@Fi+^vCZO;&&t(Xl+fFtUde^RDR!kvOFp> z7J1j1a4WQ^(v`x3Pa@#z*Vvf4>(lQfP~CMcGDh)mysMp%O zoEhFb5Ro7Ot0OF7Z^FF*P3k&w^Dw^$~Sm8L}fHbqoaP;LrIH=)Ym_ zpDz)s{qf}IpRJgs-lu?R=o}d#EYsfVY_TGfp3}Rh*A-*lcX0IS=Iql6z1$4#*hgH( zd}6bGzl3ZD{562pE>#x8V z+5x&-q3k3685ZX%^6Rfs2KDgYO|afcWu{_wvd>y(l8FW$0yIeAuAaDBm`+7JB{KG& zoHdpUy|x=!DkQy8eYJ+s#=m**;xVuh-R&8oy_`%h#jDN}hovH&+prVqO!Z9eYn&eQ z**o{-0MqA8Q~H4Vq1g%?W?7#AoVLOvkWdcK;vc3qaZT=OM|lH2P#paD)&f7rq)(EW zF=kS-z;fEHuk?wr0B+1rG51yfv61ZAuwy`Xe*zu65rZQ3J=X;|3DCZTs%`|o;Tqab z)m&&8!f(H`A}a*Zjc(ES?>ZT7=Fi31KKPeA`j^z4J_M$a{qb%e2m5#oZXbFyM~Zq+ zjugYZw_aiuvQi}y4=}r>Czn9sD8U$E*r5F!?NR^HqrB3suCkTAc%Rhd4n^6;M=H9T?*3jM>Y84Pcs}J{z-bQwjpC2$PcuN&uV2UtCx_Bch{P+M zV!-*gV<{#oz(Ldx?wb`bfSH(>sH21w4BY5~Q2$%}7jSf7jI?iII1?UGka52o4FLhp zx5-Jfu#69fCu)i*1C_N?7R)o@7l50sni5)kBbfKI-Y`w4P~C3oLoxXf)d!Tfs)s?S zmbW-Id-QJ_z9MI=rn+zEY){4Z2kNBUg6cvVX?w~x$GO$*Mm90fR}}-DZs4&7bgpOI zu=`X%7#o~c!$3(KB{NEoJu>c^D!dVryUyE(XQeR0Qx~h*FEH?W+-~Lt4aMNWbAt0C z?OaT`Ou)mrSg{I@5*9^dve6HNoTp$20GRyuJi7Q_{fp86s?@UPKxYk9b-;LNH0c?h zmb1;#I3y5ue*|9P_hoC~oj7Yb7tXvo8Pf+3KCs;aTW}pJ<8i^!i@y@blig|7ViCe5x=IS2h&s6ghQaRDDCa^wr+= zq&l=4I%EPt7Qp{mvTBDWcD#9yeC7$S3^FYHgNDq?CEcM*S)V_PZ4G*xsc70$T>N)q zJ982}v$nRTzm6%1%F12w^LYd8;UUjJ$ZI=6o=q`g;fX(xw8@}={7rrA!*Dbm0gQ3~ ztExbme(vQuG5z5gF1WjHzx+4e;le7z=r#aTf*v{bqfOs8BLQD!{~zU6Q?q>KEx4~> z-|y?CBD2`xreeM4-;$-Hx@Ii0y$d)-L^PJV^KD+?#+l-^Og{~LvdzCi^g2cE_sQ<$ z${R6YFa|p2CtPrh(`f>Z_anNKjjvp+&)n`$5ZuN>_$Qp*~7@8 zp-5%2!>-eRtlcVPd3cVwP^@#tAcm+!G?k?B9MTn&J zV0Iw)&q-S_u)7a_{C&|6;KJeU1C4OxY9lS3H8$oYFoFXo22dXU^UAni(f>Mc27Fr{ z0ytyg=uqxU^=;uecwj3@BHwN`c)VliB_Q+x>`MY7;yBJ^ohX~Q$al<)bmc0_RV z>;(v++hJMfBn$+sc=aq~WP`(9bywwB(fUkc9E?Zh!(K^4XH1!By1Lc9+EvQCVpVG~ z<^^n(`n(4+a_VX5FT*yYD*|@>Lg!fz#u|9xKc=}3NEx%BI{i&9$%Z809>9XKgnftm~ zPYYG29)Am&w%a`Z!h%j?Q~+%mLpk#q`(T>34FS&aGiA+BjL!)`_@Qq|w7@NNDKnQ9 zuY4vNMa^M)2+%tdWuYrrHnIS-+_x%IyvzvElHHwKZ zaJ04!S40$1SN@OCq^YfXv60XyCS9hxxPnK1AJW#$+mL*=Rk*Ldy?pN=pvjqKL)Waq z#_~;#8-icFH3#lp(1QZdAeHXBDEsdZNT=6;fcu|3GM&sn=`@|2eRl9xw8toVTd<` z?A#J8dhpQP4KC0vPL^Yb;?_>!l(_{fO%!NIK3JjEr>0-}T7bVfVKD&&+&s|>WX7%>S*UIHgEuwVhrBO~M|_18W5?hEE6 zT+X=y5dzOyZ}s+6v9lU2HbfiT91zL$IvKQa)v2kWiCUP}l<1uDB(^MQg z6v)2ghcH7%5VQtqBAiSJNOuxhYKCI=$s9A^ z2*R+uB2jriI-04iB%nFV+R# zW3xWUAcZ7jah|KYiYeVB!$W(;Pi1(N)P1VKiRfNo(Uvf*YSY09R1Hn7X?cUXLiL7X z9wnSDt@5_lP(N|@3gQnZ_$A1p)}xJV`S@iapZxqRN6!0c(-=psWw}85lEVZ#ArHLdr=iX;E#zWP>r)F^nLC` z$nf#=$K=mka1Km*_=E7OX-f+C&!2vE%Mo zGM&LE@$cl-Y+JFmn?JyO9QpSL8(}F+Z&BK2RB%E{=DLP_D@o(_tH-3Y|1Hc#b+xuD zkGMd)jRc->ZeX(PogpsM*e zkNIuVRhY@I-rnB&%->EA>4Buk9yVxO8YtrrfUm9NsX;TL-#}#_v|Ag7*jk?jM7vmk z>*Mk!>FpgB+C<&>iDVrGX?8>6*D9(q0J!Y_gFgRb?@V16sVrISpDJ{)gIiw zi(D!K5AfzklGa++1{uxVJfY!XA%oB2z;kny&;5l^!a@aR{N`2ft6nRN$M)!tDpeWd zvy2&d+24>IpJA>jFphta?O|d!zN5$|8R_~yYQF|oxXD5S>mrxYJ^CPJ1A1HjvBL(1 zpC$nI3Jllt>f~exmmW5(ZtOft_zd8Lr6ns7+SD12JZG(PQhI6de3xA-hmZMa zn4jmqVV2~N*o@x0)P+5608-woXY?RyZts%H3~X|Eu%nz?w#1!;!%gYh0_jBX&FV+S z8vVSy3`dXhoCy37(j_P#GBqYbl zyW-(`&kTm1u$WAL7}=bCDvf)V|Jmoiy)GfEfSw+-+6X;vI#!XuNjm=dwE7S@^1-;4 z;ND%p7fXj|T+mk9#i;Z4y*oq6EH<9u9q#fhUBjr50e zMQjj#7|9rMtxP; z*sj$8$87b)Qr^Ul#?M)H96Z0OqZ*uw8qvVqf~$V>&cG4VfC0**Lo%XHn>ZG=dm8WW zndcCh$Xbm`-+wwdVf|GSo1{Ubn2k8@(^^$~dgn9)JusPpq6Ul^Rf^C%!h#SHdhnLs z${gL@-Il5sDm2LUdt~YCt0KT(E6i0X2=sc;vcty}!PlvL4J@sn7;S_?<$?WJ7Y26` zdw86u=CJOqLKSXd5pJ2aDf4`pn*#q35}416k&ZWAk&kV~RXf9b6#SNK1>B2zOxSNZ z%KkwgwftNLGEWxcyKw6-v~a#~8rgj&RGjj8Cd7gpu|GkU_ASz##eTmwui&A5;CWdg zmH1{*JGR&jT}5}r!jl^scM<$ovDZOw%i_=It<6UJxLY66IP{73dqL!GX8}t<@@nfU zQq2Wx(7;ekjM@Svvw!3fB@gUi;LjlJ<7_(cdK#!iNcP(?U!4P)fS~;CT8gW4M4-b; zhwYo^Z?Fo~^xQce|8Rv#-xKdomN7f7U-Oo2&$0hU%4yN^2fyuo{m6p&W5~1>-_mN19 z+&>hx1UGYwv*m5&tGIKh zMdI3Io(=qvfb9pV5ZP1_l6=e5=a@+~3W8>i)?>C~pu2GvB zyV_!jV{@u}5JCmS=w{CTxx_E{a97QC!>2;P3RQHq5Q7P_k>AeBJ*0_XW_XRdvLk&t z;vBv{zrOtJZ3uUW3t{shQRUb7c77VGuFsvG%ElVRpZHPCz8JGj*^$gkPAkrqJ6)~ZtIgz+EE=)0|Cao1PDo01 zo=N668^w}IdT=-i>{Q{g(ktC}2enR3==7&C1ZC((R-1FJU-#PwDDS@JO2lYrY+Zu2 zvRLRlR*W$hY-Ln#HET3O`7GPeiG{j9hKfNnvEI!-S`!Z|fIJmYR<(4#uOlnUu!HL4eGS!?d#W*qpO-5bjT-_L%}*kAf- zIgiXitFrC8q4E7>GMp>PnC|zT`pKI6)9r_W?pPj4)Zp}|?<^qPm-40}kb`A)VD84q5WI%SI&<@ER9>-|B5Gq~?iI!yhhlLBJi6%ipJXdoY4 zmOjrx#oo^V1UM8vH0JlFs`}MiTOjg+gg6NaG$w?2+Y>`?3E^NniM3Q7yp<50r2tVkyuKpLunmH<;j_AzFbkB`0_szA1r-p3ZstZ`GX%jU$25NtnqJc zDDu-Ee;^ysw2{45R`*)X0fU*nQy|iUWu9x=ViIi>w(4SAqNp=;E@p`CX8-9N zU^nSzf(>kvAGs9h-Dx`c?E6&x)#@KAyH_i}u^XS6Ze9-6={23QCx5TA zy?0Ev(+|dFfC2<@2nf?E>rxES(DYPg2|^SFfNK<3$OryYED3;3r7N@Lh0wxCi9*U_ zWFY<(n8V*DAxyX5xO1{Q%CxdDD1p~b0 zmYsEok^@6a4DPLb)@%q4qo~!-5JZI-k%LRzmG-Zd1l^mGf{%fro1VMis^X#okN^D_ zxLCj>dAklS*0r2fMjLoTK#DhL#vxCIyUgRpZY`LvGYXYo%MCk^jBU69X)%RADM^*t7p&4f%Ue1f5lvQck+z=sD z8HMH&124@OyeGI;2b4x(DI!S=XN;fET1p+RqD8Bgj}#=yM{&qF>Z?ti_WqyMu)|f0XrSp`l<; z26M;a(a-$Qec(1~zdFS4M()psZkkXzyt&8DMrq&mp{h~NBaewHc(Fsq2l+;i2#KKF`8~vg5uu?cP?Ow9pDIDXS!31+BB{ zsd11-3v%EEX#QKO*vIQ8UOH{R?s})jndUoLb}3)cFfh+G`S*`!+&k_7kS=X$QM=*` z_8f!42y`!CMF;dT7!NB?&^b)IPyftdM{)Hy8!(413B>IOBFKa@r!vyGjmJ0K&L(ni z-l~MJ2WfFf;{bjFSeJmeSMU1qe+4;_xMkWUv3s_CKibI5R<3L!iF*)LjR`jb)KsJ@9d*O5|$@0|#i2(6Guaj6CSJ8CR^WHh7JW3nuM zR%0AWByEaMDh9k$`j3)u+J<>nMuUn{m&7PvlYgV(d-$Wsxs2;koz3HJ74C04kGmY` z7Up`ro~8@E+15x*+*k{4y)4KMTv!X7nSouzE9<`(Loncm#2J))QDd2h29@R138!cN zDE`Ny=!V%@y1Cs-YEhR_f`y*Gc!@yAr8IDI%nO&{EPZe-H+bc6Q97r#a|w1&Cblq4 z?wyG3fXbYb+X&p^AZWnCSZmI^Zb3rv`76JKaraDtE{vGwJOSX+fID zIU}!*YvB`E;0suoIG%G{5I6}!lSD;r`Zg0sL#=*iS}v3b_fY}z#gveIb!x{07}5$} zNJ>5TGN>DTY&OW(gVXQ?Q*wVZ(;(9^XHVnj9Cz7%yqZgVA1UEsC?i}g--*Tr^~|$2 zWi`w_^javb^}ipe)v4dOC40}XR@j)Z$#YO;^AVGZ|2?x{7k@F%PJbqt&nK&g^+Fcw zTA;wn_3#X1wI`PO_vI&!oqmRu;Wade=ParPq~Y!u?okcJHlLbfYsA*Ha?EZ=gs1#%S%$EK}#SfIYnHJ{ycG$~23C zO6iXX(<975V_sYcnJzS}`KQ#?{*mo?$enYVO%U5;U{hgJ&me%ct@l`NG2gwHZN|U=Q;(bdp z(`|-@-Q~#hygz~ldp|vLT{s)<-!7qMAC5!-4X5pF1s_CRc^_|1s=g#XX`-A#&5DYc zpZZ_Z#bJzb5xEj5u<8={1saS3V{ZbDsN8PTrCAHginmso&(K{T75V4W0OEvLH@em^ zyGY~Etl=h@2Ei|__GgQye;NVr%we_PL_dI6wP(^tRk~lB^<@{M5&a_4j#_ z8}wfke~TL#yFHQjR>>ItUbe-5;0}NO4*{Dv*|8D{l^p-w{^C_@qKW^5pqZIQf9%WMbOuf4CvGIN(?9kcR_TU;k%eJ54BL`!kJH|A}drd7A` z5?ZbNeBP9%u@Xx1ZK~~YyzgEf?W`^y`_E9-G>^M0&^O()gyR&#M22X&JQ(kaOO-4K zN4lJ>3mS9VYMZ`xF*{qTm8kW<>}Wm+=xI#F{{Jk1+J-BpEQmCC6d5!hL?ot!jyVo_ z(dn8DnHY8c5)Dn%x|1wNu%$egjms%*=1QRleT>C_U(4aYZhG!>jE*2Qmew*=LgJEv z724+GKcF@DvBmB)fus95r`3QVVNh-W3f(8(H`_m3vapB`2qR$T0Pg19fwo%K@5=g`x$g-#g}h?$!#-C;+98(PL*A+&^)tU~_qnMBoSz z%oZ=@i??#B3J!OEv;yzl%a=fhcWJtEJGFgbe^B0={mKX0__`h zZ|AZ#x4SJ)$7_xnExv^)SJTweB7;h4X-W7l?8bEdH(I~5IN}}oZ?~k(aP=Y&CZ%Yz zwLLp6zRXpWUko@f5)v>|2oM^tyR`Egiri>MoYqG@K42Vqsmc_tu2D!Y3$r%;Mxv|N z?ViI+*$I=j&^f+x(6}N-2EOBP{BlF|6B9-6RcP4H=tkQY|I>yl4)4ZyZl6-QXZiAN z==Wp_o@lDOefhFv`}C!<`&_HlRO;v9+=@=#az*hiEZ?(xA3u*~5*96YGT0zDA}DOP ze*6%7@e}X+2}EvNzQj}21gY5TJR6!@f_o)~8%W8%a3p5_0OlJW?(NZNjK~o)6UuZB z2)Oytd@^tVvgPO$EOR!y?mL^f(PD+gtw0++@9@Z#-po*p3~jW>~&K5(45ym z{p6R!tnW|(=4!vG)6BumI!gK5vgL>6>ew-_A)i*$RwJ{IoPr;-%@%8&&}pOc)aDbr zmj;taT5}Zl_1IQ(E^1^tP?ajD2@q(eRiFUbfy$dj5-w@6U!sI|Jk@LO{oHF~^|_2D zB--)+<$HR5wIj+6=L408b;i0;CNqlGe$KSaf0P;KWu&2as!edyRPXVy#~*4UYd+T= zLDSoey2wku4%X8o!vW&PY|P8U-Bz{9CFOy+x!A;`8Ekh^B7a^0~?JyiZ42Ja}u@ z6ct5+b_ggJew$okD-;e08F#}Pkk;&*0L)?jd#HR|9paJm8dmrD0qC1Q&CC zTg~4K_vYIDM@2wK{R^FSyFj^~DYSB0c|-=y?I{02JTt=B@r`>uj@P1(>x&|Lo_L%O z8s9>t4*E`NC1ixf5(Wo^{zCz+4kIK^M||A7ku(RMO9KLbimG zF8%Zp^Kb})1Z{HaE*!{TAe(C88>dJCJy;ehtpj4N18YfxYw~H_B^9OtqrysJc9mFl z{?UL-Yr&Rw-hKYGw=KWGiPXOpM)-96OKBZYYr)O1JGm(Nd~w>Z!LhSA;_qo|$*{kM zs05?GMdNxm+Bfa%>hnK33g3(w#8W5yf4Lqnf>`J8TRs(u1G$^05%)+PXlJV9ED}ur zir}c2zHiZ2?|Y5pc+NVat8dnn8rvjd>nwcaHTFcWby%MXZ*M#4z544!g>4a)oOW46 zV8WBHqlsTdV3p5#RIXdb{)Ff}HPQ|@AgAkmZ*8wq8I`{kNi`B39mBCoJ~|WY=OPW` zTmN*Rcp)Ywt3Z=J4U>zA7$PLnYrS~Ndo7wi41Gkcvda9$+3IC?Liu(Dx9KHJazX$w zZwD*AF%6-45+$ui4E3kk!;r)w6SQGQ%-gpk2aQ1NVRP0$W~45k6c+>J z1mKSTZhIdp9hv*u4t`t;`=L${MD}~Ac(iXv+w^WO-WP&c;A-A=_g}IancuoecwT2O z|3&4IRy3{06Zzo`g$17Bi!V_RqPj%z(iphDl15P0bRRwT!0DE7t;umQ6MCnms7%I+ zG?i|-zvS{6E6^og0=5iorVr~V#@AK&tHQ&G6|NGh^{53myK7KaTDux_Q}ObtlZ~cY z@!qR^BiRK>v=!8Kx)jW2d4&>I8<*s!j6EIJ2FHY#I~UEvij6Y=y%*u%^}0UgFBc~V zwmDItY4W9m6>jyD`A-kL^X=b(x4`RU`*vv#@X7D^w!i46>sYX&U(%XfykFp9Y?SK1 zSemCw-?}`v14a8InmLp}y=gcN+TNd>12sey%MLwmbf+K<_&znJ`QG@4Eo_F*_Owr) zk;uq%`zO7o;vp2W@EQ-F%`NER@OV>U?0UUUp04Uvf>XoY{>|$m**#UW=hwG#Z&1?} zO;7ifGnA*kMdVIsnf(@t&i^}ky7W;Vp+4~?jj{*LZ<@ovZDji5K6X+fwke(gm(Iuc zsgR^{IUOaH@(SJS)%N`urYg3L9y^^qldoo;6b>=(O{L2!37^ObF@+2DwU6EWwEILP zv{&Vh_gSj)UsUf-D19z_jdl&-Zs03huX>%IcNtvlp-QFdu7w`n} z4MK9&^=lotQ`8w`QLO3;e;?%3$=(D%vN+><$JVac&bP>dIhCi1#k?U!%w|yLt%`V% z87eu1LYN2ztdb!aFSYI8lap@VA^Lwbon=szZyUuG5lN+4x*MgtySux)K^jD0>7_fB zC8S$QN@7Xr?rx-|+4uQ>c)v2k48z>deP40T@61WK;A->~l+qczS>NN=Hwj^qwH{-U z3dQo!{cdrN;CURCjl5-72c}H!Iy4~=y6O*|-nNvnmR{vLNyZ2coF$8UQjNpx;d$sX zsA_s0J-~f>)$h@2#YNM^4BB0|+N_LM08lgU-2i?RoQ?1p{tUC4bu|EVuT zQ~EffaKy7j#$Hk}=>CnDVG3zpa@XCP*amXFz(afVmIB;rGej|7No~|(H`nNq)DZ1UIEN)7N zU)~6wAoAe)Qx!*UYW^MBC9e6x$wB&GU&#V6E{+UhU44f8KYr!J-YZkwx6aEhkN2&+ z@4J}iA1EiUS0C^BS2G^Xbe-YzbGNcWTb=`KB}fX#K?6%ah+>7KPa_6DiAf>DG zE+kv@IrhBDlA$xUNc|Zl^Em~Hp-nz~nQzIO`c>wDRJHrI$l0x8%Eo<#>s^Curk5j( zXplGLUDywt(m1!>v{zP0$?uLS4Bnt9y#1k28{t}y?#ePyp4q;WJ=kM~n1O?tEa8Z* zzF3RvpV5Jy`^810we2vqxA)Cb!@qd$t$)J)xuT+Y5$;}qoUg%l9N0AjeW)WU{y=n)5a7EN~IRkz}BsX#_B4j^8Rr z^*QtfR}<$~W{})x+g32Y*Nm%+h#y=E`1I4<1>3c8i-notSNf0NS5x!3mDP;$sdH|L z1||=K;oL?|A8W319W!pYL{B-NJ+$dMEth_3#p2aiihcMXzfI`43OcQ4r|<#8wW!N; zJfw0E!M~5z_uis{0&bu0ChR=dJ6G->SmO%Fffq3F`DQ+V9OswwX_)a%bM~@YRWqzybyo^#!FcY0?t17<+zBEkb4i`Og9B@9+Nu z^mz9AZ$(Wf!deF-sgTj*p!H%L<~lduUrw{X9HY0+-CyjwfY4xenHOM#3nW0^S1`S< zAIEr!lyH3>P3HKQUkC!tJ8CH8jbP3BWFxuyqYiKQgZV!(-Zy?b|tJmb@GodtE^OCv1BlpOruDvPjLNV^~52&pa8z_i=CnW0>oR} z+8(s4hPq_YS#p}3{eTx9;Dif%8N;jp<`C0m_~c!0$gd5AFWMT4S|-~w8F4(3zFWo=V%#Wrejy*8{wpuiU!}{#oGL_1#WvT(~Dlw#m=clu~6lNmYaf#vIN$FPL=Zpf2}$mUNB2O=sp?wpv0Ni#}H zFOI$5JQ|(!nEGY=0a1N*KUAxGutx)ZUb(1fw}{)QB{XeFZxK8_m{PszH-GNbVMc`G zN9mh#*MQZTfZ^IkTT{6$bUgBh5IuVBw>6iV!&XsjV?}oB&&@a}*EC<|X`;)F~aQml)*XLJ3IBRRr7paDCH*8%4{7(qL zntp%9WVl~=3oD_8xGkFE!|zB+zRT8K>h-zuN#&O>xaVSah6-pPYeEE9>?bpltD(#* z3n}U*g5Sz0^yx-C$t{c?OWsfVo32EDI;PveU6+bWujT;NEDh73x28d2?)W5z8`k`G znCK0Q^6#9UIwm@!SMUI?&03SM5=quAP@0(6?2QgB-{65OwU%s9uKeOMj{h%#?yuD&R{lGRQFsD}FKz>3Lf{LItPDHsD31&1o6 zA-r?$)k{^tkv=AL70Kvh`>4=1f*(!F6CQ{CO73XnSl%U?a*FP>EOd$!(epJkDr}=t zi1|C>2lo1aggMvbRAq*F-eOUwVkqrL0M_ZK4)+YiNgC*b}pi!AgYFZB^;G* zz?O_1JkzJR?oJ{Q19F3HSVCi8zrN%KPeQcwu`DRE&+ZY2FaOK_EofXhgP0-bO5JJBy3u|jwQ`a%nyAKY=?|er` zAIW$3)2;j63^^wji9C5?6vJMu%L#T8k9D~e=cS5Dd{|L&1R_WMgCt1_NSD^HA7x?H zYZuFc`H~%eM2|K%vS-Jz60$Kx-mZgxMt_<5?z|JMnm zdEmPa_6&1PrM%V|7g<|rUH-;0!ag_Uy(;S^9XR(T6Q~-fEf#8Sl6K+&vz~tX+3&;$ zy_R0a_UGWifOlB5s?qKc5~~PFyh`q(qP|4E!a#!5Vm>YOX%L~bYL*z0s*@xB74OsG zMpQ5(v(53_!kHuuDNCw%l~^;#RsReGcz8=09JN0=t89COGP_Y}p`;_%%yJBz!;s;9 z9&7?MMcrQM+YQ*O3`nKyjTRwaO#K^(u3O=vKUMJv!D=`b=zjUZxy$EK9TvQ|a3HY< zn2iEi+{YcVf%$Tb7pp$&Kud`ROo@VZm56=5z4P>`U&{DCCxU+SJL$Zv@VFd6@9&PV zcI`Yo_#5^($;tZmJ+u41R57*EmCv}##bSK?BrPMoMqGfj1d29SM(%;C8_@+Jk}|~g zTJdMe8~Jc2?~9%E2Y&U6N%b2lP;DRDSV7B>?iZ@z)0ZwOf%Qdwz#`F0!NGDkBjlG= zh6(8_=z8P_NEJ9`7#dEtqHm{q5i{oY8cJ4d6jFY0t2gqP`NYVzrIlr!?x!)9p0Ba_ zfwA^8KY?_=MCzE-WhqHtU$7%_{u~;U0F5eFd3!Xo$sgfD2dP8hN}XC0%e-w4g3-?k zIsES>t(LrvYIIoI0bBZStC;!Dzxz^e`UVA%lyoqi=Ug3<&E87Au^>^Wv~z8zPLzqq)iPx=7D;?D6lcdKq#vMv{`6p5TE$3?`K#SE|lyLqLUh6bdgjwzy4VM-a# zVbPrneVu%Y1vi;No(dXKkX`;N+dG$H4+bG$K`ZaQa^;yXaGg&y^Hh-}J2vb2@C>T< zOD4Vwc3fc=bO{3|i(x}c#<^Doc)iDMZI%8J9K3}2zH6oq0EK~;k2O{{^B2jlCtugv zqMtMcIW7oUbS-r7j_f7__e~&ODx6$URh*~604`yQ#OprulO*4i?TQb&e>Tg34(@G3HDYpc)S$hHt9ED(4z8yg!LonP)Mz5wgAQ=Ho)tlN-sj&I|@ zhHLY`gDMKY5^dHl74Z_gx9kl%djEuP1_8YAlvFGkBdV);ru_b*t*Dds_sR6(-D|?H*1H>mbqKfp;s-KS>@+>$hH=G zc+{ViVdm<|Wwuj4GgCn+YE;z>di0wCISrukbDr&`-@N_EuL!7t+-EfljZiH7IV!(? zs*%G=T61+grK1r-LPT4{6o1V|ECvfRher)r8E_HG4BJ&cf%Bgc??3jxsA6AZ^~YLU zaN5vW{KAvoXLRmS=7_HgoUhg|isvHqoceii%nQ-ZjO5pB+O`r?|YmHpr4Yhh**6a>G$NkwFq+P?}FDtB+VNo_7+omf1yW*y(}s_dPelu5&})dpUY#SX zT}qe*JC)O2FRQ$vi9<$mEc%Aao%Cz%;FcY_2a{WCDn&`*(Ya0EsU<8Z`4skM>m(qG!~I;7n;s)$xT z!1nHlH!BiiRh>_syxHs=(SIh9Yt-#wkrRX!xIz|PtVBm1y=3W~UN zq)tah)rcgS&%sjY`E=6x(-#BYL+%I`JrPni*cyC+*G5R0^t7M@4N(GM@;t|JMn#k+ z#7pyrfNoovU8bLnfAriqt_COWPvQ_Iw*s?73ZC6s!?V@?XHcd?vr+AtRq(306|f8k z3TYtxa@OI-Z>>wVJ)H6(*v+kba&pp;dx!kO&%(?m_-0o3>G>>pAGmn`Tl0P1`BLG_ z^>X_axP`4a7Gs`-w|XfBkyK2NdDR_?*kY8Qd%hT?84bwMY&dldu{*Hqj~}{nv#TbB zs~f!0l|P^JNW+7SVAbiHZP7-uvx`UVg5eHnqgs`fo8&x&gvx&DX?6`3*u-p!fmVM> zju+W8n!4Y3?%SOr_iq(_*X!Jquh~_k@A1)A;pMk*;Us!Zvl&-A$V^AmXt>EEW66;Y zL-o>1X0*G^MUsxA)%5-A_+r?+_1##bFFtt<3W4Gl?8YvbCvRyzM77c=4EZI2c|vM* zt!`ot`KYC67m~?q+f7VxBtx{V+YKz#kAQz;!=C?_ILLsU$7o=$ld!FJ&4Gqge12j{ zB*lAX2|R3T&Fys0bT8#xm5l??5GqTIVu@Ik) z&O#?*3r)>|sBbC-Ojwp7U>s=)SxOZ7*ZT8ZunD~P^b)FVC*K%&%FuYEX=qcwM)hYR zu!q`>D@_#X#aS_0bPV*z(~%e4+bOOhuGXWIs7cZKCybLMx2`D{wE7SXP+CcAwQ>6P%SH;I{bXt86Esp>t(-oq;pozr6jr0 z$18_knT#!Iia&0RHP21buh?hv*$);SZDl;|h&UlwplHcZXC+^&N3@=dVin(cl8=W! zr*1e1k?ot{8)(nHOlW^)NqGO&UBU#l=8Ap9VYID`*ZRSQq_q78KE~gB6CH+98yv6xbFb6dPJDR>Nd1soAx5WNS3U;5D7Bj(TSllDFI z{ZVd-x8SRaYPv)_dd@xMX@@>8+H#Ql9ECKj-T4q^S(GV;O51N#?Sb{q$79~D6t5zNh4k% zCrR2KN`w{ljfUd&E+MOyhc?ViR=?5MA;Dodl6Kv&iD>X2vWBQBv%%bFydgS@!!F9U z2?;d|`RJzm)b044=Sga+8JJ{;!#xe%C#&v%Bkq+@O^e~-{4iFmGr&IL{@GLP z-v&?6aRvf#3L|Wy=!}iodGSR_d#@8={7_J`SXq*g%%y)^6GjzkXXyb` zEK#Hblp|CzKM4pN{#a%*S(V;*$bPYqTuEJO7R{#&v9Q3Ul3rG?nXjzE9I$LFKazaP zu0^1+#unbLrc6j`EKi~uP$~hBPPrFC&Aw96(oI@QQWOK|@QO-`C6hlEgA}Kt-~4%c z)&8Q2E2}IWaHF68RZzkpLZuRZq%>z+68!M+Il|}t=xyZ66DHOunIf6UR>pvtUXQD% zb;5Yck5gjl;Cl?m=!_z=akEttF0?U>!~jy^%CfqT0;;uE6fAU9Re+n|ChRe>I%Uvv;kVXdR&T}^`Lh4!ct8_jH4pNHd*^7bMoi-W)GHW+c@u>_X!v(MxgZZxkG zpgMZ`ioDt8I-X7^cE6cEmA%Notwutl>f$|4aT zk+KPMdwFmierQP!WFKjB`RC>Sutq;Pnrt7@l~h?x$%(JWqE;`QJlL$`TIJE$%~0gvG{`*BU5P%M#J#32r=u<; z%1VsmT#L%F>b?uqsgj>{OX4@)P`xK6+%&95-L8;yri)fxX&vY`SbFNaDJV0-9OExt zM#`*v*=BM<$8F{+j10M`(o@csL;bS2q1=c5gpkk(|VR z*A1Snr?@S>Z^m}0Z7#yNq?rNlpoRFd7fYNQohS`tCswtPp?ug)H% zU2U5zM`#uab_3LQ+Yu@^EPgIjrCXaj&4V%T7a}S|8E@-rtA2WQ!-<=Nu$^hPTI*sM z3WPjM2I^odiN-@ps`5j%`-`QNQ0n5xGEE8u7*)Iq3EUbMoGZ%CU&(aK{3;;mMA&D^ zrcyR`ZA88fyFpwFmrc3GN;tSm?6}31ejO-s9bDkUaZAJ^2C;&%U513s2y(JQJus>9 z)b^U-LLDMXhr~7@C|)2sjpaF24i_ISA0u#uM}U-7C@?&*ilQRkG=-f=gqh84jhthW=w;7BBr1i&?oj%>RjFr0(qP4W^#>oF^ZwX-KO|Qk!dUB zOmj&7C=rxZluvc2T}I6{m#FAE=v+S@jeHsr^Y>s8Q|2vqx|ozCYdP<*|5A%KB}g$3 z`^zc6n?e>bje!%Y6~mgq9Hm<#72Q8raD9aPc9vaFHh4ZKO71WSjF0D z_S|RJHMTdZW%kVkyw@`zx!xH^w-3?ngV^I*_b0(Du}&muPsviziwH46Wicr$^DQw7V)$# zp2!|CK`)3dU;lv;E;`5w%s-$0xdZp+)&6)uM@jzvbeo7%#0$rPfOGghh(vFc@tr~_ZPw7+C-sd=D?9Wkp>|6SZ6}ho*Tw;`>SJU|AUoA{ z?EJ3E{I;_=wWYJu22kPy!QlY-ivDDgdM$jJC%gPIA^6FXd94!=JDgz@F9$ONwX-ND z3DdO&?11_y&yJNwst49B$I{9T1`VC+O#AZ5L$UB>?4%NvX-u(}63>$hpoZej3_Zu~ zN5@Ex6tU60m~~V%Au?cTlZ{-Cxsvf?d`dGrn#pL)N?KJc>X8I)K%_qF6v5HLMQhTk>5C(-R;L7=iz@I6#So|A9AB+FrB{n=X#R^*lNU6tXp zpOx0a9`NfmN7u?8gsw;ZWwev9ghE1aFb;@bW=J_qW@oNAhbJUfO8M+*ZWUj$Z7b9F zg~mOF&KoQEuepo0A>NHJccvcs2CIT3v~L$$f-f_pSw(W`sT6ATzMIslxw~EUxt!EW zZP_Usen-SM#)_YU!b5e0Epx7fxB`zc;5Hs6ciC`l)~wGM)8f|a^f1`@RFBW+!1+)7 zejl@VA+@Fk0A2Dh=Gw`{+L9bjOja5FPe8Q2*0_xTiTR^}Ia z!_xS~2nPnEKaezG+&{(e_&R{YB|P+N7|kA15fJN(aO+qJ2nAJ{Jc^j2eURZdcqBZ~ z2nMXfMMPp`1?UgSbZO}%TieW43j~y=jCYe@;#^5>Lk0fO4U-Ct5|Vt~2!2R8rgjp3zn^+R%4kM_5DEZQb+` zDquh7fSFvYnA?-A%bDpYpVP!2b%)5{_7{#;VRFh+5?Uf;UE?7pe_ely1(8TVo*UK+ zxTx;%-*Xh#c5G9~nZCI4HMi<2U`HaMYD2CqJdL&b2oV&NgpZe*{% z52(0A%%%A2qbG0hy#4xH?AZXeU_f%+`w(rMGC3vbLz+!>nLjb|3N1xZb&Zr3ZQY!f z{9;)SV>C^pR4qjvM2&y!B)`&eRHcRqsZC!9$*5?4M-36W*$R{gmmFhe@YRvIVrO{6 z6tz|6nNc-N>sdWN8+R)dVeXcJlwz!!bkl`T=SZ5ln^?V9O-B+zj#kEk`OA>%<3Xngju3T!BXfA!)KeE?qr{UnObZ`A?-jr&kh%f-U&WvX}Qy%rSIp$v}#_ zm`+7tywaY%0#8|!bKK+UH`a}vQZv>GvB&KdE@AOYr@djr7<2X{`oVrrCN}X9$>peq zHNGk9;}O2a!v!_5=y*IKd&_KU=iFC^o=oN4*f^GjYG#Z1SA+^OCCY*}^ECI-n7jXe z<%s_KSqA^O?Vk7OW!7OrO_gdLefwfUyimn1iVh}aPc(O4Ar1Jol@~^xsC=(QjFW=P zANLWcB$D50AC0B-ZN|iimha2|lF^Wo>?7=F;G1^LGh?CSlsk~Vn?e4v?exz=k4~z;2qJ5wmYid`qVySAtsRQ5`XYlFjH z;ERLsAeq6_(w9$oet>4u58g$)z1<7}Z8ur;TKjE-?@lo#uY+74Di9?R@ojM~61{QHww7s0*V>ZDKKG z#}9J1RR6AXv0^60Y~F4oUPMQSjn=Z$;Qm3RHcLq^9+dMR{;m)#+A);5Z#j%e=R4?G z-jgI4midJ^v5}Q?zMvAaots;fSXnUW=`pSAkPsxn9omnnhL_9-^=gFnEwFR)TPtuO zJ|Mol2b2 z9gm}cz`yPyDP*z~bn%}Aq`2nhXa<)2TK%-DGc%@=+XqTJz^3Y?pKSk%cKVaW3})kx zIwJPZFgG$P*01Ucm;w-n#fY)|#`X4(DHDxB4`TL#HON)pc?vOtXhY0A9p2SlX@#5B z?tseU>vl!35SozJ^6!TWEt2=%;bu3LVDQMZ_uno}p=z%#vZB<3ws@c= zWx*GHyw3w&V|dD}^Z0tP1y29@aZ2}d)Oji*nIYL9YkHskTy*I_rD&2tGDAh_j68*3 zJhC2^4rQH7nmeTxaTO+Y&a>Fj^r45PIy+cNpQvC2&49dCW=Q((w{@VPz{ZjQ(J@~o z%!o%K8B+Y`!n-i0LIHCm?U*#7L+$7z2KMSRr6|YUIyb`K9NhD2_nD@Tl!&>WAj>HB zwTeHof&QP3o4wWm1>C>^yapL)l3lx=)Az@}0Wwm6muSc{W~_2nB{EfGryR)jvi?T0 za|N(d0b1=qAg0>2<0b0ZocD){x`CyAh@!3<{xE?TId?aq1oG!R4sWCk{_MGwB3_mE zmK2_Zt(=X?Y*YI$+R1uEy~m$8nu2iaqVm-b?237Heyb4=%=--)fmz<-f7<65(a$pZ z*pUzg&bO%P(Kk_#e^i!Wj<8NolA~FWV*e9?#BbM(W&#eU3p~hr8)-eXtFq#;;7fBD zC&aoD_kBupDC|07YgoVmds0tBfhGjs+#J0o&iZ4-k1^~pY&-$1Pq7H3q#K%0&K^BO zCxwm$Xjtqd_^O_-mun9;=aQW=CtLWP2UJ@vZ7xr^+knv=OD%SQU*mFo{|kwjXn4h~B;}=FeFSqd&UcUPAzX+toXHtC`49t6(=?8= z23vn%FK%mKCs_3xSOJwUhZ`b&TN2|xn3e%`!tL(X!!Z%`)1S+E_!16yON{4}_V35n z1Xu4F1#6BB&s>&Pr`7{>pSk=?erwuES(ssAM{Ux0wkw4YbnbQYM#-f1CE}Ry4BTe6eRAb?1^+F~qkj$2I>0P-Y3GjmCPcS&aY70LDXI z8V=zjvTWr_FS0ST;2v~QSUU}2HLS{4y_u=eVFqwO((3JLVNXEU9YzU~Fsr)@KIzcS zpq5WAzK<>~$9km_nlfBj_BTH(f05r74p&`>6n@kR@^04GrbRnK@5?M77AbxGJ^@lW zY>{)Q{fS0z@vs11tjKp#Z!Sa1i{Lfz-=3;kCMXGmho8 z*8I2?b_J()ULP9c2cV|X>$mS(;1?9WUnO34Pk7vYmP_(HjdZx@!)%2mWT~Rf4RVi% znXywHwX+p`lh9ce3VW8YQwU8qM;Qx0I1NZ0K^pLn?7uG>Z3o3w5cTmYZQb!`86m26 zAI!KPB5a@3wq_}>ex(`yRbFt5A*XKL<;~GhYFqmY^+d*9r&*=-JcN?C)V5WC@jZse zU8}V?TfJ4iRWeaJr^DOyn)Fy4uZ40#nUZp57-ptNNlxo4>>iqUV$%kUkA@=*S*%FK zKf%^5I(OC1=gx|3l2_fV5uHX=d?GsM#sM)p@dBz(S7UY>J$;#o-VQ5TcxU)OuD|MS zb^YVbJw|d@z~2qiT;syCuiG#nnJ@XQ*-yZJ5f#tE7Bkr#a&ck#FyCe6d6DFweJ6b` zv?@iUpnQl7dH?A+U9b5%8B;#cULj8)kVvr$IhrsaR9+AWvE+NHjtZ#{_IN|e&GIA&DJ!Y-F{ zyWe(7>1R!pPw}-7LOi)0_T4~R;j43cA0cdUGrSorGv=M*I<|V#9DD=c$=EF=2rn{E zJn!N=E(I72&p`305!(gc!PV={m%7;2Zt*|64VgZ>tKeE!Iq)zp&{WiTF^N=Q zA1sN;9CN(Q!zt(O@*cQGQn5HBkE!OzphJw6`a|wr(`CD$@P3e8tCp-TvvK@RCg#4o z1v)Y>lT$@@f-^9BY55nz)vyCEUq0`5Q7ob0aS7e0VmUZ|t6N|ZSvZu$+ZkHEMRV)R zY)#b>R#4vRL=dPsug4=XhK#AP$7LPb&##vnt+Hs>ACBbjE|fMpWi5v@G@R}u0ebaK zv3p>*PXjCqvXwM-u*dQJnE31hDMD7IrOs}3?`fsYk0-52twlU~g*}^!jI8>LG>^Z$ zZ4buL6+>OaOFI7X$^asQtSeOwBNowt>2^Xn#g+6+2IX`0Tzpu(1w#qvpE0I~7-uiR z;-pyoZXa3}L(G_t-lzCjd$I;VF57>KDvkVV4F9I{TFB}-c;R0z&xhOgM@t(RUwotU z;jw-S}4c^T~uFF7@JB|UXN36tN0C6qX^TPx@!0eGfUBjYb5wHa40c(<< za8b`+)b36&?_axseOTzrQ>JVJ88H2OUgW+ON&gLeTfyKmrvGrI>+t7wa;jRx#xCkfi^OdaoF#xp-9da~?;95qQEe4oG z!gtQa8oA~v{>HwNQrIxl8jlmmBuvTh3cJnEm959I;PDvK`t7dsGc&F7fQ+rGm4WJH zXa;phAR}8A(Kb|9R)dyU>qsn3xXFOydU3(dJPF?uvK52cK!|01%;BiZ;~Ivi-xtLk z>o``59EME1u9lPI$niUT@O$$|q3`WC`8GeHc)L`@mUi}*J6ULri*_MZd~5vFT8e9B z12fy(-5S(Y{`gdU>fT!|r3g9wD8~-Je||vpLWi=fewCM%0AZ~8s&)xjce7hr>S|xx zZ+#}=yU3@r@yD4v@*_8RuotZW^Q+H*8q`+)&mIORF=YoMFV->XRS+%7GwxZlsO2b{|2uTcp9ow9m82 ztszfWNGq2}O9*p!ya*Kx> zBlVg0JVd!)5Up|+4^e8E#iJ;jZp(YXOoC6?5*;rkC%VnX;8l*I^OMkrSC>jI`h$oz z;6JL(>u~+$uQ)QEy!x#0|FsDq^F+uN>@H!#qMiy48%ova1`3wYTKC~L zRHJvQtiy3vPjgHnElP3czcao%th@=VWQadeL~*V0a((<&zlwp-GfI28?{oy`@U-qQ z@$~kV(boQK?8BND*CmUSB>6A+r$ODS3t`0O50R>OkFN#2pKeK90TOMa^9Z1dCyWT` zJcH9|t&-)!MSK2pr?R0}&L0P?U);`eVCHS-eb})PH`J}1>PxA!Ts=kJ2K$ef)!4P~ z+mMucSd{fZFQdl8t3<@b_zA3$YY8`t@W!-bb4g*C0p2-%fB4*g^6e_mvVlBOl2q$JBHWo4?kB-GuvrBM~~M(xA21ChC(jhGj;x%HW3 zvh*UwQm`p)j>`9(TCIfV`(h) zPSHQ?(-Ta{!k24BHo*?Vy|bGP^F}wQ^Wx6I1m)6iD(Da7J~y|j(&M;D`Rxm(_RNIS#CehoN>YnKqW?6wJ&n$<< z{&obtHT7E*s&S~i!Y^Nreamsiq^q(YV>s!Qg5yza{e2w7`z|{}Ty=vmi{W;f%SO{_ z11KIJ{gnb(cdK>bH0m^21uUQ}q<}O2>tn2o>|a?PzG_bkpNFW}rKEid4HP#NFP^|r zC3_~Tlr-6P!BR)u#_kpU4~kD=&qk*S=xP|f-E8RZ4(mj(H=FU!dzfTR;@{LhhEnInaIJyttVtBVj=RTWb;*BTbn@A z-Eq_`(lN&!7oaOg{PB~bJhKKAq|6%Pq_B_R%3zJ?Fj1fsAd@$0)KqKxn%|{ux$FJy zzUorr_nQ|k`sJ5V;Vt*?rvQWifWQF<{oOB7d`qi_#q*OzP9VoD>?$~6bX1Pf9q^p| zm*D|aWa~kiMw2E#+Yot%$Jf+{K*obe>@_uTJ)t)9#G)|7 zlfEa;Q~Ck(cb}ZWFtNZ5MT`NG_FTH}Hc6p>H?>;P+t~)Mc=+YRjBn1YFmKCb%VJm@9nC{$ zV#Al?ovSRI{T-nl)FS-2XR@$5mwbJA}8++!HKBUFbsP9c!; z4(PjJ&P|n%onj&5D)J+5w}o!4$X{hDe;9tf{w?LvY4aoNz-sq;-J6@%w3D$J5upda z<=&37AI-w7d*oqiL;TaX!oWxha7B>4UkOfcfbjMj=AuRMB`)MEQ^UD#0tuUi5)4DF zX?mAt+c6_m-xTD4+V?#mElyepmSe>$mDteR9lzK39ED7dcoue9OSA$bb)VV?)I*Ec z&~j1_e#kY|+bDHzwK*IZOBb->LHT&rC^hyR8Eu%3UGHD3i#yktu)Vw6U>Ll;hjE?I z=cEnj59V@CbJZDrT6Agtul}+zo}auG26B80{=vx>^Ve;DtzH6QTlqqM63b1%(=)Ky zl^~bcgzt!n3P^xR&dDK;Fy|Y579M&IuBs+4AAKburL~G0e&?34D3zuSA&IivNy*><`y@(~RZq!&*{{9H zdqUj;sH20&uG|skh0>x8+1L7{`VN_U%H!|f_CN~v-T8#xojZXo!-YJ2d@XNFgvx5u z#gb|Bm9i&asi(yuc1~%ElqeZm^Av2M(%OsBT>a!(IAVNVsB3M=4N+OxY#Gb{(0Trb zA}e~MO2Ay?alP`w`Qd=L|j3L=(D zdG=L5LM)E7nyMQg$y>&Wz0vKq&HEw#F#kFB?JV^r9sF9c#p|k>tGB?RTT+}|SG>CNpKHrTD9-6vk)^R`(5~WokQYf;^8J9p#gK@JTZC)6m zc2%M$ipFJyyX`m`9Tx4 z7xOjY+$0|wPD0UsR#g-d+Pp=OyehN$K7OYVKmjW**CIVm1;`P~ zwoLMK#_z|<$P`CY0-Vpr1W8U-XMR88;ibAoXrY;`xfH=fpU9vff&vo-({_Vb+er@bG-bzNV9=0?=)@lRaV#nCMD z+%dOl@bis064icSDT?1<#1rl5z)$PBEg6Dct-|TWUi7C0Z-*COx3Qy&Ti`0$VFGgKnxT2J8T5Ivf)8%h)kMW6TU$+Un zB~IRcTDPrn9ur!@i*0{gTkf*KCS**uO<6(BUu;JqI`=f@e<#Z+@4lDEc-B58->tvM zU>w61V>afV#@tzEuFI`uRV}HU+%qgnX>_069LwpH9fPyfcrfaTDZLop4PZjv6?n$) zycrEdM*2RCH@v)u$otuMsLwmx2e0r{9wQB6yN|%z*@H`Wc2Tg^JBzV=^G_@yQ@Xa? zVmLZAPVMbj<6h6n1X|>&2@eYz(*&RFF^MC+l1D|ESu*O=^4ogx^Pa+KP7$?SxYPZ_ z$MVipsUomI!Ta~*xJs^^1DroXN6q6>QOm9B9Na0t3%D8-uUH9r=q2`l@7c7L!BAUk zULRvB{H+m3g*_5-WOxl(8|t zy|k~IOeO%{2PUKCuvA^$Hu)Y=TJ&hRz?#-a#+jAU+FWapYS3FrsI?R$@vRA%cy?;u zpl%|%NMe-D#wHD&I-ocx-$zng8we6~2Sr-Hiw2k(Ih-0bY!|gh&1o2de~yuMcuMj6z8hCYz{+ka1kT%WUdS z=+MM@=purN`?uj<_Uil~;|qu9&O5T;&f;J)Z%@x&po{r1aS?d}f363Hdw@f{)o99# zw3khY=6&#1@?Okm)ABShT&P$2;Z!x%q({T9uKH<5Hlfh)Ni1Cg z>O=DhhzBEI3V*&uBeXnDRVNuG?lH0Y#LG}0+~pPG>M8S)vn58HbO;e|Q@LXUu4Sjf zGz#X0qN5V_H*Wcu|5g#MkiL&UGh%QWH9)20i07S6R&glz@9#l#{m5n~nM#F~`G>vq zyu^5`TnvH(Onn}92)9deb}>h8;>wNgzk(5Inv|6dayg>vZRNzo`ZtZjr%^J@cZpPv zBbfKmt^?@63Mz^p+XTG3#{!OaQL;z4sbb_%veByn3MzVWX9p^uXbRz&m51kFG9}E5 zQmfF&5(m8|v=Xg{AACuk&WCH0yoEzqy8HW2C6`ilP-|0vGTW>~POs8L`wcB-6J4~q z0*hV|N19ZP5EO1?Tz;{ut7u}1b7Az@=Ur#f%(w06UOD4V=3s)Hi}A~_ z{)@u>00qL)L5Q97kVHNEUUC`%v)Z-`S8n7Fd#ZTS<<$Ggg^S&PF(f}cNG4vP9s6N( z!q3#Gy+-IH2eas(-?z4jd6ODKUaaK(pCCC7Z&lEhTe_7TtaQ;Ld-FQo9pX=Zfi9~+E`Ho^y?Yd2zUp0Zx9gALZ2v$ObAEA|41Y=J zf?`v`P$E49FxrQcg2zb5n~Am1>%imIDz1I%vIRT^K6tvnqI}fQim+5>7WfCk1tMEy>bE1rOdeJ zQwwL+5wi->5gF#1f;t=q&tTghAwG_P-^Iq`u6?2$M<{x z-RoM{Iy2z<84gJR60fK>pYIn>GXHnad^30k4jbUIM{8aU&@gj>)O|<0x0_&c-99%M zc@-u+GrRA9bwYs{toIzlf1|-)1(%Y1*Xn#o-lpUzp7kmv3Dc_x z3)^M{^uCjZiFCgqBtz*eHO!{r;93G##X_5Ij6D4hUwu9_xF5N1-y3@^WAoP8pghVu z#B<&~5hWK-FyH2K9y6B{=7sH)d7q-;!YdB`O8ibR^U zoUNXWcT^u!bv&=})ri>Jlg*&FlWR4)E&lM_{ddpCFE*dmc^hRWZU@8>rGldWawo+E zF#a(bl)z#{$UG^1&d=DNzu`Pxd7HuyGHi7>?J|6F{Bq(&+mjWDn?m#<=@+tCmo?i3 zhX4;(PO*m<5UNXIQ}Y9l`171J=U7RFFM@*XOlpYLw#@50uaW6OlcMdq(6WJx|LBDYONc-+sXchq=*ahL_9{XUBXgf8f4-p) zr;$u%w4C>0*(c$56StO4USiBS9Q+}~BdqT2F$yFscFVNE(#t;9EnOGMNa|K9?A3i< z6{U#c78QNI$BgBcY?j$;5Q<1=o0?S1)6hXu5)SGQ{t!`)@zulieMRW8;w)HzNo$V4 zuea(8D^sKut({%9GFFwY=H}>m@_Q~2{OA@*sJVMo$Y{ieYAJE; zdv3F4nf!=~NN?&o59enyKJ3;nY2 zG2xk27ins#OY|lWWaRpps0uz6oq89K-dbm-^9Ak3U)R35Q#ak5+hE z6yp2?{R8oQBktrJwwOJLK^}Gweol>-x3duT)RC=IA>WGdTSo}6ecBa74ZF!gVjSpQ zUaG%8VXwxJF}m2A_SiX6{7_aVr4+$QLnIclXdEieyk#u4_q6sSAP_d+Qh4Y4aPNV* zb6C!)JMUY*wPUB^dGvbYnOi-0=p3dL$9(2TekV^Di2Lo}`S5u&w*>q=FSPEd|MhU> z?=p#j6+V7uebrypU>tm9(6sRS0>4bGm`#yh-#ut_g%!tQ%_P7m;u|Iss&S9Xtz|D7C4Q6K;txMPmIIz%;|yTq-e0>OGbKX^Kdj~jLe z=IM!6PU=4XR!n^3XUd<&_qs}m7QteTF-%m`OQW0b+3$?DLiw(G`nFeym`4`&YEBK^ zUc~|gyKw#%#-`?~tNQhm{qoIKulM6d*yEM_WT|h#O3&_z_Qri->sS|fvWG-hOkQ;jiw_u zc$1KRbkcChCWQe_T%8BFEC)td>RI?PN9`i;?PTZFcAEbOq3CsSc3kSogSRD02vStu znyRw*bZ5~azuEtMGYxfvBMGkmT;S_+3TnfOwF;>ki?6*Mi@oT)`dGq6IaS@_G+zlX zF*#jvGb15w9;c@Y-U?=5LI{q6Fc#M@LQvT*rga^qCpI6PsEq8sWzXX>C^_|bgPY6C z4`@hQ1qoftzjOLU#Nvh98Q%q_tU!%Fqv!!h)Kt9={jPD%e|2m^H+^OOd4#I5zkKw% z`=h@ewBkXm=iLoCambx`y3epEeKh5NasERU)s*1tU*fA;K^Y7Yx#D|edyq!AMaZD} z@0DI&%gi(TaN$}cqg(Ip>(X7Z0D*G?Ul5YpV1>;{f1KM6k#Ie63)>_TvyO4bsf!Gx zV}k$lN(26f`TW%Km$~@Pr0JcIEY42ki+^Si@)!3Clciqa2e%JnXLX64oL(JDy;QR< zEhm9nTxT||#(M>@S~c_^LNK=Tjk(+1rL!s{_)M_nHdHuAFJ$dJ940k5ZD*!Jt6E7{ zyTd$f)%#6^aA9qPhu*^ILO`a9<=5vrS-Zxw9V^8Y)KdVBX;OAJ{s_4H;4Kpvi13#D zJwH9XM6LAT9ZY8K6M-y_K0!jG0y}7eq;%`TR|3Yd27T==2^(S%`HtZRD3D}wd>MBsmr3PMVb$Pe;2!4_%Uwc+= zfd&qgt@eX&oV*s}xf-~CB9Xt9>`ioOG5&Vm(8V?9Z>=}>YVi6b#+=t7U{r~O2Y;X9 zMW&ttl5N_{?|a?hKjveH-1~rttPhpqr3O~nMOM%W zoPZ!XB8eo-R>%;@gw|@#5B~k31Y5~4m=R6~7i)FoLuGVQ-8H60DXP2nb<0}7(rpn> z{xSC|9wRU)K;XIb;ueI<$b;qzdTn#ZflXZ4@9p_sxribq;)X8d&HnA;P|}1&AB>rD zGRA1;3pM+IHn|g$_7X}|tx@EZ*?}DaX~bs^y08=?Io{?%&AY)LZc)heYB51|BXMgP zV>Bi_!q;L%lNTCi4C)UXigydXG}0+N4+pTHp zK&D&@{Ge|5vo;aY!{bt?Qk}d(fPJoe+p2FoJg0%D+1(~3HWXcUA+_ym$Pc$o&(-=g zxk&Q#ZFE!)dD8dkNcunMxwu}^TGWy8T73zll^Zxu9i~a?MZ0=%SgUh*cO<=e#dVsn z{v~@xmO2XKbIwFj_E^y{8p6;4D~V)ORx>h7N@;Y;j?}lld&lv}M~79A#y<`32eyjm z0OT4t5nID!;zg&)0BrcsqP*Cu{d0%2j3^~h3 zoWvX}3fz2XowpydZ?YhlpJCGtFg@zKdj|bqn$wC)k2P_mO!8IQ?lZB?6~LnSJDUDH z%Cep2cq1lBk?0Yl^=E6dkW_}=iu`r4HtlUjW{Gv>uyhKGd;{ITv^s;!IQwfC(Pmio0?M?{+WXsd=75!_c99-0Wo4k>mrrn#=qCYc?XGh@G=<^WyHg0ZIT)FZ; z*>HxBa>>>2Od{2hG;z1W-uR4*34eno$18hc3R}V`aM-3nMg7BQ>jKKsSzO`W&U-#; z42b0+EJxBrp=q6$lGdLH_15tRCyUZN)U5{0=k$vH(M>?lm%%s~a(GMsdPP1CtB?%v z_VikpwYr5&``S~bxo;oxO$#Vfs>WEy$`Xpy8spv8iNV7bZj*1dQrtMgMqY7~am)M^ zx(xV1Q;P+IfIZSjW(}qu(Uo=-SMy0E=5lcRu<$F%4IMdOuSqEkuXyeyDTsah#FL?= zz(_biG6%#nSTHuqwI3x4?9xHQJLvLT{9m>N{IfIL)JFbJ-i4TLdwSdq3qag<uo8X5MCy=*yoD)qy4;tAx&>QqSNb^FCKSPr)!zsn2Jx7z{X z+QvAk9f=q;<1m(K71;AK#As4vTfa-OI9Mj$X%B54igV4OoiDHuw(fQVCmhFmHkuK| zn%Pl`Mh-E@>-ZnqJMW~D^Sx9|$*#mWa{vozW-)mxv9X;w9{6;wyX%FuN>Snew3JgP zm9T+li>#Ly>U+0(-QJUWe`5^lGWp@L2Y|6|uz0m&c z>67^5)KAqP>z*Yd^GVBWXcI7vO+eHqz?c({B=NCg*lc8wdG;3}V}b0%>fm6E?>nho z@<80S<@mJM>QOoJ-L_xJhBbI|#P-_leGz7~W(O|3IqsdptN67Oc~dLx|w; zj2`m}g$~#iwALd&05AV$MCH)Zvmel+Ifdfk_xwGJgQRqDOEGa}GV8e;9!P})3(oTjkq&ED*PinCpm4u47S>%B?bDqet`$1_|umRYgIgDhR%Yj%i{ zuWu8S-A`AC8puc~>?_Sxm*q=jkN%CGKv(*Q{ji{H6akJpEG+ghO9sA#O95O)bT#768C4BP;z#r&E35-jA_pRPcRU2$Ksg z;O7M%1%Rg=UXmU?VGV44w9v5Dry z7}9WF(b*ytlouX)f@H6Em5?^l2OxurN@-{tOqNigFujx}qIJjkA6#ceTBN1FNZMbf zRu@jwJj}CxO7n{6;Xb@0vy$rh03msD;*cA( z=yaMlCmDrSgVI$y9bNefn|@cJhn=RJGEF!(#3$qUt1Zf(0>VON0$GG5J1F;%v9 z@T}0*cCQD*$HNmSh+k^@sKg87v6ZlWN1Tc`z=iue@{jWCkP~H{+plymV%)-!zQ^GE z9x90YRR!zckgZ=snFT zNACaE0#vsf2tAr`uohsimf1qn6;EnDH(+O+KEAl#s5rjKMr`!#|CgwAexB5gpwcM2 z8MzMlwdTBh>;=G|02@EcM==(cuyJE1Np=5AT{axxvH_IzWsHaEjw@BxGi~Kz#{X=L zfvyjT@^lh_y#H_Bdn48Zu)EIg!K~k2n;*V9wCNL&{~8KoT?Z-0(Ip3OX7jW{Icy4u zKGlkOf#VsZBa1@~hIxv_W=fzmKcN#vAqKV4`Etyz=D}>~(#()P64vV*5B%1v@(3LJ z&Kt?s)UaGs))dL@U`YaoyH(PQ`-SX{gxT9!7<|^{Y0!|bkce6&Xv9^mAgxU_H$$U2 zf45r4UprT0F}QY#=4kIMXKyo}Nrk~t^^c5E;yBC zL-fZK_J&!X1>Sa^5h5HWhk5Ml0EyS^$eg#aaqZT$_R%H5k8R@OwrX-~_9PN|{C&*8 zziQ%_N7>W-Xx7*CA9#&MZeE$^vJ(5$bp^bFi;Ib(nGL>Oc5O^Rel(l zyO^8>r-m!j2B;i0xMeeRVt?#Uf;N$?BpYN*m&6pyL0=nf)UA67v8#D=%JtS)kTtLK zmYtTBy9!@4V;D#82Q+S0IFD@Cq4zDaWkcMDIy898Xel)G>7zBK34$yL*6UlMP_Fl#DwNPeY7Up2-)P**b7pBZ6n5a;YUmt%u^8CNn*dCsJIO+m za=YXSM3F^^|F=*Ja41T83W}IHX3*8;Fxp5hsV0 zbUfxE-L|-V!wk8x_Wc*Q_sn^L6_oD%$SnU@yneAyd11M-)hh5%)@|-p1AiH7)NpLy zqEjEFj=x`sa1C`uFd$;Yz^o=VxCk z?+LFXFjnS{hEy`Nf&h1G`$)!$0q^~%`ca0ds!7a|3WZ%lj)Z^R(^3JYQdY<08@B59 z;w`#Ehd8Zo2`K{ocNbcjK*L_9x>fW)Wa}#OYaBX7Xk73=FEGpAt4hCnOhZL zC?d@o|M@s7(p>EUUg5Id5_{vRpn)l`DX)LSx7I70j}J*9{W*c04qZ;;nZzBnWRQji zgMSq=lPLA+CYCF!45k$g78!9jMvs&5qT9@^7pCwu%Ki%FOos@&rTXnXMv7fJMjKZ< z8!QkC!rX`+d=S-K>@fn2#54i1RTYtQzw$(zW5b>-_~ewA$3!Sg42ixCz@D5jIw*`g z(YQ`Tcg-BBBu=ytVSPnbU`ut?4?0U$2AMo)VE1hg)EsYCa+E3%uUraBV%i%RsOj~1 zG6@FqeqGHJsw+A@!`SyP ztxxIqhn9UD^F4Ohb{UbGnVD3wqzJ4hY_cdia%$v*_VrSo$F31#hX@n$ zMG+)2+H*$h_vJJJ^7B~4TrOgGTkoQXiib`;H!Bc#VnhtU2$^wco&Wj!=O2K zAWObmrR|*X=L9I?4V&8%I4W3@3h7Bd>L#be?$7;`E!Wet?&-}>u7@%gU)ICt#`!V@j^nXG!!T)%nAjLBE;{)gqQkORH1IfRO zN&VYmk7h#sZiLyxhD38KMMMpHTRRXLRbHruyZ>Gg{4+@yfw*nRX*kO%q5GZX>lkC$ zQ&N?>S|b80g*Xl-W@fZLS3+{o(Iss3nDagJ%92_%hw>5S{!&X7rX$zE_B}c6hdpml zEiC;ymJFmDXy3Ebv|2#5cHF@JISb^>2Dr|Rr|q0sdLf16!t4|hjHtX?B;!V*1Zqxs zw^BNgYT(+9HlKGoiv-1iVW2? zJbn<2%B--kYD1`0ZYY79)yl}E;obw=hyE>5$Qotyw}cfFPE-n4qF0A(m$)VT(9j0v zIuObmrFgBVgWMTwDkLw>CmK|r6?@N-w+^Vt?a z7(9ixVbza>FS={o>@kkFL4&!pgu#w2D&pQY|2<#T3UjaWl0C~Yvhf@3boeIZU%ejuR}S zKb84qMH1^e2eG=4g2=GGzGj^h&iEUCRhO?&ve~@cgHTX8kqIjVne&ingXMp|in>F) z@A;hPk>lb&ko^WZq?oA%y^F*U6zaU+*r1nRiR4XYUM*e2Qqer5L=r>sl1T_d;-f#f zjI|JMp{!tlgNj?gf*)=|;9-dsSUQ$1RAZcX6Y?8F&CG-WlVG(jUye&#Wa3hHa}3Qy zfIWZXl#j?2%weMtsUvL)G7c}XVvvD&5S^kY-1E;a!9yB69mN))oq|fIj#b;gj4oQO z)Y!R61ejv-Jv)>75A)$4T~`mv{HJ#Y`LJ%&M#jNOJby2f#q9ou$>97`mDkm6P5kJ} z_s@GL<0fjJsvk54s<0{%*8T}Hpib>)KqduEM&(SN_cs2@r~dJgnC`SwN?i66zd!RO zhijKX0p%w~SzfU9SEkk5*l{;y8jU3@*FHC0{a+YA#JF4tMu+t!Ty-aWZg)rycO#!_ zxD4L6DP;22R;GGfeXTHpVUo28dMyhycz)^if*tgEUjNu=e(oZ9CrXHP&1-6{FFFG_I(rrWm zEzQQ?QYHBytiUNae4d#tTLj+iJBoi=yGQxQ{^L1?uukP&^fu(nRgEqUW(8Z;c>}tq z=$3$rL2E{QyrxpU;MJJDpPlv<2{K^Kyn*;H9qoP7NJH*W{a zzQm;ZtX}DW-iC|n3LGcv>kh)IZksa7 zFT>&fr7p%1(*bL|=Fi;^*?%PcN!x9e3=-Zgr!(OW=D*b{)7lBKR*T~ACacqFJtO4Q z^JW{_xdSOtcq&3YcIe~*9pJy5e1d)}rE9o25hlNDGw&OD_YuLzz8rNk$t1@`gs9v@ zOYR07Ep8?u>rK#rpI0m2D0WSE8$cz^I?bMWPp;_soiov^x$h+QiZNEn>T$dO5cjBk z;I8parB$V@%ZeeEXPV?U`zVz{-)}8&LIdrZdbz$C9r}HFN5wX#kZWPhlu(8dUvHKf zQodhKpb$ZmGpA-KD9@&xZ|~r|KnpCNXYUUJA~PdJWqd86;}Y|x8l%e@vZjkdcVog=M(h0YNY;k z-=_ibz-M@CM+f}!GCAu)BIQ9wKv-90?s`3EVdnP!O>aWU3 z!Ukf8+N@cPEDM$@LOQbbP4mwNH6lt%P!#E6wm5DiQnUkVTO3v$)TXd`J&N}R<~E6N z=OH*wtKki1Jq{Q=qHCt{hY&TqDm0p`80v+Z+KC9ZH==cGjvi>7Yx~xF?7ObzyC<3z#sZ$VpMS-o$17Tbl3e^|yyrpL>ZFBlRQj9b9td$ptOM zUnYB{g1&prJm@%@<$5^T=kPNcQ7my6%VQeoZD*p!Y7;8i=&b~K^ns% zXHhbf19KjDf`eLrEacVc}IjnPxs>&2CHxb%w;+EA-MuM ze%f&|!WcmkY9k`>>)51f4Z6aD=q_eqocUu{-mebd$5QLOZM#k&p-!k=KEn z$Hq1A?t+39w_lbDuJEV#N@3H(BgrZw6vf2l=w!NOMiL0UhY%=kx}q8Z>m_}oinwQ_ zdSuQ!OI+S@)qc@JIrJJ0eSR$r8D0E)N~}i2}|p__A!Qa)Sa?pg_N%WPnk71qp%jd3T=N_(`Pp8JO$j{g*aqoboH zoRsUXuU180O1zCm|GWsu+a8le3~DGD5cAeUzBj^rUkVQBNfD zQGp2ENh1yM6$rTP+#%~vABw2H=z62dLD1yoF^l| z`cUJ$)|al*YSv$Log$%cR`_kRz8acUk71BdycbEuS{0hS(N*4OO?pk#O%r>L5a#i) z?C{cx-FKEYrJBxkOBJD{{f_@BJRKagWs}9=_!YGJ@7Q4^hOVE-X)zDk3G}N%j6^H} z>XYR6iPd1VNbDR>Ma8G+r9)}n@YetcFK3qj*~XouKnqhk41+TiZbY-OH=>l!jD(Fv zNpw0OC0UhD;@{Z)QJsp1k5^jFhqu!@l+YOZwGxYrv2___en?z~CC!X{u0Uf4URnKN zAJv{XrJ=lhu%0kny==fksHw!=8QeCK`|D{_MAAw8i_kgvGGL zcB==kUzaF&;B8j0$DUzqmL1I?Aq_Y!IgY@v%H_^-_m*=2bre^rz>#7c_U03hE(hj8 z+egDR4O`354=O@br?B{drH|6b#5h{0p-IwlLh@v2q?`oWCQ6$Yf&HGm`QL?W!aYZQ zFn{zrT*>O{t@VaQVZZpetNQf`C+dEDeQDo`_SqGXjVRY2KMOJlpDBXG)RA(_xjn~h zm{#q!<;-d8Qu~W9jPGJ;TqL%l*dII=pPB^Gcvr|C{!?Vcadt1|dY{B>OHdxcDuCbo z;pwJlL;e|YkAR1zPv1P|JW39aSk&LXKOQx0I@@Sw2W|%-3RwcVg4%Vcn1dmTwuXQOZ+b5aS*>ODW@i{ z>a{HY=rqpLrQ9XHW4Q70!8;up?JPN9wD0Nh-us~y>wwE5%NqtdMk$p>&pE6d@3P?& zT?x7*T!kYIbu`7ogtI)@5W`<09cgcZ9H^cMAh|N~(mD{+y)BAjiJmeeljKlhwyyn8 z;Y>!QkxU)oY0cH;j#81BA`71qNaPC-RULOGZwio6bpFiahRrzSmB~Q=3~CQH+I)mc zpV1=vbmv{yVTMY1`sN{ZGl_Y1R}}FCJpIEU7<0LEtD|k_CE>-Y>uRms+mPd%x67wP zX(LSH2eQIrmZaBC-0j9AR{oJc-itBgDw37>P8h1_jHC2Pv2p*H{vztWIa(D7ot*>3 zwrWZF%t;E@`^VbPlHtzE zj+lk)F_3`_H2N)W_p!_JDb(E%YZDs-1_O1P@}}&`8%i`B5<)j%7YBMJU$#yfKcd&K z@B;O$03KmGnF9oeny#);Q<1FGyJb!8i}_vtS-*Xr(pcmN&cqP3wY~k-y3ghb(NqFb zhs60h(E1vle$4oLGQF?msbe#er)Wu@H-n#pFeqdmn>{u zw9VSEmDfb({cU>Wc6nG>0#)UmGj?XozED~BoZ`yiDolzp4d)J(ui$M=f%FR5-y-hK zhUZH>jZ5`Va7XuM@g|BrD&>6t@Zu%&neUNMedr!~@usX#I9z-G%eWLvOzA-EMhcX# zI-Tde%_Z!tth}vEeE%J@@R>`hZ!*mVUod?Vp&A*)8)L05Kka-KL!C`~+u$aUy+7_M z@{s)XEOWw4ugoa4YJg}!uvD%du$g!^BzZd~++$c+vEa8k!pKkl?pdjR#mmGnB%#Ua=5+`%IS5*=DURBF8 zP!W3JrLQQ9eoC%`NhJRU4RK6_CsX>4t%h%|ve?Fc(b*Kc+6<2|A9_jGJS+%1es%up z6AxaM?xUu;3{Ypbrh2$7&Gv52j2TKPzV_-8T*t_w?b>iW% zfni6l@~})tQgp#DdN+=-v(&d;o>S^9e!M5{C8_-?5!%=-VVb*VW`CG}srdp6oFkN- zhuiX#cUE{tNpLc#qoYsH0c^|eEV8A?`mSdCw{H?yZXDLV5r6OQs_u0(e((PhX*op; z#JPmudaQ)5gX{_ZmCf6c6w-5}hA1(Bq3kz&qCj%*X_&TN?dWN!3uXX869CgL#uxXZZuuQwajj|3}-SQ*>C zvAQZx#=T@HO_xxOd~`{P3ha@GTdbJA2|;(_9Fqe?`oHL;@rY-FS$vWS!Os!6E0(Fp z+}^?f%HLEuVm@a1(?^y%w$KBkF*4I;Z1EVGiuQo^BA<#kRwqW{1w}ywD4r+IYA`(7 zeNF!NixdoVrnw9sfhx`9Mjkv)6Nm~+#P8SCwk7LlZC*er9QIgbV?LvDKA9Zk3vK#F z#kp8bo3YaiI2%Jo5-x8jhID~@&JQ6C_r6S5XqlB1PJ=b7*t25t1&>+RDbsbc>2o>l&Qi%{LFeKgnwE;AuX-WiJN0yCfAE zPL3^dOp-G<%g&H7?0C7Zri6+$Tk(Bx>}#@Z-CPE`i8`A2hDZL7yZEnLrzqLo1vS+6Hr;7KHPac!6l#IIUQTH0Cc;o+oeo@(LC( z7!1^v?*qBefuR9|IJm!?iz`^V?@v0Yh>0YNt;Wp#9y_A9N1X3jrW2Qxl0Ec!z4_y< z8%VsnKYXm`bCuqTo_;wM`<}UBaiv*$cFrJ%Z881s*Jkz9-XI%;bjx0uDfdN$h>OBu ze?x}*w9qf67Md#LBI0$qYCA@7+8YMxX-!!t{bON0(J;>U74VR0=JK6tZ8L}7l*HNI z821sEM@t)Z7zsk$R~cr&wk6Yh*K6NIs@NgB5^S^w8tbSA&NU!w_Uf`*PD_M3$Gq zo;+RSrYl7ZaF;DnTt>j7%czg}&^^Y7_c4i!mE1d)6tkAk}9CoC*@wgDwO$TU>~ zNGzv9bf2^fv{CaEY(~;|xvu+k%nx|5`4g2&^jpb!99)n&=?MR=^xMXN_aAySIU!P5 zZLvL~HLJ)E> z0kCiY9lT=Su0eot;KOo84+}iV`$e`2gO2Wy;D&$WO;RA6X8E_y_=*Z4aq->j>r`{% zz|)8BlC$^!ZWA`w6gD$+A-A_ontNRM4NSEISyN1`8{qe+;klz z8J8kIQRa_jLqg}Shi24usfk&C&0BUH10dzR_7v7XwT^thznLXJo5(^GmCOcz%7?`a zlh1g!wlfG@qI?w{FdZ)I5iHXt8J+I5uploJjYl@BNKSS=Pf@E z0z^=61l}K$4Fr)Di}+7s|J&`x+$8FAUh~i8ORUgZV!- zhpx-LCp?=P%5?dv-05$KBW}?qg~FHtDRDMVzZL~iw}q}Co6L|BH6z@?^U}tj17%jz z#5F)*fBXkpmOkM|K3il6wTj}Q!vSeSSXv$~lQ|t5pPQHhN`17sRru)4ozMT*0$7K9 zH{&{$n2p9URs|(av=?ecqceZ7bS03BNHodQwobv%%sS)Yxm2I&6~mr8c+JFG+PRAP zJ^nr1$1$3Gw6(S)>2HDCazZS&Zm=J*&_#?~cr()*+-?M#7OA9+N71zsJ7rV@ddOkf zswagi)**7(xQ;HvU9U7NjEGE{UWj#2b!!@#X-sa@^Jv6;ho@faRQLTv2^*Gw%T~R9 z1B<~m4l$Q4bADHebT>FTk^o-*81eE(*^%!jmF8cO3h zSU7++nf^Tu@HdYFH@3I;PFB#&$f@{K+Y;{joaY39jiWr=&28t-v|T(|MpHcSkz%3j zity!)4WsFRh;&tv^(yAV&gmF1^RJW^tp%D>cFE*~E44XS=lgv%*^s~f@hLeSd`$?y z?TRBAO>9db2qR|^*lX+MRZaYHmGoram+05;7@9f9M(_^9TLR}}dUC&*?d8A7dH12e zXXMom#)N-95B=6PD?~D5K{{2dYxskjJ&}4q2&<$ytG*w2{~$x&jNrXSY86 zPUx#`8MGmCG({lg7%S=DBo76bFm9j8cB_+iOdh$WpEA@p!(U&K(27_er^M^K!&I`( z!pzIL^kuT~beGDeg-0-^dr{#r%3D>9nUH$J~5SC?n*>aZ^2x7?0+xz$W8NMA7D z8hPcWQ)j?(SU#jqpwtP9BMH)-R)byjmrz4&h(Cb~J)8>H_#Lt08 zd9&N<^IkFeJ?5Fg97St_(p9fj2y}eCaSy?e{SG>8!#ldxlVGi^HU+ykv)eSj*0w>_-9%zb!)s z{Xfd^1rSz&*DCl=Qmzaf)m2detk!=wj{ZKi3B3qruk7yP<{BF5&DQp-Zgr<*`ic>Y z+hn0fGx=+3a6}fwb%jaFg)v^UPu)Kkt~H;99kI;idXTKh@~eaZ*N+$VicK(`7{5f^ z)7WE4M0Z)D@kg6v{}6qvPDFxu^1vQTdZIM!lVriMP`YsO)z7XIz{nw)qF z^qTUx!3Y_Z@M(^+euQ0Ddp7f|Avn2#Q}o3^N`Im@tY|nLcTQW~<|~KUM_leK4`>H} zPc1oiA&w&*+EK&zYzyayKr}vXo+jz){`kI>S|M!yxXow=tK_$kYIILQu3CG*$T-H# z$;hkcIY7TD&IT1SslJuX=b?T_ou%gcS+FyM^33{+kL$Mq7o^L8oewC1={{1{Ow2L>- z-DAOTRU(g{T2Xe>8aVXqb*(OzP@R?m^x(QN(K!MV5q51l~GJ)x(~`fRObPM%S$ z+yRwvp~TYfD~a}JaS{kqzMfU`DBkdZ`ZA&E2-$_|wK%;b*UZV;EPSf43;uNpH}<$D z2-5)}*${i=Gm1Sw%PYOm(z2465D?BSm%>?*k*O7*{$gpQbCN7w6~E8}eCUM{5cNtw zKVM(|ogg08?>~HR1nh?av$K4fTAGf0m7`TP+CZ`FijxpCV9Q)YUo7Y1W6ypAia_0* z_+C@!7HY61Fi=^s_gj!HK;|o0k@8CArUwQQ98yh@$?XJX-gO#&t_Ef*Ag=e5R*Km(Ts-&D0jzo+~w z+G?oy!{xp>yC0&#T*fsRs$v9OJHPe)ZKb8{c+*|fYRUHivr(c6X;$T3IRFa0!p&jC$Dho#TWz4Ox$aSS(5h4PR}K0j%0EX0b; znw0{zm4P%aT|nP_2>0ahZ#nn_h8axmMU%v7oc;DiCDCtePL+xYGqM~;KHW@<1vHNb1?CBOFc@7jzb8v73_NB((&J#bc zf6Ed7Hhi-YGzla^oOBgZ33uLz0XZu_IZXlm@?n5!Ao^cEMA-4Oenb55QE2b{QQ8&P zCZ^tx*FRO`-y&&ma2c(i`u`D{hw_3D?fn%MOeUk#!#e6=hRkXDHH8f$()tr$1QMUu z$RL^YYQxEks?1d?ZHBfv0{x1?8@q$rnmJb#j56w$mLjL0!kra-_$ga4TUvCqzEqcv z#>i`NCl6}S=<<|c$Xib+GKZJY4COrkYTw0;X?IJ;8*Q7qsY~pC#yq7`9ipRGQ`(t6 zk1QObe>wEodli*FC+oCdz4e@MJP8K_U-^q*U7N}GLsVgLnNAu46)}<^vvUNEVS}ym zvw7Avr6h_M*_t^;#SP^?`S|WRTJ3$^S+~H`ombDs$iJ20w9X5I;4%%R-$`zrqnJ#f z1S0CwAOL^y1IN~BSQkqRh;p62KQO>I&G!lEb}#y^sTIm2f@ja2Q+}?f%bgHo$D2Q$ z5$`wm)!_^2h1jXsRaTPgE7pibhMjimhzvFyHg|HttWR_bTfc?7=Q4yc8!?p_!O@x) z>K#}gIaP0KDhw!d&m^TMc*qnti|BIpKs1i$w}yhAapc)<`{6TKKKhAzWR(BvI}5zQ zUl&ewMYjr^{?7D{IzbX&`&f^lY%H*4k_cXf#}hAB8hyfWA~V2DEbjMTpgATl`!gf8 zPTW|&uO#k`KRN%9j8WFXU&?X140TJ7cR|lmFYy<(yA@$AZ8{H{IZgLH$=VSsV&ptOw|GzWO^OP35rSuX8O!%u9w{K@ zXoRV1KK#Uon}(?)SN4jfgmLzAjPpw-WWuZ`Bv`O!O~xw9ppOoAsd(vYED ziH4Ue=CqBnk!nIw1Zm*ZI8XoEG5Hp$`W&xi-E|?u{52CHVPwsSA%2FINLw6C2|0B( zB2Q18>Qxn}nFt0542On&m7d*sF0{dT=N(1%sC%d_QK~Chtg!2{%h{p8`tS4Llp>6| z=Oi+Zi^jvHws@lP-t>I95)-WR&0~n?mEGIbg(Hnk1An8B9*XAkS7FG#CWK;3-Sp*! zi)psDMXKss*j{J4{#|fx__8W2AZ(zwFsmGy3okR##7=aI zUL-jNlOZd?YWd4~kuhjn6xd5h5DW6;k%6W`909<^&zDbjtSN~mTre8Fm`szGI0BUn zda-(GPT#p3QAz5hBS4etV*4t9(JLYPg-?ir;%Fi-1MrsGPadSqXYnWTcx2} z%TvI=LH^s&@D=c(2jVynHfw*Na@V((mL_flD4rDUs)n4M*Rg;jZn@xOl0R=3P@a|% z6$+#&w!t%PRXF4aSjiB{gq>+_Bh|zn&^zfPN=;)%8M~4e4_YT$QDfsvAq7N{Vbs@g zg=^r+7T^@dDHBOkDI?UR4m(n*i|Y|1w5tafz{;Z&xfeTVB3e*(_BCkz#42|}#aiei z?Z2l+Mk!Sx&}LsX#EB`VHFA|p{#u-~qqe)XOsFV58B4ER z%p!O+G5Gf`S~z)760&UAoDxLV%Gf;P=}K5aRo0Wi z`Fywomb<*sR|RG^JwUz0m524k16np zq0@*h653gUJL3XPy^!Qof#n=N_~iwyuV!j-2OoUt)Ex)(pyPZdL;)s|6vQM!??ppN z_xiZ~tTt_GI;p5UKin+~t@6VOl<$8Vum?`fF za%d~#!tMGW*W`1SZWJTWn`OYDf4gk~}t zkK$h~^|;ywL>-sCVGf(4yq7^q{2gD9Cja#SN4fsfL7!0n-JLD>_Ewi2ud>28<_|Ss zpcP*8yUpA(H1G6#`y0fKae2L*UqM7d;_q@mxK8o<)DT0kZFB#!W*8*M;4ImC8?ZhW z?bbkzS7_4fUENtqIw^aIK0Azz$!3m76LTbR&nUXhe~;z50F|%NPKIth^PhJL^9>lM zpk~aRs3THlOd1cDj0sl7tSXc@?AM#ti+3uWIZ`ni>*=^!Qw}rrw6nPmh$vZ9ja>(^ z!)c0K6sfk2fk+{GnEjUhN()hGTtp@!0lA8Zm(W)ekbK+2j0s{ugXnzh(%Z0oh-(>( z3K~IEyLR8Wg%3hSzuu{fgQ;m=w-{wWJ_F! z=Lv{)DRsW-4^@5EYZqDQRVRw=J&_ED(zn!xK>l=TJAaXBE`9{N$L+}Tr16-WFHX__ zvOD8S&oMnEAx%8#X-Ow;r%J50v)HH@muHs=#GA$|d|499;(`CM{Ubo;12zLP!W9y6 zkd()trm!Z4g9R!W#t8a`Q8qQD{meas5@;MQV>8C$IxVPaU2Dub7dHDCGb;)#IkYQD z+L&+p^RT_Mrm|o;!K8COO1&(bWK<_1=I^N7!5@sAYbxl0lnlV;&#qC8~o_tlS=j6bsYvb{Ax#8Zl-jq({ccEx^1}%X(Jh07Jbj1_94xG&8OQ& z6y9Ulkix`52gra4u-&2FE9h>=n1cX)gza*(>t(6KiDI+_Hb>e7>l@}Z!f%3i1s+Q~ z6F+CVjyiVu08cDu9A0zg0@f7qeA3!n7HQETEruL|5&OlArpzm0J*3@L1QcVr=1Cb& zR*7_)(8mZ9e43{ZFW2E84THiedaZl4!{m}%$V~^noaUv8#w%lXpG*>qg(eV|AqQ_eVz9cxa&+}dz}g@e2WcY&sZ0A#EE;40`2+Mz_g%2q~r?GL)<)w2sTz8iE*kn4C9}Bqw8PS<#C(7TTby($sqh z{zKYub$R&-l~8nYv{}=zEVW*z%H=;{o^4s!uYcV;1tCn8jt(#-|qt*Vs z3a2{Pt~g9b#Fgd}Mr|1k6sHDqh60#|Uit|&@&-3t} zp?M@zii;P0r&E}8O!{ebmH8*)k=k5wa7OWZSXE1o>acTN?CZDi;PY2ltM~e;%wx%x zEf)*d+h1oe)-@4e)m{aAx{nqcOCGl8c{>iHwp=gPUc6JTwq=9Y#6j2Nis$KCWKA(B zu}~54{Ep+Yrq23=f6E}LVxY15=z#&T$|m1a2!)9L^5hXIVAii<=7qtB$ej%<+A5!*}%VR z8}>W`GB6AnXRtI{`#3nSa$ZL)QQ;tM77Oexs|d#o|1pRg9+m#-Kwq0Q2;G1Fqm2#TOJp6qx2qy$ zC~bWw3%#Oa64cpTa6X)Eyh%M3#l2QUt;%3O)#M(T(1QA=qq6sKhDqn{V7yM+P(V*x zumJw`_mCrF1o8!V?8sk&;Z$lnFmgo2l*3mA57FaLy102Co0JhIp`z;(N+XPF=si=a zJWk~vnvB!%qESr?DzhAw25M@(WHo=G?^5 z6F?1f65CradFB`>H>OT+0lSrlCX$bxjYrjc=4~#UFz201`>SF^kJ!xFL`6np z25gDq0#c^Ai)Gr$zJDg%t1=VV+-pV53b8Fznnn5(5K{NLIEYmBLyl)yxdKC-4JxEA z%WB)6x`g<$Asj<7#stTw;XE(Nm?swF9S6xqWoehEo-Ms@3LOEf;*~s9g@B|TLzJ` z7TquH>C%sVlC9Pxb_87=6}C+=^j?>Ak%2&q3J5+m?RQpoyR(j7!q=1VmtCif>kK&v z>N+|m0K=9zei@N-m1!O6yg-bX(w*3;~_ZY{if_>v3pF{kS?4)VguB~F&LY3H%0rsk1sfu zi2_~6)aMPJU2N?v-%~&1CK8Us(}xbTRH@n7@0F{)MENNx7 zk@{B^>wxkg1-Xgz4R$r)Y;ijSa!DnQ|~a^qU7^_t%VtH<;EsYQd-527j`;lh_nT|9a+8Y*=}qp0s$_ z^^o>`gpNj~5nY}GYxwtJl?OTwvk^EETrOcYIrMeYOMY$j81Koc+iP8yR^xZSS+{H4%N*4O>V)iL3l|g zfpRB|#IF_Yt!Jup1N*rLOn2{Uy(t{lEGNo6^v-pha5J+pK@t@H(`@wJUQ6(#+gGURFM+yc#FWm_(iNAViEtIN#Xb5Gs-NbBHdvE(vjXSRum-!$Y;oGvG!% zi4h|u-XYM!3`v4WWdUswTM28p+gu7sDKVV;jML9zoKbP~G$CKkBLPLb`Vi01*3i=M z&?d!Eo+|cd>}d3Xw(@W{HJd1rRMsLfw%9qjUo(O?i=SZ{?(sF-yz!Jcsdy;SfH!t6 z8#D5PqK6Jlf&dL-z_tkaL!{S-1J`cl`^d*`z{AQP0 zni$S!$Ezby@*pYQPb)zRaL89|8IgcjNS8f@-fK6q5TUn|$cN87| zz9eQ6@~hI{e$(`+c^Ol}t@Ggt_haS86~=_=96cQI5z)){6mHN=$70&Su{H!!26Jsj z5TV*uB%yyCkLRlgPm1qr3d~4kP|Q>ov(|1t3Cp5)W{nhf!P}f^jTM8B+oCFPb5uMV+`Korvl((RdCxnB2PyNObRji>Z@D&#(-9)|a`3%UvWpB$g zSEwa>oqWa_1r;@-Abiyp2rwb3I_j~hzC9il=16?FIgk?%1|ooE>}BJ^KAIqTdwXly zTr!@Yu;pP*)XBjQ*O3=+^$WOVh3AJ3qsk`zJvsbF$Ei%}-6BQ4pL z5j4khAd&pF|0|YRIL$35aPXCg`FTD=D>Yz~F@&Ebpc9)gk#VfT6gMSNQ#Zh24}3?H zlz<}_$2mkN8WDS^@_6X{#O7gwVAjhkM_migsZtz_mr!viBB)dk%WpP3%E61~+__I3CqfvlBvP7ih6 zvqkTKtH&m>{-<{{vA;LG2qJA`I4j3z-01Fa9&HiQQc61)?vTy=nAgicfAsh>7T=H+ zA}hlMXD;GJb{QTTvPwbI?$3c1CFU~(irBGI6o))`(Pg3`T4p$L+Up->_y+Al$OmGA zA#1cZ;Pal81-HW97W~pEmae#tqmC{}jgwttYyg+)>)Yd&ePOC5dO=Fr7FXbZlG^sN z@9XEwu3gv>T}-F#-Jtyz!4eJl2H$h)5o$m|AfcVIyczd^m*q@EOq@_cCnY7dF6}g9 zGwry%DwInAk(=e?tk&Vy85sliFT%pYq9qHf)Q;5Fdw%VCx$GN=udJ?q6Ze3;3p&iL zukIO%g3=XBf#jOcZ;FuBqek>Oc6G!Fo?;v`g~S5-Q#KwE+M#+5bmvrdC8(uTb&l~3 zs+1qwY%nTIOLg*LSfJ@zRn_1w%6#QA(6#J+q@Q4XJu8KVB6Uj(vwBDd!mf?67dP+nZwUa&3S4(N%{UuNmlW!>aSH;cBt43(3k zwXa+Heq!etD_foZ$fq;;!PV>f!ZFg(3x+k^?v!$gs&?1{seHG5l^x(?WkN*JWXP%d z8Y(e1>+N)=HDlgc8#`aH%@Ywn7CzoAy9q{p`L$bU@Tn!ew0ZhMC{OOg_95JiLIFkY zSHGTz_SZJwO@fmTzuhEOaD??<899uDQ(GK|o|bfW%QC61c-g(W7cY2*@d}P3qeE@- z6qdme=irES4}rt0tDgn5z}0UoVu{2oIN3f%UMe+JG^zi z`y0J2M$0PCA=IUF2<>&X! z)C<1vSg?E7X#kLeI&3X-uAi)+0a{F)W9e0xR%p@iY0_aMh)I*DCP{L6-E56hJnr}} zw}Y=c4jqCcp<>I)cOw9?d>GKrJ(H4oH|X@}TW_%kLSVbt4=F_81Fk(L4OzDV4<^*= zX^0JZxUykc7MU7+!NTvNHv(kZfLfKZYWcxB!mBvaB1hQ+!$VaKdXKu8)>Qg7aiSrF zladnGb7Rr0yd}HFUj$tN$uT@Kp_G8ComnQvY-C7$*iMxrvwbV1sZyNQX6C~V|52J$ z%=pu0A7(9EO^VHft+*X|G>$yh12)_@Z8Dg>vsprs%>EPC{ zz*M%hJS|-^479znn4N67v_T5$Ze#U>KVgxS3#6j>q%4Akw6$mSP8QFc3Un1BtTBce zDoNQ#11S4G8S^*EVk zm0bALb{45?98HG`{0&PY-N(CejHomN3cH zk;Vij%}`R@A|bYo2Sn+f}hJUy8`w{2av6Y#;m4i5&TFT%VX94o80=fSf}&6~~N zo2iOHAfsrqiTWAI9H9rV6x^~vl@CLE<-Sw%o#GXednFpQqI*A+hmh2g7QXXVLrbYd zSA97v8(uze^J~`OS*9FkBI^Ppd%_!ef4@k?ymBr(BRC=gmJ=n>kBHsl);AwLbN;3M z%2P9@%2iaf7YcR=T@YSF2wKm(-s>*ib2nV|feCf^_Go5xeH}nX&ez^Kua8F|o14TH z3Xrw->PweDFUKcdlg9*Y=bh8$4fb8SkBIdMj<6YC+R2A4$JBcUytwK8SImlZ(G&@x z3*FqYI*dm1wz6!Mwu3C!KZ;#DqtvDcubGK!u{xMsk$d}jH$!1;kSBgS5Kv`Fu(fIZ zq~7bzq(;;mVbd`cCrGoNvNL9bqvkhB`Gw6J8lpg3C4qp{v^%SlBU$_4N^xu!jA3Mj zTpab26e%G8$1jFMW7^+jw-x&lTHkk9YraO;E#UYyp{o(zl8i^cDPuO#A6Ka3O?O&U z=IBFJTQ8LEwFg&}&^ql>mPDIaBmI})u>rgGQs^4$D+|3R_i#Uc=^LE$32gk(%qWfP zObr@i6_GdD=T8b3VH}qZE~1@%4&)>5wQNLBdZ~?lw5hDyyM9t!+bgna7mRC>fyC@R zC2m2opiAHEbj4nax88`l_tPF89-6_C)qj05Z@hI&2f<%DGvU5GwU>-$Ov6kO9_2n0 zJzwVNUcN2mpjn;03A=U+MZdPdZRv|k>w+GcpL@nUHbxy)usS_&4-c2AOHTgeP2Ez% zGm42+Ad)0yyNGAkl!*-~lV%a^=^-`U;7mmDFrv%hn#ix8Ub>;h^OJQOhzW1o6uO=Q zy@!K~%ffnf+=r?gh#{+?g+&-pPd>RSJhT!>sIX>E0lkcg05ODF;7A4FYd7=(K+WU! za7yzw>#iW62bHmp-#ek6BFzmY985;0~oC%MZwHn?QrE(uWN6nEoCgaguEDkxR zU&q>lZMybr_SN6T%$PN|!T-b=3yR8bIZ`;BkSOHxq43m`)_?;DfmQ{ch>|W$i#=qX z){HsjD=u5**N1VW&*A8bRVFc4dnFI5F$3O1h#od{#>L};doZkUH_^V>lU_r{Zfiy8 zBXoA{QA(=xX9T4aAm{vk8nc_r4@+yGMfJHk*VZqoWp3s+XUXdwX~ET$;EY~DPZlJD zH(8A7d6$6_jv_}aPDlPw&XI=?xJ0R(bPJT-Wei@?|BM#=dlq`l;!`=rF_WVYKD zR#O~_fca7E!z%o5UmsLv|93lZ*u`_tNh^5_nm!1$UKy(t#N)ENHTw^wst z%SO#MJj31$3g9}Kip zOtqVRCGVQg2ExK^)ds=_$fAY{W==iwT08w%a6SWI=*!DXlG$pb%zLEXUSA^QBEl2c ztLSa6>enw1ZC-Edbl5x$ST9-GEzB>bJ6i?}#7FjCIw7C%Xdt^CJsZ zDqgo-gfDh?maD2dWbcmUuFBQ(&WzXBqMWNeR}EDI@;I!P>Q5-Z)4Hw^cu5*hrO!T0 zC^exN@W${2t^fJ+al<8ta~i71nq*=GD~t!gd+cdRUPaYa$_JP2#yD7G($`SR^pBk& z(96Ph#z;|OVE!ry3a;%5!ydq!=+z4B<&nYT`)n~Hox{cvOLP76z$KM0qE6)81_{>4 zQ+D4b)L1%9tYDxtoY&O#HTLNa57QcJD~UsEq7IG&pOx3AACiT%qRSjnfh2>ptt~4- z#u-KPY0|v}E7Q%~>148nVdmf==KOv=hTOn=nk9bU4)F>+o6w8eJVFgEwQeKH)|dF9 z!%8-~&pMN!i|kWol3z_IVm^)>c2YZI`63O@>^1VjHQ;B%JAPM*^cYU{d z6as!Ied%gedePsOTUuON#TsF|eSTGJerY1}`VQ&wt-5_rofK8uz1?YRiyFOCaMYx% z*5_Yy^Uoas6%(KHteLBV8;CQq8YXGwOtkO@M35Ad^HqkY!Q=E$)E+2qC5+dErLqmb z@nHMV_Pv%pTjY-mS@P5XA`Y|+OC1Y)C}=<;w$|0%$^7RGl#TamL1G;B z&~??2}!CE>S5Q2iT@Wn5`T?`G0#6ueA=ZD9uY zmr@C$5$@`E@Rtw6tBM5IQV)ewZXw`v+gtb4QG_Ml$|%b(u=O&qEniG{MW5_AjM-Or zgdwF6@ek4TFHP(Kk)DS{j7#VJJBfl84tpnWoGt3>G?%!O5s^~QOTgI9M`|}Mq@Znl zIf?hUTzrXIhW-WoQ=T1;2n71*PK=kw=!z2DF8E0%N|x@uXOBtB3F+zB6}nU&C~{fm z0MF+AMPtcuV-3W%rc6G~jLoI-=4DUs!TNKA>fpRi@5c+prP4FJw%qn^aZ@>2VFziu zPFcw*$>|A9*cnof-TAMft{Zw{Q?a%U@>o`P)Lg!65#*<69xo4H^zoY~Mt*PVw#58= zd~)&`Tbsui>Ts#>2RBX^PiRB>4}M*mwEpe<&$RemM+LG@9$Z`XOo9@YYuj>97ZY^b zB!&itBE$*zY4~mlBHR4x#Oi{=7Ry*u#%UPCiie{0n^K>1RRZ~%d##e{Z}Qi2p|CLV ziZx%b8f0YeTBEU6R}mN@@|!Lj7%66)fod>ukWkO~!t2{>dBi;PPbBSevyTwemq!E1 z4PpxgFmGTZMT)vA%S?`VEwMqLVj!%an-Q?&{Pomh;;oXJ;2|dICWk#&Bn|j7`WQAbQgo+3Qh(gD3VKQ9;Jy+RXGIR#j@qv9 zh=`jNa%|?5bLn@}Ww(A7Oo-EG(cCD_?P%6fbzeN{r@CRmQ2v+V;M5k1#=M}!Ewx7E zuP{&6Kc56`sXSgF;2!0I^!K8<28ZO&+}`2OxYu_Jsk1wq>~roQ+o5L{wHzuKV*_X9 zYQTA=uIGC#O~9x`675-i5i>Nj6h(e8!}}j|+&A_6V-svi$dq$mdQ-VxgY1@YZee(LXxDYmK~=&O6E$`HKFV(HL9APTP1x;=@9E!DzNL12t|I~r+d#)iYmq>V zPqdm0l))MYJN?ZBg26GEq#n@?ML}3i;HtaDIY?N__w~JnUfI%QgV$xYV(@hjV-r2tbg2PdlH0MiM9u=b9%DZUI!k z=vA^5t;#y|~g zNMn9mH-5i^xHPJRzOI$!DeLyw!0!oqfzuTfU~A1kAgL!uxLX#0Y;+Ob5%KO#iW|g@ zPF&Vyhuw`WW){4Bjh1Dy%ucr*1puBO9Spr}oN$o9wZ^OG9Y4>7E;Gc_HUOg%h4WHOn9j7w|ciu1kIn24$F|GLa8_wG2I)r z6sp3xez*g#dbZ4BI=Y4BWtB+E16J#b=m_{Zc=T#W0@p0d& zZ6ENI0jLq+kz-CW-bjYedtreb^yrZeRCt+X^tsMguFuqH{L=Mg8n6Ec42mNAKRyB+ zU-?-E;Fk%u$q<6O6a<8bOK^wx#L>CKU}Sxp^V0cWHFf?~vnjx!i4u`naPO0BCIbTL zhJ`-*Winm29pCv<4hT*Uornk1#%eL)D2V^3V|!+++KiKHr+yF;DqqhD4-0B2hX(%| zS@*8b&;Q61VNB0S^l1o6YN^()fshiQSPA=niRiOCrqB$K^=M#QobnPYhMy8354o+k z!2@aKcu@#B8;j9KDRuVHcJ7nua7+2SEdL558#X1A-zYg_xNWRpl)zBHXQ+gd#T#tt)~(O32n6(SM{>ZjldS4 z+ut@{BB1j;oFe?qaqy2k1=K9vw{5PF`=0k@R4%W!;b%$u{nX)BIw4S$mxl*n<*>5! z7XX9EE?N}gF8nT=t4wqp2ReRKV2oUIQ@k@(Hbsw^{FBE5{fT&rS@>vk)}FKTBO1b> zNz|)B$kK^8tH*yP_x+CM;qkHM1mZqquct{ggLgaUHIZq1#T@*|yqxPUAve6o2DB0Y zdM(j(v*Gpo%%i0v{@(5SkK*is@5_HejdOpwLf*L2(Wl$awMc#~LNHw7N~_*pQsy9Y zmV-V*TZja1HusnG=fxwJQA-gP@`Y={nKL!57Sow~5m^@DE#yv9NBk;x3fe!8c|CD5 zxPrbRx&HW_b2eV?2GfJ(RM#mN3UefVn&6qFsx{D0^@;-(5`m7}K!^wjgJ`4uS0o*m zNN2z<8FLwybYZQLfuo5`d#YTDf70h$=r&b9p%_!9FLoCi!*WcY4@uoU$VL1w67dlO zIkJ{%qD|d%uq_Nk9f9_H9!6R8PrOwgrwk?czhtl7pB91A^Vv<=CKG^d!Mggbcrfj2 z!@QbTXwX6;CF556c&KpEh(kLFh^mK3ViDY;+Md(nk!pl$e=ab0UFO$nM!<7x165Ux zI#mF~hpP_p7C-?Ioq9%KSO@T(@`_X4OVv2tykF^@xii3`yRpB2E-={hyI!1wo6#S8DuX*_;NU*07Mp8&r%!ih~;kXTWp=;KJ^WvL}Vd@(%l@ zwXNhQ1Gl2ag2;dS43j$T@r*yueA&R`yipr60*8dKZJHK@|? zzDZXk#3N!@kFQaPn1yUWuD= z@IOZmB|c?|GfaLO^rv{z{L~4uR$&J%!3;M~t?-ci;(q*Jg;_&p+OZGW0jxBeQG-~> z-m}>d%4nPF7#D5;cPX?Pf8`k?ZDXsea`DYl#S={`sjK_ z{J4=x^9CW&*YH`yK_Ca)y~t`U5hC@2xzrbke;C;LN#g$+@Bh-`-{H9QY$ib41bN7N ze0bpD;aMqpd90En=4!`v`gOG>RJr!pF$WPkg|NSN1S7CjKi36xc}Qb1Rx_P1M48;T3a+);NaS~{@e2|Qtxd)PHh{o+*GveC z8wqN$-?~Zdc@6pJF#>E7@VB{>{HOLG?}#M_d9X;%(YpGsADK6ibi#h1`(NsG0>KNK zwdN$iQRkmq^sQ}}q_i?!m6262Cc}R76qDt-z}2gyinx@eJeW~pwj?nMeqao1GDud`*FhN+S!YJ?z4Fp3NVJ25?)zHzbg!5q|v3%|yt=_*3Crctr)^px3+D?+pM9?ch*AICZsY ze>M=qhRdfcV(%fOUPf<~k#O|PO#|s|=6;hT|CyH!FNBDZL8)Og+ZSFOGa5tX&Sw7` zLAY4$9bl?4<3?*eU@nO~Sv@k2HS?7TMzQJ(hL>_S>bJGKjq6u+l;L-r#?RhFb$=RS zWd+_wex8au*bNeI0$+b3-gt+ZR(tmbT@nj+e_>|mZ<$$GI?16NOTP3+s&|CqGYq#_ zJ`&KK@?aA_kjQp6ggGPEF!mrx!X%-EkwxbqMk}HzG{D?gTEEJV1)hX}y*(3Pinhvl zaJ!)pWq^7DIuy8|kMk#YOSj&an*S|*{UU)5Aa3F+gFvoK&%NFK6XO3Ez2=IP)S=M7 zLw}6K!~r42Kc!e^g8%b25IoJ+dLp|eUI`#$X%w#@%xO4Gb~eVsV0UI?DupS3qEZ1C zAm}KsQQ;B>yBLWS&$@8`8(mZeJvu$8lcf#=vs22H;+5vH;i8A?%x#{0E?A^!P5ix0 z{E(XyLSOF+1@jTJ?S;i|rEr8oN|Wc=>8hv-J9aOPaiW^DT8->Jp!7b2<{;zEXF5OS zkB*obqZCFwEUO~xG#S*0V}CjNP0Yi@o9;6)s(LbD2XD%5#6h5fHPq$M|Jce83^y9T zumKWt-*Xd)bjE1p`*L=l0c15NUv|I50<$RBnl^V|7Y&5zH-{N;l+Dl2S3TB`>;*W- zawq^2JH`niOOP|KMBT`MSY{J&0QQ{6Hi99{;c^pgS$Qy%B}92>6XhU{K}s%bon?HZ zHnL`mY4#{`SrZu_!#r7ZQcY-$GGFA6rytq^Bw!`5oG~O8x=rz{$6Yszx=`TCqTtD4 z;?Gh1&N!ZLm%;<{w7{c1YPFU$LAykH?@(4of-V}G^3wF5rw`CIv{bB&mKndg@tco>r{};A`n}ef8T;N z(*|4vWD>Ts3K=IhtG&dPK>)V$v_}Gw&L~;0{vrsR9(^;3iI~9C;PL*-D-3zPjk(wd8ZJBf8pgs;tShUD$9ANOCo;+Sep#HY`iT@i-+JD>g)o6k>l5X#BJFD^# z)!~z)w0_yGufbZ;+8Z&p0qQjIia)wLjBLPMEvZ-*5!3L0S^x*Kkr#r#TDN{(7==%O zxsIOspCsM`Ck5<0qD$2nYEwsfv-1>z7BEWBqW-Mp{&XQEa;}!_t^Oo)Hh}HvLlb;* zfNH+#kn5qY*QeefNhKU&W@h)PlW8;U6fB7VXS)|a_?@Vw)2T8f5Z*GWwN_}ajv+R8 z27McwDK#0M92j8zM;G(l=DV9lG{3pO145j{u_78s92&W3iWwu$=YM!nyCrbow6|LT zj_(HmBS8U_Sis`=zhh!Qw0&U(HK5Z38W+N|`*xb3I5gm#u4inS&c@kjyTGjrivcdx z%+ZzrwgL-vxxIm)JxQxfMAwzy9z4JmuG`|(RVY(ilvZuR#??kJn>t ziOd_@QV}g)+r2BHU#n>@u2Ej;KtMlT5r|1MDWM(FN9fJ++o;7tvX8#(F~$(rVKY#r zB?E!D3|2NTX*hz+No7TuZ||WMa@}gwOAv3!~rbV`2`6- zno{b#PRWlJmXnyt2BDn@o4USvzy5P30LC6b)6zA!1>mUv=zih%Cko)r9XPEzmq>*I zhc7_vdIH#-XHKHoDj*^SK!S96+Q@>Qa1uJ8;sAB_z^M()xv=MG#Gd|>5&`)1HX?b2 z1V)z>kqK=U!^Sg~l!SLuT5Jm@oP;R6Ql14&|>l#}JLE5CZM z3ApEA_8ck{cOtTxVW}8d5`Oes&-oBTTkt^xI-eE|8E>`ht-`A-~#~y5u0K;-s5SymXyM!walGqnC3I2BA zX^=EYABO_Fn`R!(Y|JbQ)q!=|gC=Krq%>udsy@q*rog6@F59tO zFzEvtg?e&WUXe~M2``dtGC^#_sCt|5jO{n|@IZ325adV+E>8^b0!b(Rwm96taUfoCyXI~iL$IcPFcHPmBZC4*fT*L4J710 z5-HGZl!)3ORs7K+t6yt-XWKWOP31d#*BRBS%>d^4t_!Q%8w~i|?bGzw$Kblv81P2Y=8xsdkzl7FH^94~{ zIyj>xDS(N(+0myA4I9ZEvkRxQ_cxxO4BV>?`#wZ5^mSvXa_DE&&$hHRo=U{RJOPz7 z4QvwwlSb-C?50PL`^l&bS9Cnj8FjMZUDiR`X3Tqt#+e~uYLp;lz6|6t@{JCyk!{b$ zH?%<)A*R6E|% zkUqe-@K3qLh)!U$*hKAQGaoUu5lG&I8&!3qW3elDj3l%J&3%davcsEP@Of8Q* zn{=)(Hu!p7Z$G;wam5PTi zNDQ|Yrkp?t6j#8@e{&rbH_&#pM>_F67k}V|_F&nvcWW=$eOg6so+*zDeRz1~17^r& zVz5e05L@Y^YWx%JB34r*=1rA< zE2fLFRDVy_!D11ynD)-^35)ZK@$0nway6WGj_M z6fs~)dP8gxY*`=F4$m4cuy4^nAfm}y>3a3&@-mTfjC-?z*geM0S4c>RS_Z?--Tj60 zB|iT^8QgaF{w~yu%kOou7`YD0=NztWX&GVZc@@n$(luV$a})vL$4CNr6l?AbP$fMs zUlxj_!ut$Gv{TmC8p7n?K^aL9uA#07Cql%C(U?NCd>k-5V1MB%t|A(pU~NblsaVoU zauF{DjTVI(7&)Ljp&D$GnXnkp*TIeC_s&1y-osXYQ*!Fpunl>ClyM$}3-8=jXUilH zkNSdXwq8-|`oZHaOC+zWbs1U`g5>vVIsabOv_8#9QqAk6LV@j25zTq!8xKT@<0~~# zh2exwW58&*8mhpY&hqd_BudVzZxb(a3F_!|yDKRvd3XGcFQi3`jf?Yqe|>J*OeQu! z0MH93Cs8bkWv83}eq}(KaaQmKfEoeZM7n+H_9j;kPdb(pd~1IjSU}hp*R{X{5(bF+ zald<)9XEHK6X!7OvwGQ-pHH1Ks8T)gnEX( zwan`sPZbOFpjtRoAYzAU^6C13N8Af4 z=m1y@>*^951{fdBUn6_pGT(D45oU4(0jDF4UyBw!?lq(S9Z#=U1E@fO@B{onzDMt) zQ^cA8BTiP9&zb(oHTEq1WQi3ZBS(->`GA`F`Z*hk>b!f?oGG1&jF~A5;njfhRlrk} zD)zTl=MSEPF5DbS=y&B$w#xJ-Wl@|nK7HK{gBom-WeW`zORpi325<-v3lL^jzG_@# z8;$g^ANc6r6y?JVQ+2Dn+&zL&A8m@$R=tB>mz!Vo(0)M}k+ zrG+>2p#b9(8_en*;;IXBJOfTexB9W&9AaqIvd#ZrDcZEY_PAu>IRl`s#(oC?|JXNx z+#9^e$4P~A0czrs?~FLPQ?*^1`y?3>Cjcw@`mk=_B|StTnNb29*eMeS4^3h6h~7T% zCP@FdmynaX$;&Wx!s(Mg&w;w17jT?1ub5-4)XdO_Ec41j(6(h#*oH85gII#I>kXB- z$hCOrLsYbHi}Vu951#MnX!_JLQ5(>hbB)?|n=*+T$hH^6xBT>Wu7AID$oApAxi#r!35rGQV11)&%FMmvc4*a^IVF1{<2nkcDxr02h0*bwv zBLnrIyP3dYguJBRcvHqmD#{Nr^_aa2+g-|ZroEy@C;8QaR>?;GFX?x0_5w^xe-@}@ zl>daDPYh-Kt>W1M&x*fgk`R(gNJsY}Xjyub0LFQr1O3mxFhgxnbs21U-?ipy)hw%n zLY%=q(lt+3%7jK>WGR*Y8M|KgNEtW^I2n1p<>;tDm#&iOWyaeqPmtqyOZ?gQIZ?-NR zuq0kjl>B!AIiap&&pVW_kEKm-wlmR}FCV)SkLrNcITSG~tJJ$!Tjb9`;p zII~w#5x$q!N4gPy4NFQI{P}lw2p-P#&Aeg1KjCFVv>Kf2^x*QJCD@q;D*tMBKfM_q z9`CU9FD7SMXs5%|1BONDFz0)a9u`q}k4u?^qM6^`!N-WjEfrS)33>v)kP4n~UPXLY zC{-(&KWTP7Gn;$0&v{@W4@P@>e*yj=xaa-8MmN9qV)`NWM;I!ID%J#ON&xevw=5y2 zK}UJ*lq9p~D))o$-z?=VvGZM08Yp+91q`_+Hw>{GM?XZNODIg)BF~FI<>p8(G^3;X zknnCkWf`EwCWbe`SzC3s;|{*JwrOvKI|M9J5A+sfh6}rt`{-Kd(JxdGN(J`~&mp(` zx7VHbBETG30AvkGUw?Bc+uOIQ4xpxI^iq6hpzz>Srxwj33nuD7vD7vUWRE6lqK!vi zf|r_BjW8VAZPLCK=VH)MlJ(OJhrfN!0{kg=cF1ZBdM+q{@r-GPPf*Ydkd*;2v!dd= z|HI}V89P(KyBFVdE$f=i6~X;<=jzIEhB0m|O?0=XF;u@giq{tYJ6i2W=^Jeevaml* z8XwZ1pFhgwM=I3gI<4pr+82avfJDdxU@)G~akDWDmD*Zc^Ony5_rXCRR=4Xr^!n|K zChmKFCA1JhOlxPSE#v#<%QUi2T-iv|@);WuN*nMqp_&PPw?DW|Ken^ZD%_Mu4m8Uz z777p@rICmeHEm4f|#Pm^(>Ua$vGPRmK(}33*_$$F>DEZ96V%fX9(WcA&^5CslP|8Ak z*pL-?x$$P&6j&)B!EtSgc(`XK8K!4uo`IX^`J^ zX2}$MW}vzI_hcTWEXaGJVhUqeR2tjcUpJYA>>o%{&9WXS{&)s)6LhClZI~8_rOOdd zmivH#yZnG#s@Tfog&{eW*B2Vc;UoSPh9Rm_=8kXWt@jmoV`hg?*+u%{{vW(hYhIO{ zL_eZJ$*@<0tuLcFGtGNc2T_T8Y}}5lD2BqG$@SGJRCQNi zhl_VJYmE1*&eTF9h=2j5gKFoba%0kMLFN|#G=WnJ2r4;Vh{Q8};=4J$A7B)67oCqg zTUz+M=C9osJB62fa&oeHl60$}3m&0?Q#Q5@QW6ojv;jNB!O#Bsof!6D@Dt0fL0^>0 z%5z-~Zf?nL&dRAgs|?Rr=9V|=_rvYw$n=UCQv&1?(W&3XBE8cMDi#QJ<$7efqL9Ll zBVo@mLz=i3{2iwD8HmX63cQieI6~DU4acNkrM`7ubYof*;;w{U*WC@i-*)c-yrt77ceD^4*a$uBB#AL}_lewIf zsh{JXgC`Q`ymcZ5EP--zbB_S}UJ}@jd=F~$$d<+*cp>{@dW-nm`I8blHERN31OVC- z&>9tJY4wu%^gb3>rt{0#I2Ip&(twh>8j>@Jl5+++LQwYZw*-CST|u2T}W))vh=BBKv<) z{&^?Bme(R-WqCPNbaCDM$}tm4yaG1(f*O}cee~IssH9s(MN#0Q2LiQnm*HEAT8i+c zFYI`k1GaW&aLl<(-;Vf#uaL)qRu4*riZL;je}-Ghf4c97udmBgt(E7sIb~mKrA1bW zGl*TCF1^*eT=KoqtsLEv9CqzMKvY4ZUyGW%jwmmw+w_(F*~Y9$tWwipIO98hZ8qBW z1(_A#qBkU~Ub51=MzXF`kD$W@#cYBxA#a$l(%K7gpYTGC4WxOh-0s*OrKb|z~T~h2X#lU zmfghM)8;LIsKdy#&pgUck}b*FC)|= zBhUb;*5lQQ#e`)u=3xQI2>6GC9o5Bn{vFn68yuNnba%Y?G=C)9W)Fn^EQlgF%KIlL z$${G9KhWgK$VtuGdH!b(kV*|!fxR2>mZS6JH#f_m;$B{EQdKep#WxsG&um^3LB0#w+@U3dNf3m11}LE#WBOSB2Hk z5(WOrt+BOXjng@Us97GNo=0lK_HuiztH#ADR<3mB!r%?|XtX*`j`Wl28o?$&E-n^6w?A zV3i?DauQna9V~#14~d-iYuqkHdId%10MeL^g|#qLZ$3d4o(KUm;c}bXYJ#}S@m*ng z$-AFTyaTAV(xTOO462p{UQ9U#kJvh?x>T8*ZNw5Hv{tAJ*YS+lRkVoik2K?uQQ}d= zs4qWX{;`o@B1e+Jq^fDX*ZfxF5ATBaie7>&4TIj-s*wtLH0qV540-rlfj{PCziqwz z@4j#C6|&b`-IqAek{l8Fu%gu(nkq23HEVPSXI~Xz^2?x0DtM4$M?jneQ#Zf*MmU&b zP5$hHh12v_Ni+3xMvNxw&E6EY`2$^Bm=PF}f%MscyV(cuDcbC64Zwr~pg|3$1J^-h zx_H^vuU{%<6Spu4ewv4%bvGk6UO6{3Uz|e1LOL zs!veDf;d{7!eQ^L7)uA2HJa=`V(EGVLS}mYsb!A07a%H$VO`jYmu`(Fz4epZG{Gje zM}cBG@oPz2+LDrr_R;QJC*3N#j4p zP=!&;zoRYI^HwF_CEKMc^;zE+lW$?|qWDt1{tqtu_l|VY-;Gi^p65(DDrMTLv!%10 zFHw&B2md8z8uOdZ&(DAQI1yw@T%OI}?PWWN=K|##aPk2E5%HN?nHZd2%6}5sP~I-o zzp@SrW~S|epUnF)&PSR#vabmuiF0s?Fg!GY;=4X-hrw3#?}`>4vE(xOl=Az)9`epq zu8XCgmonCUC^PO0x7`oyEQORFrB|xxpJE)}1-E!_Pm4$92L#oJS}m~LR(!jo{xM;O z^(vFfTewq+n4|}Rd*`bmFmv?X{z=&0#Ty);+w8%kd|<#)bp}up);D?f`!SEiikRGq zaMynFlTcDA@TopeNAG1TrPL{Yh;;Le#)17d*W##%{tgunky>mIZh42@9=M34_(#i1 zV^IMcIW%w+*iGO`5(5Tg$jwooXYO4I;q2@Guys&OG+zI1wqCsEmG%SuXb3o6fWZNF zL`~0V%|D9&p&zxmL^Mi_-N36W+CIn(u*}7gGM+}+e6WlZ5XpQ8Q>^~6E{0C{`0!pU z1S^6u3?3h`L}gi$1YcJJh{0RJR-h4PwQsEA%U;qrj2VHnGgz%%!Fi^$%0uS?8l29t zJ)E<+Ks=J|s&(PQ$OH}seCY`Z<8Rr=87zLE+bxX1-MmE;upz1<+Wj`8Ny&uRT}zSJ zP(H)LnczKb_TB6DJw52lw~`~cjQn)Tpo7Rgg!h$l0#N;z4UqMN;3qdKTZ!|x=SDz( z=HcUWwy|*Ml&C<{2fUHPxd$2>8|`+7lpO^B)D{Z&{nSYT=*t0XF-(#BV>>t!Q(r|h9-xZ z<*QjY-D;5~D922Q+YXp^JCIqn zdamM`*-$+R8S(^-zg{q&_3LvjXF;-_has@u~J@pkd@eo)!Oz#LO+ zAm|E8qSAiuUXHbJwg*s30iECKYN2rv0>aeU;)`gnJY3?X8b=_}!GASz86=?gkndB# zI=8^^tKrvoaPcO6;7+UMW@PK6X5n3%B4p4xK?H)JDgH74qrdZKzzg+WK{El)DIx|e z+p;*1ej{#a!uRr2v^F=wKeEqAilWw+Q?g7yi z@gxI9;`VI(yayoO2!P}mxeX)jV{Z^OY8{EnMLbkh)YrE~!*eGUEH~82eV~T~KEhpq zc@-yTZ=JAXl90#YV%c7Ql@H)`H`KWsBGEyl;4k66M~#}i*p_(YqMb5PB_3VZ7-gmw zM@*phXAG10x@rOYzTTAC_a^vyy5a4uJ)(>j_icN==;y>QBKoK#MQu%CFsLNN`MGxirwBDbQV?N1M( z!6K_Z;_Hcicki*MRB9mmT(-05)MR^@$_=EqavX<&1%rn*s-B=^`~FVK6skUXMP&pKNB z^Qm0J@GFQBu35-UG7key&gXFsFeV~cZ4fgu(k+KekIc12yk9%0XFbt#|ssiLHpk8n8Hh%=ooxW@pB2*Y1zeobJKJ;Ka+9AE=G9 z^RK9tenL!?II`M^Pi%fL9Y7jzov2B>GpjE#A}Oo&uq)=jnTXvRz^>VxZtb7GVXHgM z?TRXQ(IP=NCVQ?W*wiHAfzo}ch(nnpUs_HOlghiYM5h(KQKeVG7X7lXy1v>-!CLUr|36fjvOasA>a2apV)&HvI8R7MSt7Q zg;43<573zbJUV9W!pXO64gc7X2L;=Zj$=xI6g#Mn>ZVQ6nlGHu!Nm2Ph#{W8p=ZL|70Mb;OJ=+z*s9O`_QDJUP#+FRu-%f6H0Gxj@yuoX|sM znM!UD$;^C85+9dR_QmeO$A`bJnL#r-HcT>hG*Q+S$jiqEe#F0TeKNSx;R znRo`LM&7P}!$X}tcx8NR4xkQ4*y{dV!ve-3wd}ts4eWdXXFgh)W0W;!)-3@7Rv0;6 zrkOK*%Cs@&{(tOGxNQ4nes&)gB{q%9u1hgfh(7Gcw|7Vy=38aOe^;j!O22}9xTz{-G3jb7HPD6rJ992{@$+={xNYP$c;VfG7u)!y>0824yah)X{O?QEG2Y)- zDtxa)`YL@*DdktFGmORPK9Q0Rgm~Ri^TB&2YleH)+^9BsFIwvAlkiBsuZ5HgEOEH@ zm)eH60};@EBh0oHA{)|2qrZP2(ahMK5=9zd-k08TQy4ys7NKboy5E+Os>7<>wk57D zz~I-RnCU-n_nTf0Dr?^wBHn=#(+YGJ-vTWFKvTf4YN$kku0bLQd2^EkW@u1_fw+?T zL~8vT4$8$TAC?I!lg_*N_;}YN)PsLrg;lLzO{@8n3j`l*0IEf19M@jIyu^VX@_>w- zh#V)bl&Je_Jp^CFAf>LJScWAyfRkoJOc|4ef%fq+`>JCbi$2F1?!?iU-@_@jyKkCP z{x2{L{;)G)goUn7W*pqfGHOyX9(=K_`|A38^!Jf^ia;NI32gBbONZCClwG{oGu|%< zDGwWi(mGDb7noU2mi%=y-D&q%1P+dR*#@%*Y4y1?l@QpsKb}sJjHwv zC%0C<>Q2}{z#P1D765iYywd}DM}`ro`ggv9k1eZQ>aKl*s6lP2nO^Iohq8>E9BdpW z5-DkEuh!gp&IG4=2N_0)kI2g^5k;DCyA|QQ%i!X|auOxXEb8>)-e@Fa7t=)J(#^qH zyf3J4*4-~!H`x8j@wt#-IJ7NCU)5Bu)cf8;RuOqeg4rJ2H{Oz@vpW(F8E@nW#N;iR zr-Yg8WuHDd<{MfJ6__IvMihVN@lAj+oAEd4VF&{jJ6 zep$nJp9{PK(M#jw+W&}Hd*-Ms@_@-B)=O@-KSn=AdjE-90ayZnGvg(nzamebJV~5{ z8y`X?{>?gIX*zw-Z&sA=R~#|+N?#duEwEP)X^rKEzkGF<@BITlOZPNZiyN1LQUIia z8f6S-x!&v%8DN*-ppz~?=UzgRCZ)ZfaOT@AOERD{Jj79YN8b94$j4jqSwBV|I=gyz ziQ-Mhsow&9YTHE;HR%dD3G->&n6_;OOC@&5?;kIfdRbGb#|QBjI1evhkzxN2_bl9w zFUH;T3oqpaKrom~yh}`xDI>edQn@c`r|Jy2#VJzV{w?=wra_AfD04I|!B5kv6AhhP0Y%EaZ7m}L}jFJ`?SsW{^T87NoDv>0sLUu;g`vh$F`9B^G+@3#R8`&}L`py12&ETq+gv)@Gv_yeLg(0q7 zOvMQ0Bl%3{9rwV`y2@{8P=yGh`brcKSq?10o&`Ok&ts1h6&DBO;K@ndt%J)4K>Y>q zx52HG&%J?tcbYPNEv(c|z9;}myjv;?Jb*uHF!B8pR4x13x|+0$@7~>G!$%&Sd|K)s z`C{vG-u`?=mh_3CklQnwuz#KlQ!9x;u{M&uGw?o6LH}8yPcKweDI(E2CqoP+E-s#j zN1xoP&w-5!VW*4=FY{856B@Vb`TmnC>W8TCsdIwCfRA2E4K0arD~wD_{wstN)??1E zx~4RGbVEcOS7^~>B77PACSBb3?-Qo61SGJqf!>|u!{20yOOxg+UC4l+m1J!O4|(8? z@uLBts?YxU*1DS9No03%Pvrif!SEUmF?jY$#965u zB1*k#x;X8pOqwxF?vCu5nH|g-CAZ)44ySt|enlpuAb84cw9g>^UQf&p$WZf^#P9#m zS#I|i-)!CK#R=<^%Q)-&aRn9UgqY=U&-P(M;^&pD_olQIA=_(3F|z}ux8p+?BUwZk zhM9m)7qiw#dIv|J-D{)|xd?+_x4_r3%tIVHn_GMqPd2rrX<%wwpe6!P9l(XdLnqYo ziqFS0va_il#rI5Y(O%0*Y{Ku_-dszGidul;V@t&}mUvC7r0ER%YVNcw&kYrX$i!{P zKPU{-rs>n$COxFndvR!mo59=05ogapQsP!X5%xZm&~{<#Q=E1W?rGoJ7^Z9sw*0fc z6ZzOlufMc>@j2g|hiZKju&g2^eJk~-3{%s~>>f#0%(#;(4UT6RrlqNvuGToe{G@6y zHiSL$p^zP5myiqZAPGRAdlZiioKP{Eh3=#e8CKvfxRPKNh8YP}!xuD;_QBE`^wt}m zvBj=Dv74EuDVL;xk> zgZj^t){5Katq7uz?@@0ah633U^ll4kRkfdY`$YZ2%}6LalZE zmC6^=Fw4xy~hM_FU?&h@OSs4jh)$5^g#w zST>uamAHQpkr( z;G!DdU5bM#3{<&4{fCRSs0rA@{kP~~$B0;D?bPI+%g7=>3=2hEN(!R!`>pIw#HU)-)4x10BvF3w%^t}#&7 zma@w^*?vOr4>01k;VtC^NUjeHzZ>$AUPE{~yf&asG#X%ATaNi_C;o+FZQ;vp7;A2G%< zc}^yNkP{bV6vs?WPFDJ{={cn1r2711Zg%F)G@P#iR)5>1gIbUWwob_lIEFgBr}VQb zZf>ypZ4s;UYP-%rm&MO$_Q<>2r&sSWWYN#!7@0&B=*U!FnY{uc#IFU>xl@J6+GnKcB)2d3 z{F=cv(Yxl+uz1~D+SkG!$94`}>3wkX>1D42q^6wO7g6oj?shBigLxZ)e=AhLy@oy+ zsM`c+s)kfAI4VU&%>Tx}_I72(uT!orPReNEAxD+er(5B}eR174Ctja{kEa`K zK84chgiC}3Lw|c4n*ao#@~2)-m`)g}L?E7E7ctEbB{@HY4xl2BjJ0TcR{2;<+6Dq2G*#88q{LTVw4zk&C0>fFDka& zU8I$0?;afX$=szvuf9M*>Xf^e*Ek0nT_^+)9Kcc`zg0&1jY|~_>{|lqQNx|k{VNH& zWI)%j0oU-yPr;3~64DwjXQsSapus@)wt1lzWpfjju=msrwg9)97z z_BqEgSc^8D11V2AGRkzB^4CtruBe&fU*Ta$3q&xGJ^rbARfO*3^Bj%q-3FiY!$zI} z&T_;S=BTQJMPL+1MVhADUb^X{)glk-*;aE+MuE~XdQ7`m67+OcEGsw>8rpKPbR zT#QFWREFf$E}%sBN|cX!SB`kdyNAyd2ZRNk`?>Xg| zdNoq0(USd^t4hWXL8@KGNxUX$E9n*6wbvAXAGqo(eB?AsD7wD7{nTwT z;DF{)a1(N83EQ$^C?5@5I@>*{zMS>{Dm`86Ta}@S#|u1VeN zM};lsLXR|ekAj|4pM}5%PiK6NvyAMZoa(cn3OJG4u2cw@JM6I2yg4-zHTwAU;QR6amp*4`#6uwd!~o$RheVlOo_DQZDE9y zBkLA%iG{m-tXTT9chqw2WT$hFpi0EXE$ebQpSxAYa$M{=q;-t15iuxbtON_Dj^glw zR<;r}gqo$9NFR43)I2xPf4|>@sQZ1L6mdc-Cw*rgmbQ{(gd#mfBX0ZfV>FJ9T4me12Z+CIaw#-Qjp(KaKZMn5xf z!ZBLpD(q|sk&ujpY4Qk4>KM!i!>6Z~_V%0t+RUEvLDkvor-UuL=#BWkpWrQgb`Ble zJ~UXlg~*>MAYHiV(pVg-=M?7R*50$I98|@Wwt0^Ww&_BAvQ8@c-1sRisy09!T3cKD zygFxkNz+?2=?JX)%&sSp!2j?vXmP!=qG=?czB=Scb0lja0!m1JN8g_tiJFxHTdsfj z+V_onW3?zi1PA>Q*qj*WLtP&D_GMX5w`>7cEBJ(ro4px&#}T@sd!!g$M55m^5!z~% zs@(ngxocaghbK5w@WfwinOyq(n3?EP^*?&_-?PXicBs8@%L#Yo9@=OlGa`A;nl#~Y z{O-Qi^9a~4mDOUCi%8j(`QCCf{MH5=veVUm+1Ka<#+k8zA)75T(2pahiVxSDI>7gD zfd!wexG)X;||oe!3Orw}cPNc4eG} z?jC4obp$$76K;4_4eeceHnb68fVb2SL5*Je2IcDJlwc`JBVGE^Cy(P32j7L}s%XgQ z-Ts*iO&^jjy*?#tOKiC5StLD~l3b=Oa`>AreudA^O;>v95_S8QbKq5`7=eJJ=$v?< zSL691XF@AmoP2kqZ+34TH>O>U^R4u^QD7B4Srh%!+;{jK^*{UuBs+8kE;T~E1Hw(9>QI9CRD>`Av>M`^L8vm=+F%tq2%1&RVR=udJvj3n;MMXr`?<__|_z zQBteBfg4+*Ut{nDFe7Cxd6dx7agNyKnAA2gBZu5}I`%W6a_lB@Hax%CSrbX+H3fdD zeQ4fsZ~IXhxsiK9tR|4a#TPyYyQB~BrIPI_#L%L#Ea#7&>JTx*+Gn#F&)R>F>c^M; z!Jzv$Xs=WM7Qf16t`jO3_EhPlEk=+LyLqj;rfQE-*DO3I99Er8YQG-jaJKR`N^wkLESvU}8L>9rU12!!+uBS{&CjQTO<&A^T9e{H9~NBJX08fq&~v-j z&s}8L-YQIFE=F@Q&dRIsgf`ST(e$aak^b|7;(qjl4RXlqWB73Le>cDA=Dlf zEor?UxXal8_WA(XbWwU}E>j8kN}#6)5-#dQZM*$j;nKb)K=;gj;g396nA*zS>I)gq z`>7NGkZ0gZ@ug<2EGf`yPJ8zJJp}_6HZc>$^I%#0&ou1_#oDq&$eEozc|B0GRivkFl)U=H&2FywRE3KKXq#L(}~y@8RDtFl7Mpd&+0H@ z6qd{d+PB%rKwKtkPE2N9!;m?9SjAPf{I<^(N;}DQ7WqQ!J-#l9nQUC~O}6_KcJJ@# z|7p+6mc+m*$%Za~c%!$Rb?{0G2yp!ueV1RQhJTu7^2rFTO2n- z{7BAYk<_s3)dR2bHN;&O>K&A#>+I}7j9jq4`C})QF*0U`LM$WR1>c}3#RyP4zwf(9 zzUJP&zR;dNw!V%AV%L>6=)_Yk<4O7e^ZKe|mxD301-C7e@#yn20BiiymH}6(o*pIU zVko{-XS5%`q!Qg~`C?Mr$Vm`dXTkTFMab7d7wa!oge?w=x$ul_CGYv zEmsks{cq|TfG{4}9(xAGBXsM_`jXV3rwdeRj99O~8GgA5j0*azTNJA5(4;2Bf1bpg z@%Gcteh=ou6Nm|&_}ww*R`lIRBb{6OE@j49@>ep6aiLn>uMEi%0c@~sV@?58E?sc8CU0lt8QiFS>3`b9KyQTqNUmT*twbru~gbiIP0gSt8I>!Y31@a zj5;b1_uC7C-qG+==Rx}wP12{F@_y~j%wy9Pe3?l>S%zqw5}Q9dE_bxn2*KGqyP6V4 z$OD&A-mHA}?lVZ<)%B4!q<0_7$E9J@2o1>X!5ao{s&9Y(PB|^s!Y6R|Kp6Y~cOpQh z5w?>n{np-?5^)XG1gHpL1fQIE9ZMqa?NJwogr>9n<3LtaR2+oe_LfqlmG{R}@PX|H zuo=&_FIn4pHGT6?cfyqqt9RI|vNKh&n=zEVNy}!I`Ht={zo2UyjAXf<#HS^5+vQE< zkVdHd{+M|)e95<6OLglu)X}A>S_V0{vQO_=kXdVN3f+FyE^X#jvW_{eT9$_6%8hCm zhSC51`6a+Fkg7uh#u(QfUjCLS=9L=iF!XH~Hgi-r+iKsLj-{GAyynmx ze{O2_Sx=R8H?3a-A9y@+k0t^Fx90C}y><}vxu?nW;Ixjs@A6~E8Tqq&0eHOZV(9c3 zFCt5#OTtMFDEhf!mDe071pVD}lrOXk0YxE7>X+Eo)tBTB5(7)V^PRxnO<<@vXXTxdjYJV2B7v1YU@cB$NBJFY~V!!Qa4Q zuJ_9P$?ulEZ&OD;7oVCsWBvwWqn$tJ|EA1H13jd;f@8$C7ZNdW3?jPBJVfD5=&@Jv=vfMZsE2;^TCo z9|^Zqet7=!HZcyj?Jt3k-wt}#%f399)RT%?{q0h4{C3*e?ugIX7<=woq*I(Q<Vd~!B`Y$egZwbF2|GK`gj(c>HTJPp{y>!DvLPT~H#ge3wma+Kh zC6vE=6LHa&;a$H8iaHK*yQ6S>iNf4a$gCkF9Rww-T5C8Vh6rL}b2L`(& zv8;%h_+sws#A5Zvu6!n1tfFyS3->jY%OF=zm)7HMZt`z%Wp3J_g1d=!Sv!mb`nsGH zoZKmNy_D{$Y2z)M_TOizY7rw+EcQPD9br1b4M$}zpk>7sE`z+irJGF=V6M~q9MHX* zbT4Wa4guL0m(ktd-`~#VMPCT95-~u&z@R=fq;Ya7jd%Al_6_&0b;MR5+h&FN4aj*g ztLXzf$|?DEZHO7Yv1E{Qe#`m3c2H6=FU*HuCG8oX^X{t;gp6^8_vzvFz4OBN&{=T| z$XC&7rijy3hHi4!utC-Ogl)#=Cm3*#s1g4%&>f&6d)?tHpkL(~QGW2a zk2_c~K|r_@jrAxGD@Nmkg}|xRqEf$xW}T>IyUB?$ciUp|G;W}eSOdczy9{8D8r9-B>p@YBwhd+ z6R@oZ+oYc-H_U-=B(bI0Z;;o)SGUptBQoV45mC+Em^2yyCR(RvZ~C_`JnzU}DmmR! z76gkJA6SE>F4}+W(JxB~x1OR9PV2IN{#$xt87;5y%g>}5=MGGphN>>wt2=zk8v7QJ z^l^P{_{p`ZQ^7Uqny@n3umP6SC`0cb>P(B9+EFVwT$%Z|8E{_c3Oiy&So-g~_vT!0 zIR^@Hp1asC-iBpj26Y{n!%|4XuQeq*o;B{j_noUCP70FkV%};9KsLAMA4JH`Z+_DB z^?!D;^tTWxRx&hfbZ*^%KbO5PXo8QL^erS(i5MYkU{9Bedz=tUq~)hr*P3J=t;|-F zr~5?ybp&}z`52dE87DLDX#%5=MP*8)?AOkI#dR&htm1X1%3J_Xrd4HT8@Gm}oVy1f z!Y*M`Pg)+`Ev(fi$^iZ(SQ@9X>_nj4G78y&oM8npOB*sV5q<&loHt(_`u!wS{gKuVC71qZ#$_Q>`ug1P83GXwAM_X+=M`XnaMjQ^S6` z+`K#z`F~#T#*h+U!vsLwzJATU=p*6mHD^aJue%igHu(9gug!^luiZk}lR12J%m)hD zjZ`Wf<6G-Z_L)OY#qwOV>vUpocZDtIJ}=CE zKYutn6m9%PPld$jOykYR3x@t@84rzVXD+KI)k?^2oCFN=2oyDMlCr@&qk}RU8`E4x11}F zM$jh9^;-C{h0NUDrc(Tw&L~~Zs@7DP*_AQ);u5m_huO{fA2{9XiHpTz^H40j*8?F8 zvqeKNl5~6^6Uq7X3+*c<@#|@QnwM-h#pq51N~3HxU)C;<3s}PTM`k-wK#>5r`hfUW z%{e2Ynzsc2pnn!rl_(b_t-f*44}MQ$0sASScmk>iV~@Uu2aDEgX);?6jz-^q7EOv> zyXXieCSDbF-5m?zR^C;ZkUw#me|CX53os5J59TS}SM&g;RN#I9ZyE4=Pw%TnwYjlf zoSz*n%5bK)I(~pOnVKWp^%k%3%IO`qYJU~&+K3~E9)nWhLp#;S2?19T0PofTe7;k6 zBV)aoAKf3wsmb=2RF?qVR>>mjV=MPW$)ht&oSLs9kRlOW|B>1$FC4XQaYZtRgWvtf z$qbJDSk~{N3dmYvwa(L4$V`dmC}pC0joI5P8iIQrVlUZeRW{#9;TOMKXuYajoYJ#J zm|TRWm~uXd7`s?ve}q+OAUkSQKy2g{>3SY4qhtA0M!7u)@xUV2rTV@7y9A!^WEA`9 zW2$nW3XT`iTJ^475a0HcewP{=VSRk%($bG#@oF=Iq1Vb|0K-^QH40BP zYvtNslg(9<)ANqanBQoLe=;YJyb`BF%#+X`XI;4wuU|kr3S*$1HTeoFo5>&n?=nEc z+dHE6UQNM~(T?BZ{5f~SwBJ6btY&Wzpp=4T%##~vQ49_!g5a*U5pbwPB@1o(1W^_K zvZ-S=0U}ZeB>}Lc*C0hMeXhE#h#czct_?|IF;YpB+`d07I-*eBhu7}o`_S0prR|g-!^{g7_W&^jS zbd$SW|1Ox8z7wSvM_r$nfo8rrLAOua*7~fP2gO8ZE#=|d@1{XN=&L@#1ShOKW!*dt z^*g3dxk;G8fBemzSv-@xN9jSK2M5Ld1;3lUUU_r;_I=)1Jmn4x&Xsy)cmFUR8vD-b zn0eQV#TwzUXicMEZ|{ZIlRa#PiG*9|JeF%ZrDLZqH(hJ1*nB@KaO>pXZcz?x2z>qB z`%|C)F?XNsL+gR7?ayLvDH8C&|gG?~=^Hzp8}=m?udlvB|n zv}!ow3oWGcfj8uA&z+1%;XjwNyBH=w!5$U^FF{x$LyOa84gHPLbANW2Z-+wZ^_$?} zg~lgK(MA{0gs+CMDlyV9h25 z%0Owf+H<#^k;4T*62bn1cMXQuh_wz6V~+M{fe-3{`bXbv(B5W^3@I;J2(3kTQuA`x ze7laR+_S_VGH!Ps4X-;yq@d360&^I&uqugu5o@Dif92Vpj+js9JMLFqxT@w^o^CKK z!LnanuRu}BDmWAh_qxKyUp)~739r#|9Dk?xh5GO%;-X(IXyWZAs>6@$Wy#|^E$W;qfhBaQS`C^6XUzR3a^$!_%D&K zJDJ;?0b1tSJpI0KISAe&p0H|6vQ?p31W`d_dB=;>z+J(1DdA1d7r%mrXSw9S7X4l- z)8m+ME6mgGr`t;NWbRdYL`u(Xj)2O6aYO)5AJ}|1HGNp1+aIg-{rgy?6$!*C9>DVS z-=^vYYW>}|8w}^bCCTCAo2HdK{@?ki8#}aB(anFi7Px$t0hzJ^@4BHUO-2tGA1|9O z8RRSYK~;mQV!!S8`ve8eXPjRPMYfL!B_$uxT$o7KS4Fe)?ShW4SmJ{^5ixL&sj#ao z+N_80@b?lc;axa#sg0bA64>1w$M@uK9gaH%oiblg4pQ^G?ZE#&rQCXl=DfuB;fv0c zXQ>N{n!?}VZt0O;!)$5dA8dhF8un3l&k*}9ZDEDGYCTb* zgyCB8n-6#Vxx=0->`09st!ojK9}27DT8Wa0{-%2^&1||wiGhjV_0z&RLdlSmZ0f6~ z(ltjUxjegyh$-pOKHcV1t`z$l@TA=9=bc^kpQk@=>s2#M0e)!)X9YCeUqa zQ8}%|p}lV~sH0!Q$wp~?O!uV^a&YJdwKOX7O>$D~kLe#$Lt@5QGL^rFJ%gK_D=$Lh zSyb_enMSAy!~ptpPGE%0Cm!-!*l$y2+Mx-I3 zN<-Dn2ahS$Z%E>+(~WuHFQ+WtrlUDiq3i5v1owKQ^^F@fQa|bKLMoye-?j0feLSlo zNJ4{VeIGT0zBLJ4;OhJ3vj#tb&Tpd41k5M;(qb}TISAg%q3p(QuO`BMeo86av=$IN z6L`G*Yc~`>Pry$;Ap;o3`6a#T3d51YoMOAcDX2bNH4sK6S}Eg)}bT{Jh*`u2|v+Pol_$O{_>ReV=k{Z@ze1}*3} zEi8hC6X$~^ftw9p%yuz%q;Iu4RJb#6nigAY^ z_P_xT*y@On(tEQ}uIZcQ2nx2eC*h>=g#3ongZkKV43H>YK5H>bZ9B2w!iF4U;%V~5 zr$VUJn956~mPK1^Z_Re(v^-_RHMQdbw;z<@vpSR)I;MtEQ8 zMXd>dVT`pX&3|GL33F9r)NM()Wj`_u_6Q->*VlK`fI43yN*zWoezG^tqCx`ZMhf3E z&2!>Em--Y^nK941pGRt>3 z0P==EL$=*;P7Pr=ojPmC8DXe}nWyqljW}+`8=g`%MiFCTVsFKjr59dlw zo>L7~iU4r*Kd5;a@+mOt%K%t>0}zcxWdiqmbR&z(&$YoV5KhT9Wr~tfS=dl*fWY3TXS?v_eJ-Yqt@Duy=bs!_aDFQE> zS*zb~A9T$?D=0sJ2S|NPLEuofM4NyAIB=o={hJtyx?Y0Kuf>iB?9ZL2hd#bb&U7h) zGBZ&y%g26oEkwOqD_T|2&(BjLq{gWV38cz=oIbB`O3*HrL@lNR?hx?(3UizaLBEbl+NEMiRw^ zr(&5QBkevExMgQ%4R21Q)w)aR2{U^yUFuz`B>>F$;X^|BEw%1>5(u8m+Y;Rp^t(`W zK&ApNG0+qJv(~d09J~Db>^)f3fG+FJm7puWKl{tKKnqE5@8;%Y#Iy>2d}==(_S;?& zC#<>J&HF}^PDWz^8d=M#h1V?@hk^*M1}93{+ov6f_@E#zNjr*1f8SB&9Orr&SBHuF zo+s*^9;x2c?!=`={AjG+xomb|F|6L{k%gCw;s}idCfOBbaQiCS0X`&efvWbZMd)d? z-yV+1I9UoCsRhg^l`Zyw_8sqPpr2o_M-R9oFn(U@8F`+&}Dn{t|V>&S%nve7yk%}=@NA#pj99U{v z8SDP-XEp&ES{ZJU?p4KXoukvO$Joy*u)B6xpB1b|{+OXU{!Tnp8Eo^2DPCOj+569# zYWHn38Di)B6Db=eu_NlZJ*IZvc7AyMSqUZ}taAOg7%C@Ee0y%4raK>y%@V zSoG|(QHzT*G2zzsU2&1uzh&mdz!zPxVl`pep#E^K$9dM>@b&!6n*ipOp9}*k*gc;<XWxs7 z?*5REj0K|nI0k(~L-#StsB2NXDmGwgQoMo{$wFC<@EKW_9NV(TKjo40=jOj_^m*;K|g6h>5D{VpnQ(#K_lGS2t2N_ z&P4*R;BG(!T~$0|9z5P5B=}?IE4oggGX;J@!Qc$TnoJJ4xG$Uh#Z%!`Y}8(S1H26O z^E4*i@%iHA$!LT|TD$oq^-ob|r9&{;B;TY+A1>bdG7o^HTKhfy$WtFhLoHkr2BVi- z?D>>%%$Io^?HG7BNkYo)GreCQ%9|F%C2-0Wl(vwavAKz+vm@4n>MLx|0)A{p(Me3vlH^5G#(n@bP25|5|K2kqn|04F5B|;3h^eUTqfS1wm&UDEZ z@viJDTl>%lx?GE$rmbM{*gP;O=Iu^@&UuN+(r+0=<+1*B?2LARej>ilsW~qkNAW~c zR{~b6i~1$MklbB4&0W;f-8~o@3<&OSEXdMo+0DLsiI0}bp?ftcM;?*TU?6;XiroI@ zJ5!^Q+E`XtBtKC>C0weDRHQ9`5F@LYWUg-BVvR}u#vY2OBv1>*{vv)mdcqoheB)H> zuO#taUE{PUj?D|LGbpB6NBx!uU!N>vYewxVRJ%Z}YrM0jOgluZS!Qq;LhokqvA4~B zEt6;O0tPHo9UcDrj3g+43=E`O_lQD+jdy~)uF*b%lb0})8m1Y*0v&f0$12({2f}3F zbkXPF-b2a}he1)OOzDRCw`Zz3rp2tbFYDEjf~(Z^XA>wYFE_%E6~nkpC{Ths`8eVN z)sh{PF0S}@P8LsSpIrG_QC5cM(Z(s{S!Ow~w{%xNuL_N=fZmqZh>08yK!M`?Dei;$ zgMo?F>l7FW#{i$O4pT#5X5ZwcVe_A`%lbm(z(I_zk8&sh8Z8E(e(?(lnTceok<271 zSXSN ztczCcbTEA5@1MT{r-q|}JRhknm`VC%D4y+~qEq;EHZ1%tay%l3EJ%zx)H zfbH7Uj(Z`Qy6k$}K78@YNV5&EJ4bIUt|yj zOn*FhMi@p&AsqHnPCP6-z!@_hd-cQxapES7ATLqATVt`EHHFr z5*y{S)Hja&PaqP4Lnob3wC=qhkGCd5N>$LpkmBV?eJ8sg?o1nl*C zOpZn+RL@ZeX-8ZDGrYynwxvznwDw_~q->f$glDUJ_8V%{3lwWoWNN=CH2b`i!_WSl z>P1RULrC}Y&F7CZoD3Y*p9sZdbe#n}sa(nQPJ%)GpO6t@6QCE5pV(`j44VI{DZ-Wu z{`Jr!nW*PO4uU!cQ6CFC5dPdDwi%4Z72OFI=>O$$h@Lto2m=@dphXOVBeAK<)D6$~ z{-G3ym;zG9)^=mPn%!xh_sp7SbZwo&l~xANUhh2QbFFx!+bYVxxBmOGGq@-@pZ^ia zF%O1AK9{`+KW2}8z9o9%FM63mt)+nAOFhc$KFK|yWO~;Nd>n^mtY6hhQTttFU6y@R zj_oX?y!UgnIe=Oe%k# zb(SzKOmsm$yWrWfOQ}@obNCl$lr;K#r_?NZ$ML0|kgPMthFgTa+O5Hgw3wI~LBpQL zEhr9!>RuEx<97^TwS}$c@UG3}-J0Coin{kNn)V9)Viq<-ReIn!`5HHBv>q>Woz0t{ zlbmQguwv`hSVZpFq28$8P>|&3i~{ITz#6k_`Q616P&}9>6FPf&$!ll;*>}++>8<9= z`?ETB!Z0!lYVatdv21Eo%g=(43NHlsje!bP0$=7Y@r+v+zr^07jT1Tg($9Vh|L6mFgT-k!`17!<*8_^Q<9qv!U#|bw?I1 zS11v0$jNU}8qy3{uwNF;8GXLUxbgu=4|oj>^QZic!{FOYQ5arUqqy?dy#wLE_MRS0 z(46lCs0h6L1ao!!v{pk^Q#Y~=5(W+;Z(k_m6L#oEgjzL`e$Tag#ELd8u2$r!uEJU23R>S(bn(E?PN0KF$uw-NmL8PsumakyjbU za(cWH_E8>I+X=&qO<1BI>>-M}6;+x^Fo@dUf5IbOMF6=;N!I9)Ygqa7z!0BZMlR2i zZW>F&pt?xj=712I_L6>cC$0+5jH82mBH^-|-E$=7kImkv9K~4;C*JRmSs|u}3$N3a zoQA=$^v|9IDPwOx@T-B$ibi`M`qP2CenLVJA5WkOnDg52269yY>SHM2CG7-!mEP9qWTw| zu$pz*J#@-E?CBbaacqB{`twTl=q&5d%li2f9y<*PNrn$T)#s2ExB4#BgoN3UD`RC( zKvY-vtzBB`+T1X}?tL4fwuN;scK}&nfWBfP!z;P@>)l#~>HSA*gdf(1s6wb(5LaBJlM!mI1ts7afaWo^`lO z^tyAQi^Sh-xvgjqqc}cC>|JuCQ#@I7>A3@H2o#&v?;oSIO6yaq6s)#(z^2L}p+hm!_l3}-?KYl{7YBa-^83R%iKxN9MSXsAq zX&gC5M2LAH4E9X`j>5<10U7~saf-l{x6e_)*SO*@b9y;8br}l~FCYyMOmHX+HP0GF z3>y3Qdk?{Tw=OWPTk=}{jHr^7j+>VriB`#dJzEFEhU#v!{_j(gqWvVO#Nwu*jZ0u$ zE!y~5;<-C1^&9Fh#;gjob%C%NNisuN`2QbL1^CwS1XRQ5lz z*5mncDYjjEtG60S27=%4?Q?L^5ZXvpPJ?IdLn277aKpQc26r`9y zG9_lbSB|M;=!SIJ)ZRB=-qNX0=_Chif~rwX(G(}!T54Bdb^~p1Dnj%6dua(KFSQaJ zq{-+;Y(@r)R`Lv8NLZE9Xg`YEJytNPEMZNetw77cYWe+6ox8dx#irFSr(IGx)c+?G zky@3ZyvQ`^rf2{+Sfh5$%;pLtXyoh~vpOB^QaO*zVFt1`pk@JhcM1H>v7BBceGh-1 zBVQhy0%&xzo*1o%yMGEK0BTlzVM_CnSG^!HLBu1F+!9^!s_aMc#lx~lWWK=9(yI$Y z?Q(^hDbODZe!#{3Y)N8!o!$GbpYFi|31eGeib9zB12PRWLrL*xa;6L}ct)6=jonv% z-8^GPjkCVPYoHnT$>k9|>OOf8)BcmR z9+Ni)@cG61iMzxf5w%JGsmR8w@Yf#<^8;E;iy;vU0Sk0|`o;l%+ZXjBEAfGCB#gnl zHoTi=+e9@Uw$3V5Xk-N-(4uU9bu?e#Bp?K7j zW0zl5KHIkyL^@gry|(qtG)oI#<$_GpokqTLOqvsr4l`d1?B+VV?PWA;K^@;w(}6>f z<0-d0-?8N*IME*5Wv6ZY1qxJEunxmJ05e zb^!O=X-vxq#)vcW)^S7@GY%;FUqO5lH`S={fm00_eDBkC+>DBLN2d|>cytFXhL){# z;K1gT3ywxTXvZHkI%;@KMHGt|T0Lm5h1u3BVhE^G2Xb8x>swq3pKIb-f| zPFv%ni!f1a)O}SZ)FAnQ%&Sm}Zc@X)GMK@Q!KBqDRtd{LhZ!sw*ap@0H5)p-S}b@{ z$9B%Z-{de;dC3lBj7{If^qGRk41|ehhnzBxRvdmDKGQ`23^1q|8t5~eQ)M(-ER{dc zwr)b`!ORSji&MbNYxP>9jAw^1)~}j-dQw*Fq%H9nzdv7CTkRzC{aZZe`9lXxjKsb` zL*?_&Sbej4lF*vZt385<-s&M28YJB^dR$aZUMC&ykjdPcfMGu(N_BFUnrS*UaN zw#th32kg2b;KE>#6K`8=JNvYb0M|r1v1vC1)V24%xD{a7*>b&B@fQ^~&UgTCv-}U9 z4=6{aed^#b>jMo7u*01pphTuYwV2ank~a3Qmr}0}q<5A33yUMKJ}9md{1GvHh7yCR zxVi8$ID5mWh!NSCa=3Yx2E)cgrk>ocVdy=6o$W5Ax))wtENColyq`|EFS0f=GS207azcjF*dt#jZHUOm5}B4CW? zQWPY7UV5fwpKDiG4d@zU&!ifLHBv?YbQ8b9$?_A7gb_Z1h?9uBc7G+zori>4xcshv z+IDhQ|F-wGK1a;e=XNgcILhowr5Zy}> zdD_VY9gx~vYGS)Jsfosm5E^kiV%F59(pAo_BL|CiWDWnp3F?kYr#0a>ttC^2N2Gl` z&S~E%f07Wl?YF*pEs+pIXlf>qzLM6&U8<*o0><1xPz8zu;8LF%>O6ZNbj$*N{AUw} z+EN&slz{K#aloBYyj#)2tZU0M7)Q`qYDYub1CfYh08;7=d^#E$Rr-9i!tCOk#owhr z3z0umu4E|11Gw>^L#q^~N3;vE$KIocwpDBsQSgj+q00s-M|#t%2Ggc-c~SH<(wfx@ zCMvIg6H7}dq+n}`ZIhcQE{yzx^(5Jr)&T@NgIo@r{QjE+WK|6fzD?H*@GhkP23|gc z;LzH-)E6n|FxccJGTNH{<+Ls!a$T+`8@W@W4NO=xJ!id7HUwwDeZ^bDCAsy7XCV^G zw+R%oC|LP&a9(cDkx{eh+FqCo2E>G``#k{>7>d!D94*jy_8!L6x8@(;(bAEhExt~g zK0cT}hBK@$PNY3DnlLhSuK0TVFzmK))5Dn9YbA8tYzqTpJn#$uiq`L8>kC>b6)>}# zzI(y@XCW7urOM$u8(|jZth3#a`#sxpV$ieeW8h$RR#TOblcsPG2iiWt|6g`=B zXxlO=+#TfzFNI#*UY(@#e6jIiVK1dG7^2%oOh0vxC6F&U({36=$ue*-+o`j@3PGoY z;}Gb6D@v~+ae8UsB<=5qX#;f)O4WvFXt2--7<3rm7?7Z%^>PKbK}(Mo z$+0@!9{Pm_S<%R^CPY^9tJd8&+P0jB+(=c@=CUNS)^-62No`b1NpS*JbeS<{D|Cpl zJ>^MW-`x77Q+3#bmB*{dPc`uLI&-UxO#`0Toc6LxO%hC~^f*^b>~JYFJLnn!|GuN6 zL&JLILHf(gXmaEt?d%E}Ank0No~l2Ft>=RHVBjBzxwh^2sFY2xZq!B768?ptp%$d1 zz-CgAJ2P}q#Dz`|A?<`Y*+pnHsSE)IZiX$|u(p36>qBHQfLLhc9i+=TGR^dBBZd<; zk0Nt1x5#8klrde>M9Bz-0z20k|GYIT#S^~|cSz!ps)kljW?UGi{~mZqNC-$pz}mq! z$Q%x~A$hyBv>5kDR{*mH_oczC&HAVNmu}oX1q{(Z8wHjk90A1?oa;Q`kp?mm!3N{&%!y>K%alQ|5`Q3I(dF2IRR*-S|x^;X;L z%u9VJxe;v=Gt5YkK?8n{9+T|gw&OSdqkU{i;7j~ftFzsZ%-g|os+Efg#V84b9C3{y zdCri%)nk&l&!AZ5Td9ky=XY~Q+EOYa$%#(48_s0UU%3Xmt$4_oSrchK&)!scke#Fa zUc02CmeE65mQ#QG+ta}r-6Dw9@xzpo^mH@7k#_GGmogXTZ9}PsDDdIY|Cze^{pG}<(HWvRkE*5%4KR&UC6cuU?RypdyD*V zYm|R!DrLl`W<04tR|#0h$PF;hwBM5w2#*rW|?q8sm`%kJK zVF3Y9`2#W^wTIb2D?OdIZPVlHsb_u|1j;FxCAQB{c=Zt6!AR*NQJz91ZT}Q)B`MCN z+YU5KdJaKAfI|q70@cw$P99De&`^Jsg3C&dr&Ek8FUA|qw3BaX)o-=SJn9UWIhZOq zXrv>t=oJ4LwPux?>LjISgzjr4G!YPj|5|RMW=9~Gxt`Dzgsj)7AspPo6O<*QkOz@< zb$|u=Q5+UtHFS;!Fj5{D$OLma0}y(ePZv9o9*QNU0@yMj!m&Xh z`yebsXOR|=XcS^p9g>|XX3w0#A70>(HT?G>4a>o>MiADJ`ew6eTq)=C8)okM0PM`%0#Y#4M6yC)};F-@~G(^4m*z@ z#Qwkz_`rP-sn|5^O}@8RDW&3Ch}=`$jC4-t(Q^Xe0aw?&F>p+Q(K>hlKs$mjoN$11 z|4L_|35?$ey@p4X zDGQ-|gm1AJI$q0DHgNxm>QD}q{a}E4K{;X(?Qu|8RHSwbe)3Q#*fz^0nG0wo#Hecg z|8<#e)9@U+Td^-wC>AXSXp|d26*O+Ciu8g!lK5X3qpjNm^EKiy>l9UusnV0YFtq7B z>!4cmTvQZ2?pr@d=z|VFu0o_+#iR%U_E*hId~Rgh#~J>d)KX!3>Fb4)-&&Djm%kW4 zpM^g`lQ44piiI5jbzTpN4~_LZA+@ii30vwGOH!kdAZhZ>fK6A>0jLE?F5S7dZP8ng zrKR&Y0Cmf!w#CG(+VAw?K4XSQ;QhM6g`-^_B^2W z(jLedPx_1-(zU-*7~JOkq}09N?!@edx5M;Pg+zCFlZ5mi`H=5b8WHHmwt)0KDpn^oC5P?v`2sowH8 ze;;VBfFNVZG=vR`vm9}X*t&MIWvxGk0*RBEoAryIcE+>SX;d4c+|?5E zt+nXT;6umH_ZCAR{w2C?%3f&uejS4@cZl#3Sa1sgeTxw~Y83%r(Tj{^Tf>_addmVv z=M0P6%#LGxIqmZYBwZq}35OL%atgMlFw2i_%>r|a=t^+5i=Ow^RrhUzQQm_0e8P*& z``BEd9{}pK!m;wXfw~7ki^<}d0oJ|PwEqN72q(R6@vN8};}`-73U+j#NUSUA(%(ZH z06!zW&Q8D~VYXu0B$9TJ6X?^1eFXzxE6{vtGvcd*ZbTU_j4&d!OIAGoeVRCzmK)Mb zSTkWUDwHorcy}=QcOCzfMT!|!4>I2p1g8?VjQaZe;9fpUI5ojss zy(Z~hkPe?^&nDec0g&%_MX*N+uGINO*8|WDQjCT}fha)`M7I3BD|6YfpS)ajnK@0o z56=Ftf9z4B;E=NZTjoSW2#SxhPf`s^k(Dn<8(Pu|+)yVWdM0@otnRaS1`(Hi82tsT zU9OD*KdsRr^->sa&(spir6jS&IP0GxU+f*h88%_34{l3&*BrXgIlP5Sg0z!7WYi~}Av*!h+MQm%R5IeE|2^$6{W`_%x&9Q=AwV1B zpWLDL&e`dc(l_&j={GRhL<{z?iK2tM*Hz{I*|KXp2eKEt!aN_MUI?h0rBvpAmUG{B z&`3(+kKUR9Q}K9y z;9&Y&Z7Jv?4X0e^*lyg{MOx?Y%>QGm2IY?GjN+A#$N`26$+|?13)l{5Txf}eK}_MQ zTi3ls&@s%g0D?-A$lxS~LO&DJ-bYn(TQSb&b25~KGJmiTVPE&3y4{@nPHamu-*n|i zYy^w3a-*|)C77wIJ&!g5Q{!(5$QRT{7ad=DTSVg7R*5{cWIh>amJD#;y*vCN>9H5M z_9Abz?rt{Sh4uP}4-p+;GV^O_fTy?O^+UIpC3DhP02dYz3ixn9yy6|vXms&qZ|DM; ze})^L^_=fr>w~v1B_E`Mj))>lTAUJW+!lVIu9N5vCW_gvbcgW_*JA zUY0BqSorZ&Y~5QXI-$bkj2d+BgT~Zl|e~D-QHw(Jr+Blu}s`h1IE11I2+b=%fKp7Mxp3 z?<6)AKkI(+j&zCcc#kq_H!yXmCDIFmEkQ9qL!{d9q{Z;yoV?-ZO@!+J(s-w?6t`jr zgP`&fMMGmxNTV4s8J^=qTPb%P;|~e?Hgwsvb5f5$Mf$pSwq3~FP7i87GL!0f-|(I* z^A!&1!*7mpjNl#w{7b?eZuu(|x=x3-yZaB&$e(Ls zKM(>IYpFwk8Swe@=iy6u?FLRQ-33S+igAes5#LJxl%EK%ON3$#H>4weh95&Ef&K`5 za^8ccqhvoQVQfljEV9%{aI7tmAh2=zQ8}2k(*;44dJZ|rhn<#$%YA-DOhv+h+Dpq8 z!6FB-Wa<5D@mXK1dxl=yCY7K%?ftW;&duZlU>N?VigbIK>l0ch*zF_26xa^Z3Tx+N zubAn?b&|jg541mxxZ2!^@^`B+{4l6VDdULCdt&IUyv|=GU)2OV;3gBI0xQD8qHVC7 z^kFj7sf%ZEzL4S!z|cqQ^&nqGN^s@CIw-bTvkDP0kLKU*QH=91()r7yX{=yLJ3
GYud>LSWTMK{}zyD$3`-33pcU9o%gLr}SzOpxypkv4BGtte%zj>VQm-1HAnU zH-fhHr0YCj%b~PWy2t%oUhf1y%6vJja>0yttRQkeD-pW}E1Dpi`31S9-=@5%*p=bf z%&e~z7BrwcpSh18i(B=fmqy3QS)6!aCwYD^CpY#J9&`52Fl*KJI8V z^yBqPI>N2A@lwOulJXMkyL9YganSDgys(;wQ zeerrG?AxX%yqd_K_j2~pkDMB?lmWj}4Xtaonn;k)i0IO*I3>xF(zBS#=YtqvaS^Ck zb9Ak5tBdgOnIVbApr#uRl}8ApiDMZgW0}K3N3l<&P^r<~0(IN<6v9APPYk_HIrUui zdRs-6SlfKaEmPSW93ao87SH)aL0mF`356;%(DYwpoi^v-wuXpx3{<1AvL`JG`zvycbw}xd&;de>b1So}9L`RZMfH_G+O5r?9V|UkxKFS}f5fPIn1yO#rM3pI}#dUX(UC4Z`We z{FB_VwB7h=Nrh#R zSS}8DFGao5WOJD~RE_6xVoBdkFeAFA@)x;!MX|dh37oeDf~@?r2$3>k#iF^vv-O)2 znGK~Ny=_EmLqq`b6%r%ZXwJ0xf90CimL`}87 z26jSB;)o^^bZ6k#jv~r>F?w+ByHC`nZ!OujgjCC_g_%quo4qfhGe2F2{Wmc3=C!Qj zc4_UqyQ-(UNN(1=S3K{N9M7^CM8>iWdVq2roUROV0v%(@&m?aC);wd{R}c)I?Y)5N zeunA&JQV4LdEcJjXsp6Uz_AAC4LV6B@SOu^RFzitJxc4HJ8%N;N4V?{_aimb4{&0| zQZOWKOip*nPwk4^rcvLA@riQ9wKcjshiQ65D zg+VA3@ZNE<`PkMl@rAwtois$|GpWL9tQz&#rby3)E^4Zk$d-xSMWr2l+W+m8z(`#u zX{J^CieaWq3-lM8)X2-esGItz_M83ma*BuxV{gPl{oJtvC1h6G0AQ6kI&2oJq4_Vm z8e*WhigjDQixR1{U<%jDOukU|g4)}6lM*;=!3zsibyZROscxep`)Sm|dH<&ca1nSI zNFb7Ca7C!Qd@;hp(lGS=-73<*!Eh(Z{3-aC;CO#XnRqNbzHS2*2Zs6_)YYCuUDl7^I z`W6n`J&^;!z=~DApXKqEvslQ4K0uVfLbcs%Y2DeYira&$gD>YVf)jYefkywFz5v1jgNt|>K>p0n?6~PW+|zi58B$0Dx8n}z(Iv3OViCb3YzTIq$6dn z?kHlvDD)|Ev+$wC%z(fD(%vp+!M*GGfpkfNoxh&b| zg4-IkF>K#7l;7|NKRWE$OA+0yl#AQ_=Q6j+uWNeQ=yc6e!(J>JvZuav?pDpV3YcgN za*fw})69*A&kq|=zfAwURd2rF+dN!2sM%Qf)Y@bvI?-4Ll20=Y1P&Qzo@P=E1<&RV zWL~E%Rv|v|q!NnL$Poc)thvsole@!BKHS!|BY38SE#e}<-QR$X4CJJ~r=uLWkczCd zg;m?NZ{4bhNZMY;Nas@6A<8%)r6!_W?AN-)i}4IpP`kA@xjTpGd3DMN%(o|MM3O`% zY}v(+rq^KWH|uKCQ|CgB892AzG8qoDG`$dOex ze5d6Wm->((L?;_p;mZBZ1&ct$q}}M_rv&rAPd{YRCrpcs)Y-TH7&WAr;9?v(;aKs? z?5i)I&6i(%Xo{URnZMPdHaI)-QE`MhvLEc4?xh^ce{0a9xum4@R$52 zxLkxruFl{_A1VLN9#{)<-a_po^cUf>wtbb)p0?uC<&^&WBqNRmeC|LQ35*x`$2zbm z_>HcqCMZ}4Kqw06gJVIvz#gCfgC!Hhy3hB>yrdfV0d(hUYi5?8>nNsdyo2oo~r4>P@nn#&9h`C|uP7T!IkJw)8yc(>UL?$6>*D7%^X%1K_k zShwXu=!>VoCVzTn*mFETYLS2O;HbqOc{?XOdA=&T-e5oRbTn>gF-G(3ej+u7{Bf;Q zeAEUeLZJ809BCqXV}OyM49Yi<#{0zkZ(`rb*<<FWDp%^wM z`V$AhoKUy$ijD|7bpU1M`6C+gQ0xW0fpOwosk?6j7k(~f#V=bOuoLek7cg7(8`D@g zzErU2d82j8C$Y<7r*ZDGhS0}L0ha3UNFOQ95~o4N5V}(a6UFZC&_eV{(gqhv)50Fd zQHtX}gdd$47hY_B$&W#X%O&P)HU)5Y{I{iv_m*0!hZliCWu7i9yrcGx@}l%+UUR+` zzZ81IAA56tIU;w^YB=k==r>;1B>~{63pbTU;s)^a<%1T0t8fOfxQ=|yv8-)Fo2?@^ z;{v%eA3iI)oz|Aa1+d*lkT)wWmY{b8=^H?m_XPXU_n_dY?O_dfJ-Ed)VTh}HtsVdD z6K7Lg;N8=h#jj$oUW^O9f2)Ya9gAZ!3-$sK3|eXbuY?jxxY$l=&uFUn-FNJKhApmbf1m92 zkMu=`?wN|zYy3UmY`eS8JpMV`dz5{&a3+*l4ONN@9J87nDg@*O5Zwe)H$Mtc)nk@E z`26Og_2A^%&h?_M&u3SdNp3vs<2-NUT>eqr*x-#wYf+IN^-U!dgl^&Iv%&tgg6ujK zl8>jO(G=N3SQvOa?Q+lfI5s2Uufco(s`~ybWO*D?V2kHF#ov9wp=0+ zJLPclyT#*^XsG*eiThqbQ8+-*0e;rK>9>u!Y00*t6y1rsPj)cbMvOT#I27F2+NGLc zVF*&<HXas4YHO1^7ip)$ z`^S|G!CtFhP;4oCWs}tozgs6Q#!c(YmQ4Y;g&{@jUcoYWgtP`+Zuo2M(nUCq-HA8n zET>rON7_JX+lTj`Tq^o<+8~Db3i;Q2;<;eeY3sp7nhWR2em&WT`KbLjBaRmRPo08s zcs1b zs0ZX?r5^|P()wN=Z(J*}JO5=a0p?c%-_FMemT8RuAAcv-CZUwXZNExVGdNKBeR zPOx_cj64p4C`5m*&c#Cgsu>qK;1sfi(~%=y66{FBn#BC8r*<;9rbh;U39QE7yy`8% zjazp78IGtY9CtIFhR7U7Res@&=gl=ELi z&GFW&F*z+8%K7@4>pwHQ<4@73k{8(htm3`Y!Z_?yXMwfbsABqCNWyKMHs3Bzygg zdBBaY@UR{2)bZOYm_8?zIt97mP1T`Y^@rLx3|PKd^N7g%L3qCi`1|2})YD79yS{Y2 z)e2`{s?Ik-Y%)IjLheT31=DNQnUN)@vl-=`ey_>a;Z8Z3Ezbk?oy?P8yXn>Xu)Q6F zyx|)sA#2eXH@upWH-#m}0qgE@DrbFfC#y2uf2LZzC6bByF)l_RkrQnADsX9R63XVX zaOm%kkBduL;9QPHN!~a2d~)UR&-c# z4@GqQmxmD?WG_1>*mj5M-D?od9q%jT-`MBYF~zK}In`$Fc-L?#nd#fIdP;#oZrAazwms3qdT{Ogalr~L zdVz2>Pk2>J%Md_Q#MtR+ObtK`sisuhl~rui*}uHI!iHT8b4XPN_47z`zI%v)5#t#8 zkBW6sV*LQ}cwxO3E~Jyh)rw(C&eZ;Bd)Hev@GR$~N2=aeovgF3r;_BjHuPL)UqRWW zRcU{7^^b+`?8HW7^)RZV*RNq2(kmDxYgA_&n;YVhN;CJZ+svi`oH6t}XVNz)mlWmr zKlD&l`rnbX^rMd$>uWYb!YS2$|0DSNba1El=;QWfyL*2VJ=rut3CG3J;gOKXpePqGat4P9^S>%Gew zjcwU`Aw0aiTCvMKCf9jV+g{!F^Tv*3x=deWC(>7h9@U*yf@^44IDaP9S0}0OdOVZ# z;I8ttteWrJwA9f|o%mjz@`{S|g-)G!O66(ZDyrtdui4qz-QC@awl>&q!;kMQxu|BI z!>&)$wHEm>C$m!s{-OP?>V;46J(5@Ve$VMsQEdO5wRGnEwQp){jQ`-8wy%n3#-kzg z$VXDlnCC1*M zbM}DnH;Z_bBQ0%@EJk#~tal4l?%2OS%jbUb zelJX6xm_{m?g;be;zC0lhv*Rcr>M9YPK zlY3NYDZ9J7`=7Zv{b!5Tz1lCVFgMG0K1`{M=(+sKSUpQwuC`w!58d0zd`OthHkcT{ zCbZe87;oQmFnsb!@AG*MVEI0B@Fx81%tfw3g4xv61a>NDmc-q<<)Q|>HX~kX%JJLH z8RFh!BrQMAej75FTrtZG=+w7ijSN(H>2D3?j@QBmNlLi6lpQde&CZ%2F$%WfIW`DZ zKaTIMHPBnq2-)yBniVm5nk*vCn@D|;oMqUzF>b~fHF-HrqoLYJW@&T|46oK4t%R>R zSzp&l7+nQ}jaOdPS~3LN4nw!ic6F?U@QMb18Q)2f%Sh;Gxq7#l-p$a*GL1cW1vWuN zwgc8)(2=4!=40paBq}$7bTuj0mye=|KR*3RsHvk*%VyB{fQy;#L2>wC)rZ=nM$SDQ ztH=LN^35~n`YL%3zwW^wC-O9U$HMhueA1I6$dP;e28#&L-B~&~!~o_)=JgyPTBIzV zlg#3?J&`i6Wy{#_hbr@d(-)}>zvwk){E6|p)Y7mLPH#xBa@w`H6{Vc4 zkfHCBbWzDBm-OZ1rv7bvQae1CT>E>Xl29NiLS8eqD;Yy^SH*SeW?lR;-CG(nB5viE zxRj=*tEJj_Prxg^FD8%+S~s#I)SfQ|<8NfW(f^%ekC)XdMG~SWU6lX$l@igMQnM3U z#Rj}S01dUj&*A7=9&@6)CI`mSKsCI2y+^u04PEO0kZm0pp;_%S7 z^~hi%g6FH%kFEV6wc$Sy=MOwo7ar0$>onZB^7&+c)Z}KIH~kgZs~F@udE2grOgHaT zHdm~7Uc4l#6xwqeS%v5-zl;$QoY{FfSd~~XTihSvV+xCnc^qA~3N9Y)mRMpv;oH>T z{Q~&?RS8n*xii^`B%jSSDm@Zdj-{0K^gw*V4&*`$LA(*mlbpLBPfwD2q-Hzoz};*ix}B5 z8*qGeDZA*lww`C81{xC6UZlVnA%Q2!p1{A3&kvigHd0@#BL~%yiyMxmG5ftB*_yQw z2>{ERj-+(~>k2guu=x-7X~1tW4yuWL(^3 zsN=S}?T}IX9CnyqoYmm;C^wD#NPjg;6m0o-g?Sug5e)MKkg`yHtjh!k_;m!cw~_tq z(Ra;7kCRxsI`E`<|CsmsjG2*huPg-g)0$lLdxhZ2kghIQon_60O!(0!NApmyOWVIB zw(O@;r^Ox^)oR{%Szvqq^H*R^(bMlN&rB<%zf!z2uz@^{a0wpZw~&*URVC@z9#eRr za;v&aoWh^;+eKh@wl9ET>|I1!kb9I)661gA7+N!g%JH$3p4?WODLp0~U@-0N?LFnW z=R71al*U@bAhM+UYu(wOL@mzbO}#b^YNTS}#-q7kWXj3Qk3|(*4o^&4dfkPnOe2jy ze!Q4F+kN6Y?|$>6R70fv&wH-7nZk5c+jtdahSXtcA%^82dvS}@HvEBb4UPWdDV`w1 z@auHfv+zmFl-qdfM)?phzI;0_$eh&GDIyIv; zVR~!k;Mc!SH@x%mX%163YRwirJ6z*UPvxu55XgRGps?*%x2ER83jWM7C+rT$!bsy> zWpsnMs7IY|&pV2{n1Z@csSM%(Fy#fS|74TL8}CR@Yx7gN8c;NzVdX$xB&+Qqt14T6 zF3ikyLb`x((M6=F-~9W;*65x)n3a^P+s5@*OK51Z#62a1g0!4Bdh}0X) zK%HTxL-v}E{>cg$U-^Ip0t-;JeS2$o$zL!uy8U1zsr)bVqsDmj+YfJ4G?s)7{OuRV zooM8$&x-@3SCOj>ifW)e1iP>;SDfxt{k2;Lxd4}F(ApY54wnT+?4qK^uc-AUTkzWM zJByc?((>)-ibdt``8e5JS)}QqYt&)Q@BYnjmnKO6>B&k#3D7c@!F{yJT=Jc)<59wJ zh3&K8=M&|c5szM#y)b-XImd?g_nb7`oFn=%)Qrct{OhYq7K@t)psMN`3%$YLFMsx! za_Geog3MD0jL#srfXmzG+Mn~8(^+$%$_xg}1h-ZBjAh$T=A2iD+JvXkI-z>?P=~ z3lmjG`)=Kcsf|HD%2=_74);Cz^ZTK=im76cMsn7-0}(w4y(eFjlp49 z6~hbX@uF_Ic7|7IZwX2;SKmmeb(#|pS&MVV#)JVfhYHE=!9ib;+L}1uCRqJ|SGq!R ztb9Qh2sT%3iq<~Z?qWnEH5@8*q%d7({5hL52|d}-iv7D?&K=HRG}X?A z*NHZfO=Ii(wHMcJLmf3Mh{<@{cG;|Q|Dks$?!4v-3DH4Ur~i+pYYLC6Yuiy{tFf)d zHXGZv8{4*RHFjg$YML}jlQy%YMJ$OAxs~^|J+E! z|8*f|Ragn!ngL9zfPet7v_X4AuCK+`tv|Oh>!O5kdi(a9^-Oo^9a>l_WgHQa>}%Ym zs#dKHbFlwpQ^_D9%_PsWc?%N!Ur#nL;a&diYQg-7lbn}NrLxck`e=39C}R@8Pf7tE zk|~Q@j0>UMhc5!n78k!oF?!)m54QON4UvEs7z>Kq+t*Ue+Euh46dd+X$Uv7}DP0Vz zny!><+z*z;^5;n?-gHexjXj`vMOQJVoM~NoWW@9#q8RoU2C_L!Sfkz4_lN)XcqIXB zstu>_WuoJ!(BN1|F1$}?_S_O<4>g0#xPN;FCZb+BF6ZSAJw#QcVcYXd7{#py8Sr38 z)Ab}2UctPq<4t{iiiJmvVuaC)sgr+foh)o~0ndg{VOb5Mj2e-A%AHw!OlV395+wy= z3G>me+OB0~*9cRKkHyIwg50WKcgb)B#9jWT|Fl*C$N17hdLdr77VBw=78D7)m|-ZF zA`K)39viPcdPp(kNJlFHQw`eQ@!ggqCPB729yAdv#%j~F%wk79>h}?>O zA~!d;H~1Zt#N4iYry%WgP&>635Ar06KyO;1ps3CKx_F#q0Dz*Bz-PTkK_6}&m~g@I zA#z+EAm(99yU-NPy!8u>JV@0rsjcxT%XS+>DIXn* z=iA@n|NPFwegk@R^B8TcG96F5SDdNf3sE#KIPVrvd$v&MUGIJ z)5_*_0+r(kDpwb`E05XTI@_8z9z%b>?{kmMbcY|OCEZ8!avO6!fK(Q}w>ys5dlxn{0?rD5Jta3Up5kcDtxm8Xd}k>Ut& zEBOl>zkgJvw_CHd?+!C!cD>OlLMvywg+enW!&=&;e=ArTtDY7l;^>ROY?Z}$MM;VF~w=&j_%$_0k`4@$=RJ62oG{fol z?-M0wnDKjL-nb=J+3u_{d#J!IEXPzjOt;jt{VB06+y zAm~i3!w27#dV99225FArjR3z`8<{RxpUPFMuFbv25E!3{1X3yimn49hdD%^aTWBf_ zr75yVAszDC@CZItlR49#v7^xMeP5X5_mupjsmzkO&I_XxZTXA1p}jF)#k>h7pJBvo z{J~XRNJzBNsI2o{xS(b?Q}f66bKF1tD_?n`&0$AJEcoJB$WVgNwesplUf_r|V-h19 z-8f(zdJ(b$E@1#UV#h;X`}Z#aR17TgEp4=E2mlxZ+_b=x9a3g8HTCN+(!k1k785aq zmF)|mW_%`cz?_xgV(sBM>E+#a({Ql^qDBcHEMx4FC`BfsWui6*x$|k-u$$W^|r|W+4%&SJuy>a$wc$A>dh1_O6{mCQ7egqtem|?=xR}Db75F!ky4aB?$ zm(2_6MQjCSm(rtpI;s@XUf=ehzQCf^r^I{9yw@H z=UIl-yZs0prfab=G?!0e&hR18xo3`}GS^1&lBCZE#&{u33_OB0?qoeT!3z;1qJ_wn z&MVL>z_L#NfGKsOc6G^j14MuR!b#?Ix68ma>CSKHk^ICvuHg6 zsYcnc$n?6&UjYIk*+;pO;l^_6Vk&?CGU{)yOW4gMkmb6Y(Ewj0i`@8}OSNUL$4}z! z+gmvdYG(RH@;y;6Jl3i}GYY~CUHqKj8ga3qSu+EGyfZDEzcag z%galNv+PPkk*S!X#MF1wZN_gnZjqKsjZ7-FvsQf2_LJBKyXXks#x2%Fq%?+?+3D}C z^3-x_pYN@r4BBwC^MAS|*Cud*Nk35lW9PSy8NkZKa2ljqGSF!f$YqPdVM77d)MU$> zGm9IT?9%vgb}C1vfY|^pYJjKN$^W_x<@-+4AoSl7WmmH8ss{;p7z( z_22im_p4G2xr%Xx#MB2Z9|1?j72)BiD9>JXUd1%toEvmosFGOqMoZb!LP|Wt-TC!^L1^B2n!20S1SQFbU1-`K9Z~wOV$LcoEM)DsOJ9xu}F(JJ#Sj7O?+e_)R7$)n( zPHYR(tov^M`{ZJTI5CzEji^ayylxsTzEq=L4i;4V-( zb8Kx$Z3Pmhebo*9_1+n0#M0{Q%=+*pSKZZ?F6OZ@Tri;nFjboF>cWs&*c; z4CQJ=Bw7aYCiw)v7+4ihG>O-6c%3u-Y@^VYP?4G)R;U9o#$`jvo389zL;E6}>^?}X zO{6LJ-oD!c_wauX^HRE9aUNHebt#WmH@}4Taq!FD#nvufoM7SupRghz<}%{TRGPn` zwO=nBo$?#e?T9gdbY0@7>jUwAPJ^eMu-EdqU=u@UyXSJQHE7ahK3)r+%U%9$!W_YC z1$pREEV3^78HoYT=Nh|Q?YH8<=`x+6rnE+HNC~BA0oG}_ZB?iGr$>YFWjt5wYIS*x z%3ST($4%hpF*^;~&r!*w26CPjZCVjeg=@JKYVW_$$->`DD6X#FOU&^un6?+^E9Agg z?w4eVMgD3_){(Df#j?yTpKU>PYxZWt9%pyKZx<+TP4qEzR$-~aEs=cHGiM6UyJY#~LtD!8Q!gLM??Y zZtb-;w>r%?O?yFr0_lH2MajTx z;&!>i#K=&NW!JF$X~S~JDrLkUwckpB!$3@yK`PV?CLiliY)yTpkmH<|J_0YfLS59B zsl#xbLKcsTKFnW^eW5EQ#Jp=#Vtc*q>}_`8jgvr$gE~>eNI8$i_)%W&`$gB2MPwPd zZl;U3^H)`2$9h%HQzMl9Q77@A!EBk|IwUeJ-zGl~G#OYFj&K)n9g|nKwL7D^yh@o%-Qo*YsyTN@M#VI(zr{!WMMGV z#9G-$olMYY$H?^Ta!M1vb`slt{CGF-tL7E8Rjw7icsB2=XFz8AwpQgF{~<$>6*r+s z?fmAsYzIMS0(^g)^4$tQgl)DH@iyf#*^AGFa=6YfE^lM%ne8;Yb0}SyvRYKU$LMs- z;msy-Dj;dNI;UF-bh_KEbUty;(P5H5#oCX-d`avg=x>~UpKdPVT`o8IXLnLRNk0x= z_tXFQGQ(q;e6ai!9lyrgCgc@cS_~`^%iu|Mz@pRgCmsOam|nmZw4KiB^3}C!RaPx~ z9ErbaB&H)o(Jd>6FG{Ui>i)R@R3?_)YCg+A$SkN^cyFEgX2#o^m}-eGlODV+0Z~tn zN@H=C-+_6MYgqG+BxCF6)4x3rM@l5%V0h;*Y{w#So8)?4nPq7TdZQp(Yzz4vxDHW&m+$@-OP9zI5t zMtq>go3SOlrlKc11U>^^D6L7CVJpY`k|2uo8%2SzbS9%ALS3Wh$hx0x53WrQ69*Le zW{|OlIQ;qLlY z2A;%#Wq7x}wJ}zD#z)*jW@t({Xj)#%zluzx-KaeUsAvY$%LIt#HU_CC*!i&C{bm|W z#|xkTwuacl`py&oe)HR+60K$sOFDf@{2fyGkxBBPmGv4nYd;A5cy%9z0f&wAFI+!_Tn0Gt}lbpq4f3j0fI^RN+Q<4Rqp@{%rqvfyyh1J4gKpn zh8v_~rBnpYr!HbAFv`T~eWey&Myi^H8m5%C{p_kW=-JVhtJLTGGbJtQ6y9t)Layu< zLoKRIYxyL%xetF?#kYV24%OGFD4fE%ABin}UA1;)mpuxfeq%KU@=lZ4^p++7?c#+q zy}~ve-QVZ#e80hA_;mS9qwyuCOq%=LLttQVavo3uuLA(N2!o#&ur#ug@}fM;2+++T z$msw|L*S~nr6x*$%L_Zg@0s_cNf*q=??zEcju$H0&%|M8Zy?3QVeVsW_s!k6vu2;T zvDfPYHmDXvA8$@%m&$IfrLi1`SsM~)c1!~c#|z#6xK`|)jwo|L)WWZl#pQu>yi(`_ zC0iPgIYYRTT2U-KG3!;WN+Yb|3HSG5+H^%M6^1o>jWWg1JaP6-#{)E6Rs%enuJ11% zb#3XE`0@}GpQR;%AOm0`25uTa84aYn`YmAPa>|vUMDs*Q$H4k}w@=3!X`1y;WZ>}Y zlljb7i1N7It2F2~!WwK+R8yl3r6T4%`D9EjOCP>{;?D2j=#UJkYm}r%y7SW;-dk%Dd7}nr zrABQEdzT*JVjeZAFnvyJj&^|*oYlAEqz}40ef`#%yN6g#UFl)>oKuGJU5O<=6MOr( zt*3-7fMGA}QD7j5Pnn#V?N)J2<7ix`>WxLjO1o}A+J|f?H@vKJc0S<0Qgo}cYYBdc z6r*r&rW)rSqGrQJM7olN@kJm@9Oixe{HdqQES}aSRDO^z3`5L+F0$D|Og8S5EnO8g zE6xZL+*w9gn9yIF_>21{Svi%e%n&jhzRZiDo3@=P<~^b(RcD}<10eSQ!&~)eWGFt9 zhYvb%1B*2)u;*=T_&J;o*ifEUwsNh+x{$2n7oa@lEd41eP?8C!StSz8}T^gkpt-mNFBk_cl2Gcf~Df{2Y2hL(rsuN66> zfXBVB&e?N@^8(cp}xNV6pcBr+lTlO~nYMFsrIbJ#nA+7L=AK8%IHtInQ%o z8PbCzfFCli|8F-N8IjoZ-a}EcNv)6XNP6OK*&%Cpy2|{VCZKbl*)4e8^ufX>k5=JXO*P+;pDJ6uBC|)kBA^X z;RkCu)ijI$6syLR!FlmjT`*6n1leNcM^j|q_8S}jnM5LHL|`Inx9dpF)0dLps995tM=|G;nGPvQ5hbjl zEDw*pma4Q04Q8v328-4k`;5sl__>uH<(L|$Y#BO)^qj{3$~lCI1{v9=es(MsZh<8P z8pHorNjrj3u9e}1pF#64dn2C5jfZ1d@{0%D4Hpvs6#$Hv!C0T5v_Ci-*BD)UhZQRwJaOz`}4vihvJ|UBJaAKewnn zOdOMX(Gi^{8LK$afqidaLK{fL^FQQp!s2AQ@D1bp#UmNq_%W~jyj~QP5cIb7Zob+3 zOf#?7i&n*@qp&BRY`JhOM~FdRkAXEPM=5!LLLN*|USmJX&o7HuE;FjG`H4j~%T_P5 zn2Z~}bv!p+h36H=oM24HzA9je4w6r9LC2S>a4|VXk|O1E3^zm2{nxU`MukeO{+k4+ z>(4uRjZiUrp_kx4`Z+ibjLchyg+;;^Tg4XtW_DE*xJH)5UFJ?gIMCF zr6&DMC4Z5pQ5X%l#8b-uat*(424A_q5b2G~>S-Kg3oKT#)P9KBCoPG>71z;&KHs0^ zs={GHtJ^Cn13Sw2rUk?kgirbRKDMH_d)nt4(s%L(hk^Okfe%z;aP1X)EfJT>D`F1) z^LbbWlgY^xwr>AjIe%;wYu>!iwFw+46pKqZd-8XLA$S^iOl*55O~bu-N42qdXu&7U zdV8`FJb9HdYI+iRLpWb8XIn3NZcS6<=41kfb>a3f7@t5cZO1W$U zB2kjX*kmAZM+%zl)0tQhjq4z4UQ*L@5FW#oNdIXYHXx7yBZf+R4NZ+zp++c|UE>%| zgb}R2h>PVj;P^0Z?l~t~MH5dwKB?fKw`^ zHTigXw@-i9y7LpCcAw;e)>eXM9PWVoRW!w7c5L@E4(h>!!kT1fs_qM}l`t!%sWy>U zd^vYyvHigfL-v8Bsm<)FLb#ZUugBQVI~;NxJ`cy*EKC}F&ms2SK*AdjV<$JxK=l<- z!g%lV3gO#erPGf;q@{f7^IF4mx^@F!Yd=L4fiWrfp7Wdn!h#+M2gW)+ zPMu_X@I`KnKR5^8YQaK0jo(Ti!cRDlz;CO@hh76O`saVQX#e#N(*_++JhuhCxcQ$Z zu%(S441oN=G2rWrEi16|5L&?H#Iwx6{fz$$N6}y@*~1AO3GkYKp_ef_J3LBAPz(fe z(sF+=JwI;w`{A%XR~Nm|2kz1ah5{6TxQ=HqLIPItKV>RRV5LBZ@+oWqw39<0!V&P) zTv2okk#>rW)$EBeE$*iw8OQg~msKC?^W{{E=vt z6&x-T=x|Ho`ZFpf$;r6T6J%*EeA<0rn4Q~j-NuRsvm zTJJ5vz_qb|Ch+tgWCcEx-oy=1^ny42{GS;IW{yuc-a3q5bbV!~z#jwe{Kn7kjdvn% zX+=kH!p&1f9}nc<8?=wqlTGrLZ*$s#uV_!;k0<-L_b&l4JI9E|&(owgc>~X+Pu3&G z2MKwrKY!wZ%}TGhFk^c8IonZvwg&}~1?0(b<3DiCokl4k< zrCRO}CDTEnTA^SWiyMCVe?{~c5ClB7~fyBWpG?Xh@EM6vz4m$ElwDw z`~`PK1CPuv?~0EgIrddCPUqJ!G@r8soekb(BL%rJC%L{r(HGY~ZI3?D*A}_ z16|&{5NhYXtaf@QNK!PSC;U87#UBJ1mgi~h{^5@PhtELD>yLQA0JbOcVLtt1Ummlo0T0ZwYY|`#;NE_rzzVo zC_Yc{O@zUrb^6@V0L(-K8hJ$3y(+kd@+9da)9Tr`swqKyr>-(--c&XB{KV2>D4ZIzG&m*g_difaLJqdx zH^4}hBI6m1=2~_O@;m*%h1rP8If-R)h`2VP?U5^3PSy__(|RSp9%YXJV1eZl{TOqG)(u4;fDX*iI{YM;^!XS4BTXtd*;hyEPm4+UlDt z3b+GafAI4v?@`rR{EmsF>KuH@upUXh0@i=WH5P-sZswuiH6+G}$XB!pbUMNaZH1uVLu^cUdDK3r}uUEmfG?*C%A;chP1U>Cd~O zIh=ODVbEM0^-~@hPE*!w=K_YizQj2Z&2jj(VFo%)6>nl$54E726MZ=8lO!Ny~%&_}mifWVz)XJZz1aR3Q5x&S?o*6X*<-6`a~bZwS6@#RHWiVSPvk^MBtCq5eto5O@DVIe5{r#r+a zVfg!R;1%@8`vBOHX8cCv^x`p766u zU}hQx9|pDlAZ*>4`XbfmAo0v~q5PaS@vlxkqPE0bT@9N@@maV=xR@QAv~x`Pbs@iZ zD=O7WFnq?K0+V_;Yr!uB)=Pu{T0DDJ$Z@4kBgQ^EC1W>!LkBx(sOqv~ zP?fLHX=~W;3RP{XGWgB@g$EE0pNL}u7)Z?m2$ovy##^8{RrshZwwLKY=CcN9uTD97 zX4?xYo9+tijJtvCWtU(h2Lxpe<-?UdkxYuu-%@YAY?H1k0#KjU-8noMHLKHgs4*7=d19C-JxnI6M*g2c;987 zLM;qd0+m%u(+M5(lL#XBuQ)J_iiDZ$MXH&foZh#syB;2`*AA178kHTfshs!bI`9&u z{qN3##_JPE%Sh9wN(bY_Qx~uJ8@{3P^#&2z_fMLvmEFtbQg<#BHFo%({(0=YE2fXJ z!6vkLZ+?VZEJxo}^JQZxB;D0H8cRdmtsNUYT|IJVIj}MPb)VosVkFR6F}9#O=kCrC z;6BN&$l%If;l0 zK}bpZi5zD7$9I5y9~hXZc8mF;R|%Wz8RA-(Rp@M^zNu^q+gbcKBfO8w+=>|}y7UBN@yzKajmZ-}@s2QNsF|7WOmt1KH_RFf-%* zCrlJ{>?3=2!EyS&z^DOcr2c_{nNA(nO}sQtr*OWero?KGeKYv+9jU}oNU2=-Vv@G< zZ~6!<%5$n`mj^Uf`2Om;#*)P3m9a4euD?iU;`q?&8lkVY+61aw{$C3)uwegRo#`W$ zZhN`cJK$ACz9cc1p6B{^y3yLLUoXvG9kr2~!^-MCI7k)$`2%WOcXt6&p?A2&dw5U* z6AF1GdGTMW-suKtGuJh7GWz-?U+AU@Bpmpc;|BwyeZ!+>CJx4>^_um%b%1@qnLZlH z_0!Fs&_$4w@gF&x+vmHZ-q(2nPDgpCi)*T7HWiS3Z;g(=@-cHpl=-Jh&F>VyY)8^O z$0xdXBDm|uip_t)-oS_+9BE^zNDf;q3@5i?IGMH;>(%ovIX7w%b#RF>HW-@x@$>I1 zdmOO6%%WM=Ievn2wB+T_#vI!Ym995({m$QQD;4kz85KU0}Tb3VF%t0!M$BxeV{I#ApanffZDtD6t0_uxRX1JLLY(9$@ukzeobC1 zv(1XhCWqp_{v|hi+>v@53#5IjLf4bfy-6e}?=K%Mg{Ue&hpd?ZD7V#gh~=U(8Ry)YQ{;+4D5Y01J{P1rgId9!uJ-7sp!cRAOI=?As`SvY#M9#&}O z6|v%ygCh?HJU2zK->Zvm$zm+Lhhd8Wi^#y-;^yOHq*c9To8Dr(310;m0ZF zmKWV;zQtjI`qD)P>V{Bg&e3RbRr;|VF$wtLUvOIga%<4?e>+z(CnOnYM@Gc;5;9+T zy2ZDRqIbH7%yb`6YTj_d2XKk~=8{8_JKL8ig%_r%7-k%bz>b#sESmQ=mmLsyYaA_} z{uTfPw@^_DZ~bF--^;sr6_|*F-+bL6=E+g8$&G9{>pv^GxPUX`F|7&hf=W3X%O7(c z0>Vvaeq)MLy#(W!mUAJUbzTyKxc(N3GAM;cz^|4*@iG(^tGN=<=>@8q9d6s3iKB{2 zM!8}j>C7~?<)+CkkqfqGel|35B=A+g2nDlUZ~4oGS2T2bz2dS| zAV@zrS5-E}x*sM(TjoTUV@#ae#7h3ul-l6-R=uAu&6oHg@%-U;wXHQUb-$hL$-c)E z_}XapH`heK4EkY+e&9iWU}~yvd>JK*w&S@Cv~}=!A@H{+C<(kR@`APlegi)pe;(My zAny3KwbKDUbz-%(H!FKi0&i|fkbbxo2HrdQw0C~DBc+f-H@C6o_&7%Uz@?pld%FXJ zjIW)*Zwq|Fg1i5`Ht~b^XmWE~BApIqEt0>4Mi0Xk-86{HUd~m8p$2I_9B|M+exkn+Ww(4Tq(BJ4)KSI~mOhv`|5s<`M+=NWNf_*LojkmZ)UH!y-A}<<-6GPpvdvfyUp(Fz0 zyTQp=2t+F6@=vk~4ofDimv2lPFXZ#*!IB#R8i;^5rb+9kjQ0t}=lK@+P%Mdb4L$5q zbR6W8c^y{U?}#D%zR?(p-)|FrUB>F;<+^5{dWksuTKF~`GdWDYjC&c0=Nbp2%y`K$8sKCXZ9bxgGjH9-&euZ89k#?JNqldz{d7c z^!>ccRq$?kY&fsGwx0fq0vDRnhC*zOCppgZUz@d{r z^s4k$QM7O8)wY7@qD|#qe zxWCZMcd%oqCPoQ6zoCjMCG}SN%_`sIe!wYGjZ~k@VGs{l3*3(1D?>#F#gpjL^4m$# z2R#~zp!Y$c?>`}}Q&*9fV@e=0Rr&$EH9iSy@92BSV;-OM?K^zD*uXPyTImnmDOf$s zLpm-2pC{RplmhMa%(caFkww&Y55ct4hw`TEV}* zjZm5$HR<*lzP${gFpc0Few7E*Du!Zwt}MEeBrhxCmaY~HroTzec2y)A*K&q9Inf#y zsk>0iaaF-sNj50cp1A3(u&buILW&2a!j^ThEZSQw;93-$gcAlEvILt{4gq46M0X8>S|7dC{FG(Ao8uPcER|0%=0c%x zWg!t643&;U(e2dNm_g}yxu_+OkT9LNdtF`B`eG{v4vf1LdIDXT7K7!ud8s!e1zW|j z^;8ofHPdItk1_CF(A~^Jq03J#_c+GDo8#PpSFa$T@DQ7j0#>oOv>H1xnl3`ix5_-= zlSa@~?v5A_S!BN0On5Dk8cI%41B}_cf$oKJtSX-U;j*nJ?$`}WPFqxbE>xb1Ks zey=sSw;Vuj06_k}O%=UOtq?u=gmBbzDK0rXv+iAAJKxXsKWuG2ws&;2lxAP_RXT1g zz=54?F`VJu3~yW>0|cs%GluCi@amHJ;nUf5w)M0Pa&wO=4h^vTxD_OiUvOG}WB$|c zZj%w;|2Zg2IotX(^-WvGjLU?fRL#b45lhDla`ls4NKLGQe=%e)w?XG*jO3-~S^5oh z=tZX`w(`*z7rGC#07Y6Z8QRKODpx#WO=lRBdXyu0Ajc)*bC@B_k;xvR;kJ5 z7X^A!I}M)M-yM+2IaR0*lK)`ax|8QEk=a&jwgwk`p)USwnoRfz|RxMbizTu zpDZ8sLy=t|o*PNz*NtTFqlRIleJ(JQ*FP;FQaOY|IH^P3lrx8>f8N7&mYWbuJfxOW z{#s6!Du=ggbNe)7=I8wM-h{WSV&vxS-3h(BZ$~W;J zgZJ{1_eT|maadkGL!_fKO)T7A^CqUIOI@+q=%&-o+n`ObUZ16wAesm!N^*hO-gYH3 zCuBpMGtzDwM#0JQl zRF^-w?Z{-8Prb0(wn>_t&6#v!(RWCLw5yd05N63cSa4N-A*;iYmwo35K&A@ zHUtgZl*d~jJq5M$5bmrI`xN}}@Lvn5KXCGFJtRLqLUR+R>GXxelbal^)-^PGdwY)4 zehEzUd5H&|=NjkXC&rtV*cs8yx%nDt#YWh6R?*JZ#wt;BD$RMNli4u;Be=F^T|=jEr;9+3;#GwJ8)C} zP=%ojwH&SEp`&(giiwv~2(CajlKo>VDJ!|78tegS&LFw^1h2~322oPU4h#RJ1230{ z*cg7`ULgjPoZbv#`Ke&_HbnXn9|UrO^;fVTm(&(b5!J$b(X&Qpap62kQozjCOR;-I)mDIH?9?W70S#=8P;S{}f!7T`FL^=;#LiHyA9W5cJ z%W-{iIU2(fkawUP^Z0%u-NTj^H*pMMNs5QRq8>U+DH?(iW=4 z`-z!Np0ANBTfYd!5+_!hogXAr&>Wjs88GOcxjq78BfH&)n3z*tCHVIyQ{bBv4%4)N zBzC>>>7M55UA2dS2IF_3ZL(p*o9y$T-YUJq8Y*~PDYYrl`0(ACzzFsCfL)|fJfD|) zdXeWT<)`zO1)~$KmX5x@YE5!yJfihV0)IlvGi8yTFp#iGv!3ggu5jIsBx9AGa06lB zH@k+@%#4*f#W4d;`SNCqxdb*V@|_+slTzzlrfy^MZwXgSp{&4Q7|rBwaRQ|*<<`K6 zYx6Q&m1(+R3iEL%35qj*3k6>eykEI_a#^bHp+o*#*;qw=IiLWYu{;W{S*XIfue^T44q!qF1WN2jFj?7vr<%Rp|+m6(P2{xM7f7#}#7; zAi&yFHJjmL1GA6IS!TrXGgyeun}#BoX1~Ufa(vpQ%D$BPI8ZD>KP7E(_7aD^&n=*+ z@4%jm82PCaUweuQ2DYIucvTPgF97?*EZ&F%_W|k02>7svWct4=h_otWHfYtuX-v`= zixK~WjgEP$b|?sEM~@I!&l^{dVG!d6N-G$zx|B7+*@PKxWwG?80;q1sQorlWfg0A} zw63++>)E!uXoj?EW35&HBg%|e8=m3z^=oi1<`80CLAf#W$xC669PjVpWzqVPLA$y< z*b}H0JlKA9T3zDYC$l8ZoJMMBGf@;Pe z(DBnB0b($wGqjsznW=-ZjV2LuU5AmD{fc=DN73+(8$f08KpNZmMU+L?n?9b+6Mw~H zk(Z;)9`TS*H=fSy7Ztg?)%kBOoI&%%{AT~ICAHsteqYm8RKSI*Nn#L%GM_&$?x~D@ z#qn3lhNBrW>y=7@DqA0FT_m!RC}U*lwJzb34>!^Pk_1vm=&SI_L%^vApUb`9o)ExK zq~HY!B!24Z`mgYX+ar%lJ&Xu)YJrcNXvC6oXjyR$ z|6;2X8?{Qn21(KrQqMT?L+@SST$7rYeyLpewW2O6DZTpcHZDjobB3F>s7T}*JVci; zR~j%f?a;t%AqIZyNcFdlPjpLjS<81L9dRC@Zl5{SbJ)-haOr1$0z)ar+$6BRTvU91 zpF1Eib`3J_e5|Dr*a{+L$K?4_yYNI<$MGVR`bYbj$my^t#XOU=|KEFj2j!2~sY73B z(c0F3JsnrqXdgo)Z{RiN@o2YibPsez7miNGzs=&kuTHuX)6&u!`Qc3%U@I_|%hBk1~NN0M?SQ^@_t}^yC_E8!LVw@S$ zXR+lg1~vNwavHOv#-HQC|m*FP{qlWfXZyRCdVOY|4IToX5a z(~}f9i6kQ=rO?Mz|2Ydt=U;X0QBKq{w!#}>qve}pG8TFgf9bJj$;*8hinm%9*H|W} zVB3btxAA2tb=Z#hD(ihbt&4QYE^qHjh4^Et$Ru{D z0HSsm6nF)CmH{6JiPA?TVU%lD=vQJ}QT?jd&NuGe-aYuVV4Uyf@{#&q&6$T!ga_^h zXmoUkRJ2nKqwG@|ww!HE&Ccu zZl}~v{)nDT+Uv-8^608RJf(`B9N{qGEblOFk^g_a_dxYf-Rggxu92dXj{ChJoikV& z8*jc*%+X}zLUk1>$&!TmVwG%#%Kyq8JJNA^O5!*C>e^(aS__qipFM}x)UYRf7XO-9=!S5-Nd;A*(QOPE(lF1O zGw}dLDI|GPNAGe$i}%sVYhwQu2U(&7pEM-przg9Djr}p0$BY%a@}JK~&PFCS1@P?g z)wTpR48I@B-3+nJzhCj^w*fuTOt{d$fAaCPA}s5*7;&bV>-GEu)Ue7uQgbpG5-yj3Q3MG^T!2@i_bQlF4! zruOv@$%wZ}-hxEp{^-q}${J>)ZWiG@2vv6Dn;bLCNrG_V>x!c?!-IFl5{#PRdh!q+%3qSVBZG}?xd0Nj`aM_IC^ zj<5!uZ#fZqYY!;7Xh@@331eWd#@1Z6F`o2S|)dP2}n2 z*f&m_pfN2eRW3U1isXkVIW%6%9DaN%mWV9G>qa);^j{qD?YFmlG~uUUpq9uxE}|*O z>*B(SkXnHKsmQ|~wTCO?OqX8<2RcgHr46<7Odfy?2JfD625M;D?3Zp0$QTq8qnl&6 z<#JUhB-CEl_%00x_6I#$`}cmyG!(EJ>XRsNqMZ%u;y8OB&YMb%o*_1>(fiB?4BQ&z zxMClOc|To~i@cvGFG=Kzr8Pmapda^eC6S68YLmXl8h_ks3;Nz?|L?EQTlko3j92D% zoSVU*2*R6v#7bm^ZKvB2>c9QCy4`TAUV8xgj{6DA2ms~K9=mKEoQcE~ji-B<;_x@4lmHs=A2a9NOcJ3abY`R?_c zcse>oHkddxps zI$G9Lybr0ZWdu;k|KK_R|1sgu`vuBuFSt2>cI%Dmzfz$94jcVST0!rpWHgbtWUnp1 ztfeJ=B2r=ui9ubSs(EgYkv|t4B*Na4fVUQ~eA1OIuJ^uR4>(T0oOyTj9ZKQf_L0bJ z$-)+zs}P4SEZCE!2A@{Mn^KZ#LqVlr&u+lZG$xWq{xWkTqJq!6!1);5g(TvjtJPVd*#L2^Xor3a|d|( zcmSoO2d-@%sAPQq6b;J~#o;7MQzVusn8K7>c>MeQ+rJbbXVX|UBcp5T2KE8Lj zO#J~!0*^m<;XXy17{FAe!}QJI!x0+7ob1JNH7p^BFgU}eFgrJ^YiU6)+}?193a7TA zb+`N1Y~OHRWCU7W`fiGyw^oP23QEB*BEGnb6Xnp3lvp>d1Xk{n*lL>jX9R3q zR{{$;XN&IyilcU8NS~jpknS(SZI@UZ?QrX-`aMs{lGhT-$U5kfmt{@K&}L}R?;Le+ zBwqW0$^w9{y?Yi+uoeM^iwX8piOHCg?C_78;z5a|;m1OcBi^cQ9Vj#GqoRQ6f~^nc z!oq?ZM&t!Wsn1wFv>AEU;vdBixG^v_=(hfd^KEC;{5l56qf*;O&|Z2w@Bas0L7~2B zO|1i+1TL-T!UnEI(;35BQmub@&HQGxHb81c=0iYhogRu9Gvzoxo>G3OOk-D6rlGDH zDpR4gNuW1GR?7}IDiMg1sMkg-l$I>y2kUjmd_L#;>WbNP!u)!UJ?&9>3_u2ejK=Wl zLz%uGWkf?D`T%MKiboFlW}9)e{^vjJlSxa{G)yKFx~@yWTPtGJgkT9FqK&2^;+@CZ z4bb%&$OoS?>PU)oCc*!JGAXO8l^XcH1y~pGSwsMX4{XN0p@s}m@Gt@(J6XhX9t$Pj z`@nj=W0IhVwwA zs%l~h0ECbO7(O#Tk|}cbKBkvLVok*1cy-i(!skF!$x3>k0GiqX9VJN7wk8QNyT z>8(3FeE2SR@80L=@R+7WRpcN!MPDTCniDC4XDp_!x5|GO>H+YHU`si^bBqt$4;VS<}LwIijcSKhPg?hjiHK}DJF?!x$BhH(A2GvXYIpo?`ZC2=bg*noDCIUy5aH553(y(@xkI!Ea-hZDLA3tLy znxQZ~CKh^-RJN=jw--&l=&Bg0qoU#6fPZ(XJbUwBL*XWC3 zowTRYDsR*CUL<9tt=(j9QfWaNYsn6#mR)K4<=BSffGx^rS*J{>QK>{h@hPkCo!|VP zqxt2~W81ro{Qv+U07*naR0efg3B)9VFs`@q-h;@{GDk$HOeslFqw^(*gn`an&inWn zx~>~OPg%>vsBq2>0N+}hsptWv1g#Q-;OOWmXFO9NW3^h+G))5TS;#S!etHjwX|6K+_9ETNdU?q$){^O-e zFk?)YA3p;(G91d>P#6h$EIy=Qp6xBY?FXRW+kOZtrk`$Ly^L?8zVFdW55PUZz|2YW z(v67NEi3#9$^qRgME57CBfQrbm_uTT1<9lgcocKJqw5o|uM<*@O#Iu~eG5GAwjWFZxEkH2?#fnmwZp#+VU! zF|PpsauQ0db)iz1f8DyvAaPSC6=MV`S@&E#-~-Nix^B&Sy-FGS{O~KS#)VZo_Bux+ z4iuvT5+#rEt3SXSfLx-1ecuz59)cT*<`jqJMWuhKHC;NtX=piv9|9t2-BkD9r>t*C ztq)7KpS4j6#1);fa+ z1tC+q3oAg>s5Rt9F?O)g2W2TKNFzG~<^7uW=MmYi0W2BxF*{-R`jsHYu-j1}CIzty zH9At)HA>RMHknL0JG-5?Z&kyaW;p z;b1mPB_TVlX2$j8n^uV5fPIziey-!cIp^gXZdfVf-OH93;*kk*izVB18weRU|KP;DYMbh)ITrM};&-?77-4Y4hb&AS_5@UMCo%g5^lK5r_ zUvO{i?Z;&M0Kne9ZY%E%Yc1>bn#04xt#|x*neT%Y4{)5K5=y_Tq>Aq`yf8JF24bv< zR0PRw^m68}SDGtb@vNEPm9Un`c{AbTdYW2y8G|R)=ilvntSGby2X!hVjiPxjnwJPy zwE?BL6C;iDMCVxAp5@aO)8M&pB4@SXNNXwqyk*&Yx&VEx=!`+v6PDZ1dWRn1e;pyAN>JoJHgR;%=mA|h48va?+F9o85)Izi7438tl_2cvwuz<+GT zkDW{=uc-cipYE}}eRrlJ)FE=#TkiEMrt2%T?XhTVXPFVX+i1>em>Nw$vF_H053JXU z$IoAI_ud13@ym}uWj`=PLKK2ZT|Fi~(uP1K0l{N!$Nbq-#9C^tP|+j7Q?-U=@LagS zxz@a>TAsHDJTnz5E%Yb?h7?A4P39j)6PA*pCNu$_jjkyS_$$#owZ<5eDB^9q`8R1( z)+vkMdGELKc_QSfN2>Sjx{lRqm1?Y={fd`o697<357|?dy9vDBcJqj@TA?0IMQt9UlVXHvm*}WN`xsB3;*|byO0xGkT*OU#Ll1>ja)c931jZ)z~>RzTWJnuHV#;C>9)w`uSj0R2T-`th>E zepPDm8B5Lo`1{uc5MFx_Y#0gSXR0XfzwX%^2laNBP2X>_|9#)HTCG^E*2A;yY|i|T zf_Q_#t0=5pA)=Ta9Bk$lCHdKk0|jz??~Sj;cx+Ses7ytOVF-o|Wn+8W+uru}7FLoU zRaG&aPFXA#qd9Es2YvfCWc?-2_$ARr2?8WwA1MDcA|}00q#|HILZSgnAPV#mUK+!n zwNskOgx(kyDCVN*mBNbxQmetBlAvuBp;0D*0MqbE-SEs*^h8XIJo1)q*ky}6_;j)(-qeBTwE_`Y~(=;2L_tV@)AG;UR4}Lxa&Hm zt0hxw2{Gbgt(tGqZt*wQ##qR64SXo`rL~v<{~r7KEgLxW9^-q$ddcO*CGVKXovH$XRS3)jJPC@0wOsqaysBAA#kH=v zGBq}<5=3+kJl+idhgN?INvh|$<{Jd-J-*Z*=LbEK+UX?#H09vnfaP+@;o%|2$Hx>^ z*7bUg%k=3qA?A}Uga!*spU_)3O;A?ajfP~UQlF{-= z(H4kA?=yIV82te53ge{cBlr-Ao&jVRYT#rt0bspe4>|y4Y+9+5$pu0d`@6orCgwmu zVP81s2b%LHBcDVXo3^ECYKX8}uUM=XIe@jIt{R;4ES3w_>lIy}!~~&1RLyF+WW8E# z)s;DCQ)XZ*v$|n-h$=!Ln{4ZM4*I{q!YCVE*e;m}0)C@D4;jSE<{Fjk_mIub-zSjH zb|7IFG!G<^QSK#gvur0VxXU1TJ%!m1qCly>z1-Vr(Yy`Wz~ga{AU!XeV4l+IhJ^S= z*e_)Li&q&d8O#sadOv7(Xsxi;v05cvjrDq?Ns{ViEp=Vx5|gmw*i421T?tNTqp7QU zU>}t^H4I=s4C5SYjD%n?rXqwu)6{5V((%4}d+cp*d)wP;1oO8+c)o z{@NW;$nUR|$ViTPyumGxfEQS5MXwrSjI2cyMJ2x(2CA?CD`j|5H`G2d_nt?(;ZZ%~ zaXaO_svvmU=!i~H#lY>u$XO%Y@*S-Xu$2SCbiCrFs7H zf;+d*czJb!^^V$9pdu=I8XU*oa@zOUs|)<~k`EfgJ*~K_VIe{K#@TeQmg? zT3*&Ib7ioSpPNW(zZn@4s=JoJzY>fx=uG>sstT3EEWs;uA`|NymNycrxZk-%SJ9}Iv%Hnqv6et&!08Sv%bwbn?}AliYFp?##ytpGzDGZDaz z#2Ja3c9bzDg>tHjF+eoNaCCG;)6_IggNR~2pC_gBDghFsHI=F8yL4}M>owka+NQxf zk0{N2F~_?NSYyipVbCn-)@!b>uX%a#l21ST6cEnNZt>oG?{j*3#)Eg>;gA3Lk9m1< zPTxh=-5PB)vx6D8&Tet*)-6s>PLjStdP0*jdyMHGP_lJRQ8HAud|zz~Wbb6cLkJsM zq$KyKWZVb3e*ySoW&iPZB#8wT%6(d9vuuco6%*Asqc6F1X)H>Zri39=lQ#YegP@EF zB~+C`sV0j~rr=b0sLB|UK10$v8IC(fOqKK{taHP;*?{d=SqNkLefbx1pg|i$aBc{6 znktoPEi>>>`^dtPF`|rNV$4vxA7i46hTIa*zI4(S^E z;r`X88iFD>L_7BO1GU}KkDFLy`)t|XzN+m4`XbJIa&oez`2S4<|2Og+WtTfDudJ(v zKyk{+MG+t%ILa(P_FI!spd?>u^o|+!7t`m@rRGm-VKzC&1bA)?&(W+!5l}>x+5sNN z$erN0W!D@!hZex0nr(85sdS!-$ltNNAoY&7`3H*z|h@LrQB|qmx z7VuY=O%`)6Y0rAS+K88tvtjwf8)XPSpp>T1^<3RLiBTmQc9$sz+hB4S>lcjc?d zQ*cJJTCYK%>-$aJuZ%MBT0>?Dl+R%Vgd!Mi&_?GBd8(<`c^?J*m;T}vn*RI?Nbfxhw*hU_hX^<&t|inS$9K_!Dr>* zax8USVf(z@keCBODSXxhC_$2PoCA|YrGGw#fwq6=?p>^P{Mn!VYaTy&%JuvjYkQ1I zLAB|0%E`$wXJ@x^!0dp!uJXA}T@ca>Cu?Jj0sx~hz!%=D-=z)CSk6qO41X8`MPYP( zx0Yv=#VL`h{QZr~aPXWH(+H^mUf+!{jyT<41 zrZR$bJwj#>z5bpmXb)(}M$MIQql5VT>5@B+AK zW;||YJk~YOs+t;T#4(MQqkhHZqeq--cyFROGwJ=cREld+bP{Mpfl+iySfLpRZY*AOF4;Fb|?8_mad&Exr;xo9}Kh0+=w z0#!b)7zL{mqhg$^Ef$4QvLpphc0u}>B_IgST9)$#Cnv{)CexeP>sSbT`(at~+EV8` z5ZVx!_>KeHbE?4iYt(uHs}=pKo)WA3$(Ks0zrfpMJtioTk04%6gY^U21N|8?k($JxH1)slM_0rS*e=qs%D|h z)^WUvnJ-=>Z*a%wF1^z0y2cnYfVm>h;+!Q>wnqt%9pFCB{*OUk0sZB^D1nOtSjIwpy9&Nz05twN4mRutF`RRQa=u9F zR#8byL$>{_q0GNM9U_PJo zPyg9JLn{La&bvXxF2s~AF4w7Pnmk5>Qj!Bcn=*q9u#`fT?a z!uGSb``PZYfVkC~a}Wc);arq*nH2O;sq}(?LTv>dzE~IK^KBfc*xQfS z#`k5pce`9JIDVh)ZEs(vS!?OKZV>(3&ohZtX0^hFToS1jz69N4%z?}149JY}fR2%fBBD5UEADnHZn=(Tb&U-WyyKwnIBXOOFhr~fFHv|OxOS0+7=o!& zBMSi(^Z}wMwDUar>@$An*FWUF!x^imkEvpy6GiOMvD)-5Y~yhN7m zluzpeR?5&RjeAR7C9{1B-ptC&f1GI@1HPgW5JI9fZG*WKh4azlLlQgdx{k$SiOu3v zt_V}*jPLg$qfpoNaI8(!r2f~zCPo9BKF6iq+t3y(uRjLO#{ir9{hL6=?)^}l0p}d6)fz}alNjSx077fcv~3|mZ<4U( zVzJ!ZpJCI2umDh_&E`6>9lR;Q0#Sm?B8M@`u-~$sGJd5t&rCUfRqCnpz6T1RY)Ukg zd_SIn*I7A#yWJyp1tnkCU1FC#Qoi5KFpmE&>y`b!@i=2)SFrVL4xIrc_aTmK-H%&i z-TixKth?F!vYc}cV>a>Daz4sEGCo)1Wya@b+<{}P>_7hOCM$Dk2r)5?O80}Ug|_)6 zLqKPjQZf2|{Cw^n_ufhW@!3t+^rnF9-uCu&TS**Dr&H$h`FA~>@6-y#-N%S%jY6|a0qVQKXFtwJH#t^RSDbE6Yrd!VI2}?9h zgdm1P0?u}H=jYs(z`Yr~BSND!4o~plT*Ssy*x;%O>#7E0h~5pr->y6jFl~X@V?;AI z4bQZuih+}E$t^T9>+paT;oNARM_5HguPc02;Z$a@j@W~{FR#K#+c42%HarS{amc_{%GP?c|u}Pd|g@g5CwH-cqktw0KS`m>3}%VXZX1 z56pd_kLl;7GOU%tD#@)xzr4M1=6}};z?n{`LqzuI=!m1EBf2h$P^DhzHc?y0&VK%{ z(A@jJr|&v^2rQQ?`aY>s>kLA_4_1KnbUGbc942t6lUi!2uNOtB-yR&|5l9|W*T&BO znC@P(=LJBDY=RF7)W@M-r2vO9NEpCGjKht-n{h34{<==8^i5OKwoM*yTBiW;tu|wM zAG@sx#{hjy^Dbbz1O-Zqy#k`kIz>+awgJ#Cs2bQ7BO$+X4htQ+1Q(j7p>5k?+qUm> zO?C;MB*DL=o#5zlXMiy?qwKTX17&=D-_vzn>Ybj~OUIVj8(n5$#2BfJ!I&i26T&8I zYn@BMn1N!>@N?V2-hBUkbgVy@G9I@}LT&=ayP*H3Wp?-Xc|d!2TQ`AI*Z|!`4-{gd z=!uiWcp&KQ>g+z7rzHljr#0sj(U z-3%x{%jHN*aO9OuZ9XW^@J-);AMew>eLXe?`s3i(I0&$}y?xzQ=DTqq_%E&H*N_r5 z1hhq|p*&z>aE; z2f(`%xK%4`Rq@O^p1HuvwDh`Rt}7O8!^?I;9CVQ)hQt!k-r}9*>eEm7={pZ-tD42) z39Q!~i}0}0oSBMaEjT4CwBpJJ=GL-QLNA73s$3EjNxJ@;R~)rBu(t;Pg$6&FOz_@w z>((vq-@lLdsfF3q)g{;0S3^cOgqQ(wiNGZAYO354P33GgF|`VGp89PE_YK(C(J3@` zC=PN0c1RZT%G9b-hdZX%j%mCFsFv;beLn;i#(nBjcZCLHG}fkIO2`3#-M~TVR~pj* z82X!+kV}w3gyzHfHDRi1vrn{4lyQizd}_We?A6J zuLLl7l_fFWS6QZjka1w9uIquNVT?)i)R4L=bX~tyGi{wsZP7A|VjP$$R@$in!*M{O zB$l8-%%U`>FFs=)8ymH6m&`uqku+5VKAhZPZ`Dc-?<(KWMI=R zV)y&qK-k#E_r!Sp@pH7x3fT<`+z9w@0LSHe2_U2EJ_Kd*TcHGHZpzG$x4U~UkDZ6z zfX6N)V)yuW=Z*5bcU_m;MA{($u*--T|6a!Fb0>}QxOUkMyX(HG<8#w7?Cr;CH?dvz zz<+PwlokIWgpj*Y?d^+fU~o|s^A+7DjMTw%+6u>LPK{xu6zAITTq~Z7LX1!~LK6c9SeP2;J>l{tQ`d1A1GgK+ ziPkhm6GD2AnV5X(`rw4hu9&SBC>sdQqn)D`xPxILLR~993q9v{P1`mcI7<^8+B>3F zthM4=G)vRsMJ4fE*@!5XAb>~`}mXm4S+v`8`WgcMO|21Y^*L~Hkk}9jx(7=S7 z4`47OkzmQRN?mI4tYVQ#0)apvK*ru@pL0A?M9#eTG0q(*WzyPcyoTn&G&z2rr?E9T$+MXfX8zm zBj4M=y$d+0*crpd6m<0hKWG>b&t~RNw_gPQ(~rK^n)!T=wU*Ut#fuj&h%r(W1!rd~ zZf%t*>_das? z$$U)UJeQQG#eV`o37~4NpGbJM*84@(L8SZy1mqwh0f5}|Kej+b?Xz_c;THiZ)FGZf zJ(AKP0e*P&=qE)&E`c9|yF(bne)}A-=bp+jdGTYCQsB_n@v%};zocqNeNW&hkt?ZO zU?8HjB8tINZ}mskr_$#*<^pb1*qp6y%=hT#i4sDQ|s# z?5TMO)42tX9phLV<38lukN2G-#KwSs>fV_m0e*}W`IvnS*nO;>qe_I6{q8NlS56-P zlYMGSPKC7Y{KFHAF;xeML@^{O%caW)%U%v3Ho4sbGJ=W_MI;aj0xW{Rmlf|#0R)1G z^ipGm9!iJ_NJlm?P=tUM0vq982;LPn|D`HE7{jfWC@-mmX6_?p*P;6@Vtdc)uI1}W za-j;UeL}z{LLcOy6lMq&=*6I1=(`Rd72D2HILAuETzW3FqBD{<1iH{uxR$TG9oN36 zbQZ5QcS`YBFZrAC^hzTOLr`icH_c;iXXBF%VuV=?ytIK!*K%fuvfn-o$&j12<=k1WwWL;oxsnux!Z8fCJpce8 z07*naRQkYO+jEQNzMgTTEAGpJRvS9x9_9xMAE;cQ#AEQ-fn`Fq9qYd1t3Q23I6p^r zJLXcLCG0}rK6t+Kk@xk2wonMAxiJB?SYa=HB;4zMEYN7tPtwJeFj64aUNQA-DstWn!e!4iz0hRNEbV~84Y6vktQyvsW zK~WS3z@7uVy!>B!FZcSxQ}7=`c;c}Ho+uUazNR@c20%Hm$vu{Ns6^T?9m{*qdcCG; z8fLTEuwNoM_SZ5$?o^-1#wqtm=S0Z?(23#aQEScR6XX>OSzNihW4WR8E8O zagTw!pL^X;_Q$Z3O!j1-!qRu$DY4{WF{>0Xl>d9~c*-poJ0FMw@tF4|?myWn#qP-% z56Z;+j`mV;uQf$cVUa`;X^iB9srkN`@gN0TtyxOYK4N^!yxUSX4=h8^7nR^lOM=#{ zg`is;7`-%pV&s61 zhxg)R=v=-}%&vssNxLT-ERDzW3Kz)|>2=uQpxhitu}8nBjQe#-45$z&V?f485CSJ6 zRz#M;@w#g`>l-S&!y@RAxZV<*jtdDdH3TW?oaciB>pc$^8l~AO#nue-IFVI4M9S#6 zc8>GS4kd?s)Z%f@vg$0AgzjO%`PC)uha0?ew9;|!JU>Li55x21CV?y$6!2dpA!X1620AS52}d}hQw&; z9CMFpY9p0U%&+74IAcILHP%Axud9-Wx&8XpYc4J>DavAhA3RNbmvTWQLM0!c-`hfZ z>~%gC+L1oXZG5g{&v6d;$H#-m(2ryN8XqtJEbreF(0m|thWN!}eb3vO>RWy;`8*zP zKmP6*6AELs%y=HB=lpeQYfLz$K8(XMeu_+n2D)u ziu*B3$<_}snIioahl)-6aaTYQBX#hcd4~xBD~8Gw8$64)Wx2hl+N-4-5BI^d>N{Qw z_^J}TC?q$^@V0k+umO)CDvc{jtX4QN97n}SAYh`U@;xtH$CukXdZ}2up^Uq79j}0^ zN@4FmF#FRtl-JjEH}7x}Hv43k>w3jawPdF>j)Ac7LXL7VjqlH&ZhOQT_y2z0B+P-= zVzD@Y{zS;6z9t#<)8vDX z;ANZ;FIR(9Rdr}LFH4pdh>7eN6AY=HvC3e4eq(QY-iNkrS+CcJ@Cm7G@w=5TPR?8*J11gt5nUJRg29 z3+sH2PkFfW1dusknDUH&>~(%mVo$KdL6kncoifPBM-4^X2VcbFN{v6R?dMzE19_5GWk_=_V;~TQ zs!YVa_dDRdr4W*WA$g@I5)fz~xN?>&+p_9Air{eqS}C~oJ$l=)>w26Rl-1idU?hA| z!fONPr6g*}2U+n}YrOA=B$BdVYf7v#6d|JVbTQIMNfA9&aHw`mB*N!txwPCEL)*5`7U#JvcgjmQ28ns1 zx@2kp9I%W5fAV1G()O_jGq==cURyl>ECGQ8@^hd*CM|N+Kz`ihK~L8<^*d$8&w)zX zHXpn3_#E?OCd3CyclUF0?v&sNt5R^*#b#2Sr zw{Q9I;RDO%k~eQ&^W_&`u$a#e{YzsoF4Hy+1<9||=W1g>e+>Lh$~Mi2r>A1Et@p3hmiz`w^p)$Ay3 zixL5W<#h~frRKkG-_g}`E|+I)HVWY*MGVxz5=5j85i1l9gBOY*#E=sq3IcvllmN&H z5C4#Wn_pO;{a@Y0ey$~z%H#ig@V^hK5JEy6#;_t{qNlPwGa=}dq=^zIG-ZffyN=h* zma^SZ1V7}I5P}7;bDj>tuJbI6;H-pe4R0#NC4nH}eTe*3D!!eaqe2fcV3i>VjYhC? z0bEBb1g0#gM5Oi(*)<5^DMZ8=$%TfOg=SVL91+*|{BU>A<;xdr&n~#_ES)ZRFeSS^ zDfX#cDEe{nHoTE)$IoW7pVd(E_?BhKY&OFfb6A)rFMkRRh%p{O;(R`5u~@KNE)Sq_ z3ZVWoEeE!b8TcPTWLg9#fS$bE;{<2p#qv0QcWT=lTqa3-p4e}k^lJ>%^K-~m2>HT4 zDKL`aA{`@Hp5Gt`=_z(U&;Flh#80Y$^nNZcPICnw=Ui$l_qONYXAHO!nK4yvDqW*o z)||)eseA^W$@M5dBNok4n+^;5F_mTM3cg89o*J-&_HmRNN}bw}qz>k{}gU7yO_K zZk48$5hsUzm%_2K9p|pcXvKvTTt`PIHSbNqLs9TUgn0-U>kuN)i%26iecw|wI~Hxn zYaMx^6*Dy?P!mEBL}bq~pj1iGH=Kt^A3eL^QGHJtBMTiVRN$rZtot6MVyPsHX3bS_ ztXu=p(}~D~F8Coxwz{M(Yn(86p-Fz~fddJLJOFYp`49Wgq!^M7{tVvzk70XVds+o0 z9_28<_9_6iFWngMT=P`2hQ4-!dXJJv_z`DL3TYWESG)HJc1WP zLQOq%m^7Hwe`Fwr|6R4^x%WnU9SiWG-C9=trm%w6-gA6=R zs5M@&kK0X>_yj`JqCUNsr0MCJq_NAr@`-2|gP^f@aqMZ&fk{H1hYFra6pl zA~nY9jkaysY&LXVN7FP1aHX|oHk%=YplKR5n+==I2CX&M*VoKuGeQXLb~~JN7*nuX zt$6wJ6|Y{s;?=8{hfM$ZSWI2FF_8P5?up!{!2T2%pSpg>2!i}|K7Wt3eT+EBk2$^< za?kv@FEQ?yJ~093eR#^~`1!TU!x^UT_3`U52{8uYQ(!&+Udg|Arc^QGW8?(k*v0@q zZF5Z0KXtu7*ZFy}-^Nao|C4=6OW%=cjWy0ybh1xp@kt7{M-g_4H+}>rhgw$$>xINg zi8nR(#(**eq1Yg3fhhLLq8ZBjEu7`TIaCOk7-@y%Mwfh7&iTO<{2(P?guuCMDWk>p z9lQGtB6wa3&ub&NQkt2Rh<(ZME`mp35qP1{(ja1sz_V!@n$EF|ftd!QB!zog_OkQHttnV2!~Zs0zI~90vui}Ppd_N5MZnTbV*5ctV(* z?5PPj)UqF{QbaUipRIog!x)f40O7gn8~(JpNA*402ZEBcLUL;y8y^X~HQVS10;Ufv zWu!2g)&^AXI5Uy+QgUe&YX=W8a&J8d#hn*yRDsn6y^sVwgn%r4z_^}O+fccVpkdeb zl%1oFZpcxgBugRKB6;vbGQbDt*+#fkif@hLz0%yez~zf;?mEl6y9c&P;e=+$VgOGw zOa40c4=4PCr;ARlHFaG-@v3UAX`1E!1oC92VE{{%@gWueWPb^CBoBDLARo(|$3Q%h56L?iV?0Ro)3r+H zoP+!HocAFglNjSc(w-CrX{>UYgM=JENdA9?TwD-B;Qs!8-)7+K z?2LAe*Q^l$iA@BM}YkJJjU<;oN$M!&(gi0D}Tn{OCKX+rp9Utw2kkTW9NH} zfH@EtJWAG1i=304>}3ClrSGMbRC@S5J*iASg(a-9cfvkR6u1ZYat~e~%UkbDukEGS z!w-N&2u-Ks9`p|0TFc-GjYx>YZ%r3rtqZCUsjTB(NglM}rYN~7D%R4l5t_nVqz-)H z94p&W`+$*xR|=L&;#I*e?$@Yc@c6ev(rAM(NHZAMAWn0yp*`90LaY4X%ixrZ_7;aR- zhoIO=gID|1ba6Tf@gLgu6(|G(5d|uGs^D3Ahu$kPJ0a;*K?n{l182cAw>v_VAQj45 zND?o(mayZJ;U?s?hATqO+FZ0@ixA6m)9F48^(a+3A8H z1Ufjh>rl2uyOtONSHUw=k#h+z4Afeo1>6cv(>nU#X@jQ=idIP)Q?M~5_qz`3L0rG4 z?<2i+kV0rak?>zXN#>Dxok9q3kY4k+%}+3;6lGaHllbN_;z>fEKz~`5zneI&^dodk z-aiH%YzCdFa4L= zOaOc=i-#efLsE{Ue&--RZI?3kCbhsZurbaBFqZj`$2S3&uImo{PhlvDj2ed#r2chX zN87ds&we68(n2HkKhI&1lO1VpCw0O7{T&c#nk~!alI!bh&d<*eW1AK->HNkaFQ2nV z?WX|x+{Q|dsq-2WHNZ0>D{nhL##HFbPw7_2p zW1?exJ~`Pn{yW_-`FW1V<(Lv++_$MQol;0lsS&2e|70gS*~vborSHA8{;<|QacG?E z*R}C4NPI%+hP~vUed53&oBi-Rq7Y)Q74QKkB0(vn*q1q$``?s(Ry-jjz0$ljHC7cY zOUHxMyfp<6TCKIWGB&oa|1cq%xqH~U{Epx3$sw0`-UHM)j!c#jLPmNixOI_t-t&OK3ym|14#`Fu8eOsz66*qH*K&RJ0yAI1 z-Q8nliBAUp4@oD6g9zO6Bj50ql5DmOtmj*VxlMUdWBfo-s&0=7Ij$v7Zr3`yW@I0e>MR zA^0aA|1mHgd%UNM`!y^n`pUATZQIXs-S~UAX)u?|{hvM!CE3*Qm&gMF0%9LO?cxCL5Q22M#2yF= z1g$K1TS)Fg#Kb@^B^#-+QegMMH4nVf9?bg_b9sfq;8qaG3b1g6eYzXXZ*dtC!rzO4AZ2O)XxHlD>7AhY(({QdqtB8~W z69bpVa33tvS-uV(ubX?~zARg1EynefO0#f+|K9c7&gL{{D;5H-+a1>gE(y30@hHAC zhVP4lO$f9Cyfnlpm`BgtJ7(UaVx$+6Mrk(M;G{%ENgxtLpbC+t3lz~}LQgLwom6b4 zqSG25L9ovY6a~nk`amS*J_;zYFHpb#`w7l~eMWxR=Zk+bFNP_T!YBojh!lYs1wjl% z5C}xD6atL5m>99j;Dn+NmO6O8w3f?uOWkiM2?XzPNPM^Dy$ihS9q)1YK2Tb?5U`kO zOi{75mcFrkVc@C~oEe3UkuF3Kk#ilH6`Ed3{zq#5zk0zF=Y@={jKqt`ZH#yay9jqNvhk8{gW&CKiN|1rpbvr8dpf1)%aZ%DqF0)L z;P&>G#bU|X*^1q6J2-j5$B31G%yhb7hv%3|m|3(|h<&W<&jBK7v6zFH#L|{!c>szj zjylf{|2YC4clIttFb<%N`7xyZ^0&Yd5?p(!YVMhMnI(Ay4_pcWd0WG4%{C}{6Ka32FJ zQ!!i4xab?s70l$&n||-DRz&7X;X+_epa?zND7oKRjE$TZuq-8|D(L}yhxCpM0{?DX zu6)nRc6bj_X@oKC9wN~goHD5S5-By;-tp4+%xsVJo~`$^)r=3puu}yNO)tPISlFH~ zy`yq1$~JUTK|SL=nh%}BDvgtYC=?fgpf&5>VOz_~TJnVqoEu4J3|#~l1HpPW zKG3;9EKA;*8Gl8yEem>Ma9s-s&fOMmcg&@t7BGuF7Ybe~!BQ$BidL7{;CP^C8zNq4 zdKdZ6qTsLf5{*Geg^LkOq?3|XNjfF>xeXxtz;3hQ>gtNwtY*D-L%PUMw3O2D+!N)T zJII|=jPozCv=Gd*0H;jy3EZTlY`+(vlM@y>fXo#E3FIeW@G)?dfOPT%=P~N3&9rZx zL@)vVaeR0l1DAvNe9XsEUU*)g-CBE)rcZ(K)TbQKCS`yzhN38*^fyVB$Amzx7DyiZ z9OUPZ^jQ-XpJ}B1L*PmobpnqzjKwuF`{8A*2bA$XCL6F}s$MT4bkMS`AASYDPnEqU#{xKqF+@F)3>|`hV zH7&-+WYV8&eyEfEG8@4DM-*#-k_s1KDrel%TWSX5oto}s%$ zK%^T%x`r6KQ%X7nq>=7!0qGLy6r{UDkfFO9i2;$0k^au}Uf0Jj_;-f0X6?1tT@kC* z-%kuw;-v5Uq~rd90yH$V^%!r>XoZ%JeO1UTx7cu{Pz>1NC56*TWTG_~olY&O8$=co z5z($&5bAjabVo7)Z*sOXb)7w zu~#ofuD^HD?WnPA(A$i>dW{m@`zqwqUz)V{s?yO(8syMa-ltLY@bb@^m!<0$O-CBW zu{Y^7`7e@1O6n8}sZ%K@P=8JoITU}VlaeVs=IZDrwb~ukJoH{18ch?sGt^iMjaF;L$%e2H=6}| zXYi_7Y6>E+LC%KM!7+tC++5xIg1j7eL!KapWq?+@{}leX4yfBRcgv8}xtKX*RQ-eTDciC6K0!a_87U{dF|sFhE^O((l~cWs_QI2`+iZ{iT0 z{Z}#k;*^58pT1XBCWhcQfp8LRvLC(JLD22GM1+C*h`)p_qqkB3f>a`;2J7z~-R+#98%6MIpO#`sm*F z-NxD)1_UANoKO+^iH2Xc8^H(vWFvlYn2XQ^F&WhJRGrXq$FubA>n8qfmmt*+ z>o+>Fz&~EcneJJ1+?S_md9ydeYMuaCVKkaU2-)_#+qk7)f~pxSwUYru$Vupca>Pq% zk^oLL^-2Qi$RK7EU6#(o;9}s|wcjWYJ=OW;r{&Cvoo-Mc7n-r)#)MjZ%DNKyJj!Bn zMX3{a*E(Um^+s$XkH}77^~n|pp}%=mK+)m$|6G7Nx6 zB`&Q{N1VA2-U>)99r4{?I{BP+4JWX_uvoX^Eo>A?Z_OBzjFa3Xoim~A2Nb8r>~#W$ z;&1H};CA*S>WwgTPHtJldW!QiKCA9&JT}~Hm-wji<{=~2G%R}DRU4wpX z)auG5nUI&Sylsr%I|ZSNSL%|CX^Ym)H3A>`^a_m{XK*%TPF{oG97p00CcB-0w5 zlono^KrE*LeuHJe*?Jw{qdckhngaO@K`zXvoA!4f+n@?llPE3FNbnf$#?!{>b=U>p z-VOn7cyZi(s+Ys5slukwShN5y$N&Dg1&FTxQ1>sY3xes-$d%G-amS8s*MqJs!Gm}z zBZ@qmGsKy#j?{wCl^x(!)c;oVs^hh?<0O z5@nmUaE5i6Jck9f-+D^P*t1X7MRv5p&Nq;n8qKan%JWph=+kZ+#z?*BSlgU#@^%zg z>Km2g{mX`mH=PLf4CVirHo1VkeJ-ORa&9@Erg$7T@R09K1AZ-<293|pzXXDgwfuH1 z5~+Ns;@sZ`vE8#`|1etSnQvj8!cGA3FgwoN-y(j_i9+R2c57h864jl<;?$>?m8a%3 zD5Vp&YlC`CiJ)`ur})*ZKa+JmFe_Qu4y0uNmQ3;7qPVa1)6V(*l0QWXby>u1Pq%8s zpX|Suc_W>OD2C}nuLsNL6_OkLSM-_+zE-tLxIgc^(0wtKyj92+&Ae;qnY`U`8VNnE z#vR|e6)9B`UvbyI4E>U7G>{(AQW@SqN4`Vvv|8(y(sAd5Dq+mYTyw?1|(JCqN3TD`H7%LHLESYj+-nXRaUgA?JxFP&feHNo6K3G3#L z)|34{26OUxfltWgH&LrmjI={_APi3(FGHlT?r5SXW)&ofBcqJbzx6J@Os&|lI&}7p zBq2Jb9No%{$dy7{A&c%S=-RWIGI}#ETYh`=h|FoURnMa5xLE0*fJ+cw>>Te_-WDH% zcs(kOVYJ9kip7^iN%%G&Bjl*synr#Nf`7B;UIhLtxNO0s{t(Fu-j=02LO_5Niey3e zp2)7qMXBzX-Hp!rW#?3=CflF-EzWmtS`!#KMQ36;>Hf?Nf_ur-W7)6EZHr|vGj~`! zDBpX+lsk(4iU^Z>zul7R!x7@l*T#B@;uZ0``M8eUDP#eCgYMR|&deH1TSIzFIb6=J zdBoY8uZzN!O@>oKNeYLCPD*rNg)ERGYI6*5$^kZm5TL(nqumpimWdiDrspt!5NQs6 z?N@%Wh&ixJHC3m5hxmwj#a!c8Z9q2aw!L$)?@yQm#~liB!FV{K;c<&H{7hq|MmIDj`Rmc@V|K7jlOb7cs<#OIo>ze!pdcD4|`XOr&lY$kWc+Uk%32%vTy6 z`w&RQ7BzV3Qn7ySaa-aUH+H*p!+gJ^r)jab5d#c3TKcnmQJOy&R)Rde)NWocL5;Vd zqBOq=WOilHLSdU!Y>f6*NvYnbIohH_p8d}FH3D>{tLaea$5WYt>hctv&YX*=8#gmB|pV~UeL`YVd`6pVUh?y~3v7q)Wudb} zM_v)qzw#Tuhrs_`MsE$V=I^^wqoB*;P9L5nig7N^gRiw_`Z6&qP^Eo3bd|DMTXksC z`sBZm61`exLj!R${P5GrLIh&KntC1eF9RSu(yMivjDoSGe>;C_Q<^$1K8QDOk9a=x z{499$JxxMcmKufRjBtc(`u>T4_5f+~`e0S0+WDb8+znZ|B=N(kKjZHK5H@4766Qh& z`rWr7W`nV-SV}BO^Ofy+F}Z~ROU=i@ z`U84v)a>_Mq`|rl>wzjwg`c;?q9@+{MHo#~3n(km2<$9)rx>#an&L?N*DMf=LLy8HVdebLD z{7jGg4Eg4^lb<))_Bo``gs7NKMnizBrhV`!YfS| zIKBPpa%=RLZ4HAdyK#ezwWF9Xm3lvr<|NKo=%`dVBTtzqkzLiXTEzlhF8e)4DW9?9 zYylpD0QJ%pa1HHc>uDAn%}gfwiusROE=WoDPHQ&@qBqj=*kypkfjP%Cj7UXrB%#=@ zHap^DQV?+s_tOmS2;V%FwBBBYF^7A*=D1$aq7RhgL#Bq<@Qa_AlIakQO!)p(x?DFB z@m(3V6T8F1MEamf`(-#*R2>B*!9xv5EbneJFsC5lVv=pI_9K!O*R=+?Y2kqT+kSr( zzW?(h!XL5j<IU{K;P?T>$Ay+*l^kIc#4k@Hr5tGhy?YO!1=5GoDb6`F^ow^H0a2C3DzL4=?an zv$Snn*COAA0+wZuf%=A<)K)Rw5E1L#R)`0fl};M6Sx}slk!)zi6_KArbSTy$JMO3D zV(~U3M>f~gWfkG>IB*auxZ!e4vDjQT8>40mJxE3`utDgb!p#%s^B}P(SDxeb$G1OG zIGT1f6|wrv*Qc++%rrJrv}T^KZC>jVZm@W3;V@!hLnd~&JqFV zQu7kj5)K=W;mz>hv@#1bq3;y-4$}tzB%j7Wp6Rh!Udnvdx!W@44BaU?(i0E?_I)?$ zO7eEBUs)B6Ne@5^5MgRo6h5dcTnwS$DuuYdh|2t^1U9OQ=RM$+C%`JzRj!01*!TmIaI4K zk}qumDp|r-u;}oh(!Bts*fnA#E;KsGf!YN^bj>{bT+F9Ap`3B%Xbn3v8Gh{9VSU~U zNsNTKy0)QH=8i_D$Ol%kE5KA85dqKPMnnBXuFlDW#Vj$*+#41%mf4g6{!h1%y+;KZ z6*^>1(_}kFR<^3RsTzoj7mtb1{Rj6usGJzNw~dM?Wv3G3cMa@Z%J}5UX#>0y( z{bf;D)ciJMJn~0%foD4QR@&T{jto{55fbf7NpdQKSZTAS?GDxcsQTX>u7mv_WDik= zF*;G$%*q(PB#-PbAzL~u{`om;bDXTm& zmsRn(!R>Xj-vEXtP8*1h@aR~h$HYE$rV{xc0d5T@|*ig7b zH&G|%^Krb5G2&(vdgTs6E#UN3)W4rIK15HOzLG9@iLpdf2c5b~SFNqI8@38xT#+bn zCR*ra@LJ?LlDA%|D1#CNf0L;gIc008?l;}kLpF=>- zM4<}2_PY$jO)SVOdD$r`m)dkLdD)$dq3JCHBnDcmKke94*$qRNxx@wc>$&p85#r(%~EuAG| zrBAh=tO?*cFu-eWyK|805vB36`BEd5^()Zfqw4+3Pg(oSG}(*gk@kItB+1K)DHN1K z=3soyiWNQUPPaF!pOQ2$&dz!fn*a&q_pr~t8zZ`v4~tCTBP{iA;b4|rqNWRh_wPhc{xCW}Zoo zAgS4YsmV~++PZP|ts(xGkfyBj=1N=bK4B?(MqLaPY0Ms7464H4ep;G?!SQ(1VuFAG zd^D@2v@i`TA^#?Xm+@cW@{5#@BG;gH8qgc1^{REEicQJqtlo-j55p%`42)i9)1s4;PmK;r{A3fv>ozu`u zLq$!>nfn_~CnUHlht>bjBvXMEh17r+d%SASA>0y$lsrdt6Rgt z8$CgjKvEB&qxcIP&gR8hN6mS5!jvpxWxqZydPMOcFBkx)>F+(Y``y@8)|+ipRkY0D zASCylfuLUVcR8I8n3eF)e~1!QX@nC>CM~8f<1Rj{D8$4y22q8H2QuVm_c~sTlwqcH zP9MHYX9NO)&^M3h-Do|%s#`emMyEEqLPTzWA;jFfxi8&xYwAFMw*35Re`uPVtRbyyV#8em5q>VwFn7 zNzFtxi9}20=Nu&AUYtoOJ_K$7Pa9yx8b3b;@TV%pOt zbHjOuLK=)O8M!P!Cv(-Gzjyf|;%j=Ivc7$L4NR82V~@&V?U%wmES@&Z(p#5bOo=risTU~J<}7O;QZy}5a?IV19x zv>@?EJ(k|#C+~E&W}y5we*&yKV8)pwE(e+;C--^MCRZQ9;_*EmW@d%iqUQie)Ao+x zVw3sg1vlO{(mPNX(N-9tD9W$RMliT5RhmbN76ZrSo|2&W_kDfwbaGp=_Ox3WkRxA^ zLBzHTZOh)$l_o@rsAqToHREG|>Gko<>9n|yx46z!xv%T=c4e;hJGZw(xS^KI`_#3U zk!av|8mNP2KI9mir*)T7+;3zJF_vqE@25C5vjh9kFDMt)0c^>j7>&({Mu9< z_B?%Pzlq0_cJx)*tmjAlR=D3>>BIRF@5cOPKEc5EGpQ}h0U22RX}M$6A^Arc5{2-D zA(qVL^tJ|KS`GA8u3Tkq%Vm5ins7R-khElhK|o9_c$`cRnc$~J=($#*8WyyD=B4wI zefKOI6m$Y{lNTnQ|4R~#RN z3-Hi7d1tZ$1Z2EB+*7xY;g3#3`h%Ol;QB}DVX3c&r0RAtJQ^+A7rCZS;>}2h=j%jw zehpGHb~8Qsq{XD?s#l%SR?#R|u{Otz!SkkVK?sXHp@J!7p=)m7sw! zll$AF=9!NZStwK2DffJ=^m!!#?)OSPw$3?pmBlJ6cT$5jOr8T-66i>CTY7&g*QMP} zZBouGB*aTzJ{jbj8r~GM6KFm?vl7(EPQLJawxGGr{G5V%-)w{*@l(Z5SRLyWYHcYu?jCJ}GU4J&ag8 z41+escaS)m#r~D`EQ;ve$E`rpCsJVP9=f%cx6l}gQ&lQ4ZI_@K?J>QmUPlsJf6J6> zc~sBpN#-q^05!_K1T0-22IeV<-d%PYqO0TQ#)BCCt8baJdyL;Qw<-9joMK-sE=MO$3lPR7X`Ig;`WF9i`)@Eqc!S5>*kI44rS9U5^v!6>Up}Zxdj5c z&8%<`b!%?BCcWa|=MM(e{B=m*8_R`?1ru07S?y02#Ey40fN*Gu?1+k%E?>8|V2y3% zAT_V1sh$ADo~IRbBS_h0I#NA5pXKTE5zto{R7GY~fy~=X|IlA&)P492p8jsnBP}z+ zv^TRil@+*Nnx&m6km@-*5V~fqh^DCgf#P5XbF`jf?d4UM=10l|2}5gzpq2K~$Gc2X z5tCgvCBIU|Le6sI1`D}A1?oQ(zKGvDyjh1mAdVZ-RYY#GDNlJ8HLV&ZMP=k{daGx} zbUoYP1-{EcTBX-3Uu07Pv%CXraEcY;ED(q7&^^ZFnFs0yimC7+#lRI;IzP3GCfN<; z4_#h>9OBl0T7%>K2+9-0P`iBc@A{kIn!ka@Ef)5Dr1tN1@oC(|0BXbD?GFq0@g1$` z2Z5()R5v8xt~Qan1ayKN4tU`67TvUDw3zee0JH|$?Vp!7g*t83s6Xg;+B!i?zeVwA z3%>gJNISSuvmvsQskMD8wRTBb*Cpw-)-8sJWY;6}+-@ye%>dJjW3xD9V z#gV8^Qi|+Q^rM?lA-1&=* zrl>b;2Os2&Q9Qp|gunx|8U}!p4${xXcbG(|F*X!+SxZmJNV?K9t#fX@fcN)!m;#mrUJ62C4N4^F~T1+o}z_b_4&n^;qy~Yms=D@iD>&)JgiF) z{G(;8GXP;syc22Z`4e>oxO3sZKgd3+0xvC2`xScK*DJE#eWDb@47vQbHFP73b3c2s z4(%GerpY5XFFZ~N`6;rmI$Bwt`FA0^3HMTf3kxh7XR+If8`lx}Zk7Ajj**#G3tvRh z&vz+Wgx>>-5A%_#jfd$tm&ZP8TPglUGR8om=wP?tf3x&ABq(2e8T??JCrfKE&@3%2 zPr>#7TmanEM|H`jtBhmpvexeQvlRP&V5*G`UHCRn%6$cDA6`A0>RIk)fE+ySG$?==5r;`I~!@`r-O$^)_N%1Nf~@uD(#o!4S8A zTA8-$VcK=r!kvV`Sb6l(g8zDGHEe%|J2+^JPXyIptMsn?Dn0~?eb=Pljhat~51xqv zbuhmC+gfKCnvMWFt+ z^pC};cXCShE<@0dA>W2|r>~RnT^}_a9dYM!wF|AZgOd#xk9Ft!!^jLyliJoU#&D6T zZ10N=uyfa%q@3Ubv-b?;+Vk1!h3o*|^9=vcoP7u-CfemY z195(vc<-1msj8t6kZ@g;qs|&!0{dGxd1oT_Nz+Yl)9-HsrM$4?wrFnjw)^@`t}{G7iQK4(qNJLl$wS5FEhGet?=Y%YpASx~+-#%?&XNKw z1BH(4IKEL@X(b&C?ADdUCFx_tt;Dz6X8s$(hTk$>3Xx(`y@4Ng7O@ypcj8COPQX^P zsxBL$77h3^2SW!e|A0Y4-P)l(xe9^u&_z#4og75m6!G`d^HI-J?0;!roqhpTfD?b_(La140nu{ zl1$|VHNImbHB$fGtDG_>g1=&Sh(Z>;lP1K05GV^HSR}Y>+2JHjYej8lygu&STXcYn zfDH-qM_mDQ+)#E@JU*_qqqL}VXF4+nGRjbFNrP&tM`O|oU*+MQumsqEt4XS+(>)U< zqNE7sJOa!@bLb-edW*_|4klS=Br--zQ%S$yvG*(x7oxHhD^`@o?1npFfBAY!U-Lb`}&AkyK>WO{xTD0EQ&S#|E z_kS4dmf!MOIxg0-=ttR;v zCDaz>b7!}V!#YZBBgt?y1&r|m{%$z6h(s$EfYVbYnp80$(91t3)ZTjKhOZx5hryIA-Q0R zAN|rYFvY;Ti#hI~x>5_0FMJs_;q^hfd{|+ zJw6kD0KqAVFvP=2;5Ya1F3uqL5XHqay9SHKA46GLE{pH}KIaI-K9$n%7a*STsWymF z3&Pw;hY!97>%9J#S5fpcZ1Pa}dq-s2r2_(n8kjZlJtj^V5pX3Ynl@P;AlFMs4V~Gh zHn0@4Urm30n0($%2zsCg6rI<;kISd4Mgm?2FIY=gkn{$~dy_%Vt>z0`W4ZUQEhusq zyQh-N=A+9bN`l!(FYG{;^h?zCLokVy>Tjsi2FPWSMXAe3&H)r*!7M&%VNzfj9UV%U zvKFh1o0Q33Ndn<2?iQ;wS1i4>i$iY^k{UnFA`A!X`vUU|8)rI?m^yJfjTOE7zSW|O z;#}eOXKslUqzsKb{EOrY%A25mH>8{G6Bfl=_OY(aHN!;5QM+L}?C|0>DU(A#S<8a- zyOGSf;yBc%8ERp!{2MrR0&Ld@NZZVi@?mja6EjKjqLIWTENs}J^P}-*SA!Y4|RJ8dzFCsS|U+6dt zNamhp1nPD~-GE#be+(3HAsh`qz1GlY=H133Zo|_9itPE9JL{31$I-_5C^G%(-%Ml>h$T8 zxH4f%f5GMr0CWZ2&E^3HDxHCkS)-%M9~)i)%i&$0z|+pdC>1mQ{Kfsf!Y}h6U5Qy> zm;rRJdhC%HcjT5UUz*gE8(YYGF?*ZM^zDzYBV}hAK5ikkdT@!+a`V+rUy~fSft1U` zii_UTxaY)!1#ll6d^A@!%QDUEjtgzJuWgZp)pPQoSQ^o<%)aNL^flNzT<(q{+t2;djW8~>PUYc>A_mEQ&5kiPit9Cb zvpt4fRj~5LU)=eh;Niyj>|jQaL55+Oy@gHj2z_2GFsF+-W__IE(NBUlmc0i+_w-S~ zn;^8=F=|JWktDpCBavS+?`HwL2klOZ?%-zOINjj2CPPGAAF;l>1AEEca`TR2AQVVT z>ctN%oCJO?RJ8s4fb&?_)T&Ko?|~fZazQeGQF3m#*0oz z$|yfY^1LcFB>8*nDdG_4)j>%O^*3uWI6s^%qx~Mqe&LEz0CID@(fLJyTwquTiiOKy{CDP?1f1Rf3@t`X^*)Dh8YwA@2x^~Tv6 z)N_tt&+vl zH>ivaWu%P1uF6SazV%TWsoMYFFm1$fJN_xqEnflhUr`+({s1si&-3GH3c??kXzuv& zm>y^PZs%zd87drl)O0*j{dK$iNd=0uwa0$Hbbkcjco!MpaKPG;&P^HEQ1aa~t^-X# zIYvNJ4#UUt&(`9^WmFP#S>Y%h+i9y4y+>uMJLJ7jU)gYGPxz3j_}g;h{>~p{9*~x5 zOOdZt;pVKZcFDGL}T+}1>jHn+bvmQpRhlQHB)orIOwd|UdkWge__yg?}mOy=b z(sA0_-Mzm9O8@{|b5J4DpgR}DSRki{u73s-WyUJoYNi-50fmsG3O(9 z0e)(Z*;!I9uoda9r>-O)7Ak(~){du@t6;a#Ck{A+T8kof%nd21^#55PF2p%hX8~68zx{7O*qm-JrGQ@y>RjKu zpo`xN;4RG+5yD}aPZLcC*8IJ7OfBS=qfExVPvhg`V$X=VkJ|9EQRZYj9PG?SG^nhv zjbmOS!|Y)yP;=X&-qU|GLCn?ZKJi2HT1!#%je%~ue$OAo9XB< zR$=oIq+J|AlZ7*^AbQ$*TnqsvpTnnZ+-q_yMUU=FI(ecrQNEEVHy8Kj6|-8+SHC7% zD^cmBuHT)OFj_zZH#9>5WMEar(DXyYAv$wOjUqChq?P*HlA3c(5;R0j3q$#yf5SrRD_ z`m7)^U3W2ek!8`h)68zVEq-stqZStC$bd$o=9)~cRQX{W=rA+Cvv+EO9@%<;HiOsu zyf}3ihITcA)jN!!dN@tHmp%}YXNUz;zs8`Pwz8b&K1RAMHE&<#S$E8I5Xhe8#(nD( zM|>QqAtXS1QCM-ivrIwlS9JH)tMiC%Rj1!eXUpo)#^oU))_+r`g5(YUXz8BTi+@mG z^1K&0JF^Gbh)Z5wD80LJ&9GPP8_|xRVQ%hMhq8u;dF4Y?R~@I_JOAA?0ILiCyDLoZ z_M_R_qsEUvSzkbx8SDrw!4h^BRs3ZaW&GuZO$)sS_A5=E93`}3y67Dc639oBs!@w0 zT(QI{FhVA*hX2=szW}O}X7|wtwaQUTOfp4v^zszf;twPWSy>L#`R|aOj$d#dE<;m1 zQ~Vvb<$wba@^{Pc8MfFWI=#d^n`|~w4^xKBw752r1 z)Z?z6u%#n{I^EVzCUf7AhbfW+{|aCg4;-H-=Ay%FjJI{;pX_=KR0|w<9LY(t?H%py zEPkl!m(8-aw6p+b_`nDJHom__RW+@`KgRv#J6cUSni3e<5K%CFW8e%X{oh*5b4!pN zfmyroG_X=*3V$1{yRzJlci@@QIkjTmH*S1f3b0rHHxs*HJoY!jU$IHD!r#+4#m5m7^J~V1e&c19Xv0864mx?Za=zAE zBCgqqSMasI^VBR9g{Cwrtpy~8`2}Y(h51q+hfd(-Ged^)S-*`(0Mw3j z9s5frF{UpctIa9tvElmn*<9q;z1`*d@k$FRkPcTl{@hvOS6>p`xrqVO8t}K^-WU&tzm~N2+;VRzX!5LHUEV$nBStgH5@6_l!iqvRo*ef<&o!bJW0S&i4dAempjp7{P>ROH=4@b{o1U z?Jk>qs)JRz14w(Bdv(3CZd%fAW^&5EQm&imHvCW>X#$#Y(K@Q;mZtr;>p@dw+pXR| zKW}p8>kXaD@0W5DY3jh5SuV5=43xH{v_g&hnl0sVq?iP(J_Fv*7|=SYDU{IN8e;~{ z6^$yNc@nHU3<=hZ+~B(dr9&^}+yen2wD0_{idV(?#Wf9l6=6?5#E)Fe;k9VFtVCR> zzFN0`NbT%Q?6}?@GlyI+99?h0gZ%vb2zJ$HW{xdL)d;)PY=|b3dD`=?9vae7$^RXB zHhHA*Ie;|ErE}qNaz*CT>iV7s%}ueLOcU-MtBnq?5B%cO#IA3Puf>7(55Rzi;<>@k zz(h&m*AoDU_8x9pdiDUKI%06kt!~~eHzg+pohSba^404fhCV=-kyoQG2qHoXe9v8B z_mNxkPC-Aub%dfPORbd!tMgLZlKls6%MZ%y)?&}xpQP@64P!hjw~$pbJ@r98pVP3Q z*J3&li$gJ;^oCf?kW3-Puym!f_?%kZA&cu9Gmlne5gvvqoYNssPOfK0^j$I>t@H>tHT$7A?W!I%x_0MRZADo zA?;Z1G1EphXG4KHmd_C!hZ;}5X1m1zUK^>W5ZEc->Cp5@^rfH|&|GwfR4q&`=zNN1 zY+bbB6P|joJ!1%yj{i49qw{GB6$86GpZ}Vi!C*WOwWwKK>)34dU1J9kziA5kT_CRS zK)b}E76yee9&Ye4p|zDh9!xl9KD?D}N%&xvTtuW4zEiMd5n=sdN;i z+Dh?uE5B>Ei*Ew=ix%%+7zj{>P$V$!hM}!2Xd5L!MCAB=(*K;!`PaG4#RrKo{S^~d z#eGO9DH(Od#1?yxa#jjzd{o_E1M=h>mT{QF4tNw^M|(u)_It(`FW|oVk-kP)SIx8F zE1BDb63jHfr(b~yg5YW7F(lc&7ZKEY{3ILtsCa+G%{)m>pOZ_s61rc|boXD2P<*1Q zUv@xy|Ffb(4W(C+>LoTF^=saV5V!gSfnSZhK&)r~=h_Q*PK%kzCePyaQE#Z?@hpWDS$xo(t^OAK zir#v>uY=7Lr)B8e`$pJGkYP*0Jd<*6a(C+c4)vwLIY--j2}DzlA#8t{n@2gQ`S^}F znG^Nt8tI23$k^$dS_KpqjiiiG%y+=ke2q!7!Xt_J`Zk3rmH~J5W7hYX$7)3p$EE_X zSH+Vq``7$cSD+7m8_%4C151>UXyx%93(hbL>?diax@Jy~HmZtPReD*ooZT|c4?fAR z_QJ#X%n5|f;sT)@IvZs4tH9~+Jq9RxB^PsGH#y=0E)xOiB=hYp&{XIe>nCWLzbF1J zF@&!pKAdcO>8WB8BhROEa;UTaIP4IW6cZ&o_Mt}nA%1TIu>ujK;1&FPbVG~SeId=~ z8?_l`2)?RY?P&8=cc-E@pW%j^B^_v0%wr^>MhZISH;c;_5UPU7+^C=k)u$Rw+l>;e#Si zoqAeLxT^$9sq|UXnZj-;a9Sx+%A83XUiEK#?%cJ@4$;O@u}K8r)A=NSgR)cS>C;KZ z14EAXe7~IoJ@1J?#_I?1dI~ncs0eTbH0cQ(H+{Za4BL#aI#ow|_SCAD#9Bj~E@TOJ zd~M9KGv)>-APo%&8j|D#fDp<;{od5piJpc2mLm``;9MrrR9&;MV9)CXe$E<5ydkXm zW<>e}ZF$$8*P@D>gg1z=3PMuVp8Ag3s}v}KZ)?ta(htC=y4%-mgfX z%ol%I<7B1-mZ6#T6!a;LJpjpUgw?<}r)*CDPZc=JlWm#f=nM>om%qyJd@kMehHj>8pdHe80D8kZwWg6eXm)OIksi1tcVw zkPwgt34tXAq?Qt-yE|8;1(xn+Sr+N$eLmlJelt7FF#H2N_jB%Zu5(2$lm+X|)kNrp zrg5l|8hU`_EI0ZK2h%cwHgi1m!Z74~GfN|b0OXublPn?$>h+~&eD2eH>!SBWjg*jF zge1?Sr-UtlueiJS0AAt$fp^7IJ(Q!NK^^e<8zUCA7#utAQK^eqhBTPSYHRlP?GVx0 zE-OIZLLKgA2tCkkmpmVxzTM#petB;85}dsvD`A{wa;pTibp?}qD>p?@ifdh)DD3L^ zA6UbFCChU0(dJ)}xBFcAR5ascsQZw%Ej{Jrjri|eU%7I0E607cw;*SzhBFd+{MoRH zwku=aLFU%LU6vl~gXPqqo0+O>7hlDvEd48>MsP;Q#R}OaDdXE}c;t&OX8*?pAnCfI z;Sx}FHWeAxhsJw&+SrismI)_2D#Ar#6=3xh?qF3KtzX{4%5~OB%7N0n(fp+Cy9;(^ zt}i(<-(2p*{#869H5+tnv#wcs?LDzWyKAS{=sS2BLnX=+8xxvIW8}@_v}>%Q^F97o zv0lbIwO^78dq%jbam5!oW9Nl$!eu_mlIn_ai*qj>yQV1RFv|*WAWL-hsmf-)0gdr% zhWL4;H*Qz)&R}wP&;fhCeC{%EfNY2`&UU1*afF)T@3!i=CBlJg=1Ue z*jy{vXVDMJecPA#?wz7ZuR)=Q`!XqMQTBq{KMhm2rIF3RX=+zs+WUh1D2GRmtW0o} zZQ)f4!PYM^qLld5RoQgGA1O&dQj&J}M6$`eD$)oO9w~)Q$HQg$=-FlRI^)3g{+{Ny z4qND2}ecr1^hTBTV zLcW9o0y)ddUj6q@&d<-wIXe*0YIW|N&nD@@%zZ9CYpA2)IxW=*0po76KS*tKAGXud zxm%-E&7Kcc)Rfu{$f~ z)!UdN@%qi&ew0%eC#lJ{bTF?37WAyyrJV@E3ZrXC{XZ2^VhfhOJO%!ubdhW2>krx9SO1BXVtpj zLs;7P7Q=FAcT%tK>@_a8SNP4FABv2NuNS|* z=}tgX`IiZ3JlF{!Apt}qLImYcJ=%O5y&A!J!_Hd2y=Xl%)g;wGLY6b-+x&5rmGN2@ zUDN%1M*h2ulIq&C%NNPi^uTee=59{wU>p9i_B^x_{Z|9sgtbaj zCioT6+mJBNbGvI7^s>SaTHWkgB~1(j3!jv&p1;>0_}`X-sF--q581eZ;oHH!>P#yt zY{)NA_T1Z71u0NFkrW9r#_jq;|M*^EN6=v9bZEOhhMsmUn-hWI`}Ften^~1sI+=kt z_9owYYhoevi7%}g-5Eu+`XnS$ucI6#VDYMJteK@8Vz45b8v3}B_Tp3HAP5t1E8P!a z>Y$RZQcAYZA{if>@5whhic4Pto-&sFttJ%={v5NJman|)DytCV)Xomw&OHzOaXHSl z!h30`h4|M$^^=3*`OBXb79FIvK5_-CD`5%|nA>>BFvR1sU>;#C^kiQrw$BOut_PR* zR5d0|Y&QnH=yD)sU2x*+s&A1A)zMtTW-DGWZmPgJc_y^)H%##64<8@D7PnM=u4!%_ zdedFy5OxcvFb>!PKRS1NK>CR8JY7x^P)}m^Ovd5OYE$xVP11P+Lus&jK+@S zU_#RAG?cK*3;S}gAbJ61H{soyEa?nY((3^LV93sh^b=CheEN^v1c$w;k|D@Fw7NqW#OB z?|o+=gbuTvt0sKcn&q}CrD4{Z#VOK$;r!;oXr*oWX#UhNInTf?Ldfk4{9UyzTL9~Qjs;611vY)NQc9K`GC z{8vaxwGhNUeET+5Wq<*<_`^ALuzIgHNjZwTs3$KSE<163tAYB`|Qt)<0 zq3{n)pMM+JuB)Bf=ZM)XD3qiy_io68O91W7m;+CV*Gb+N1H`_7X0#*b%r=- zSmiQLLY8BE$goSab9!)zyks1lX?^d_&DbodaMH4!;w5{&2y||~IV6?ub*ZD}Pt9sv z-syZFAA0rE$mj537fn$MKM(?k445lbcok1byeD zBM&Pt{jtm~UgmAK9a4LYh5Dt))QpyAO}GB1M^s6IMH1z^D^S^CeUMAHJzaU((6!GZ z3WhZzV2hs@Go;4%qV7KH)eTGWyp{YF0>VY?&D*e_`@}wvi}D2GlEwr8?-8nT&-E_ud|sh~m=;6GH$x;oa8bzMS*u7S3%1Cty%XXk}O8 zl;_`1=b8#dFZ_|~cEbyi8V9VT!%Fa8(`9m?DV_Z7JgN1at|T;xVZjOxHsz}G!i}o2 z+c}j2bXg?N2L`O%*P8geCJRGnsu3sw2o{sN^jQGcEH*QfXOIyZmu;E|O`M8i!mIf! zbyA7lrM0xm3LZ8cC*!=^4)9`#!y`H> zr)H7PAUOrRu;*XzoOqJ+D4BO3qDcGFN1~7?_`@t+MFa zIXG}c)4ti016gRiK6t3vQc>rgcbFAk_C7JL;wNb^bfi!5)LR>^w7$936LD!Zv(PP+ z22fSfrfn{(CxtM%pXN_h3nuH(ZDZZ>@UK(s*kut%7b&}IWB2{3z&2{V1Nh4suZ{vM zFW!e%%Bb3O_-Hx@?OjRg3~e$Kohe=qnLX&9kaAtVZFw;FT@-$F!Z7ij{gc?iwQ02pwQ*aiFc=SJ%cOkQ!#+IW05q}tpX;O-CS{W;LerUDrG)`<1E+D1-qIy*O@IIvV z!?dSaBmJY9#Mnu!)UYwd997Qt$5FPh7?$En%xot>_pmK3itME8dAEiAef)Y3$7KPs z@Ewap%l=mxgu~OnyN+%&YBSbIOkwJ+Fi)AYrew}koJzj{=S^zr8&#D}sfyvKG5ND< z+(%;EvE?6Es_(8O!!C6^j-0*)cHv#gN=iNtE#bUuDG6t=iaW6A!xIQPD(7Q>Rmzwo^Y zxdWR0JmDJ*UZmg!JNKo!IHHwdWXsb{VV?BKb-o(yK5m&>JU;^#ef?Ir5k*vlypWp2 zO&69M*>O266315LMF!-#B@g{sG+t7?OJ<6xPNc;CcGcwAialy`OTjj zJ8SXUHCjr`vGBJjy@yhAyx)pr43$Re+{IsTCF~eTS3k3Oe3smnkK** zBqhRon30G2GR9$!CyPFoQCQvCBVcG77vwxjJz1%wL**c9EU26GN79z)lyZ`7!g@T2 zICt9Gsm4g^K)@Cn!29B_HUGKutXHfGtBn8EYx__r{-B;OJ;B;FyHeFM?B*cP>w@b< zF?gal^|YjalK*;1{Nyrq`_m9&wkjl<6fruVn4rZud&^!MVkRhJ*PS;RVorVrO7UDoJVi|lqFSZ3m`?T>YZ zDW_Er)ihg5=HtJ8;)(f)-%)SH;KH$-#D)-~uW~WgX|_udzlj3gc7SHc4&H1_QrmDV zs{F?PCIGumooUQxuRdli9TFd{&*hR3$XosB;d13a zdvFV16g^n3`TBQ*^Y~F%8MP{!Nd!1?0|ZYS0a`q?FRlV>tJe7qQ#axr(NEPv9^dx} zA2;qiP+uY9s%Er}<#PUTV($pyh2Cx{mx9@JDtf*%`I3)xYL0KjqoUiwf+UPs=8(d$+n< zI*xZzyC%k|07c4AjN_$pxjKl!#170*t8Fx#3sd^@IUpdQ+B~Z8M7v`uCwWybr@?w# zoJlk1enGxn*LNtR)4Ymgq&tW($*)T0`~e#3?-Fpf@Thpvw8g`TjQZ{OPY+QAEjY^+ z!jxblHDg1Qk&q%DU(p&1ek-0d4r5rtv8`fo@865^l#49rP9y{M!yv}9x)H=r>4_$` zh)F1G*7IF{R6QM8pa&LlWv5TRhK+I@XZj5jg}n3}!Dz=n9$re^#G^g5vRw8`@qoQh zIFvZ3w9c071c@H*RS+n|lIESbExtEv3VC^2?mzfUm7ZmBtmdS8grN5>^ewdzafWfO zN8-Y^r?FbH?*ey{9XqcAlE9>iMCA=z0&;Oq-t)E@=d(=|&Y5;VjEhc2|8HsP9X1Q) zvm0s!z*^xobQ~~5d%h9dv)+liPP8LWTCo4~k;8T{kediS7{jDOt!YL?wrGFCg!_Iz zmDOuGP}?EgD_~oOD8i%Cvqejb&h-4)bhJ9fhPjf_~H_I3UNRq#}VlR|q` z>VIq*+eD(K3)NIvaA##0d6AsiJ4(zw5@y0wT+nO{@c*yh_qOKd^8tS=3sX>M&<$L^ z5NXb@FSuw+Yn%w?8LpMraFYK6NS}dRrbT4L!}BPya~ zetSUkM1moL9_GzkSfA+)Fd;h5jT(7xRBTfNz39{)zrcYBG76p?^)!cHVPGT8i&ip=4!HPG(UgAZg&_x=Ssjzc30 zFXUxyXhkwddpf%-!#J<`V-~}vI+Cz1I(IPEmUA=VpD*=` z#o*6xDfV06IAeB>lw=pP_fgRTxWsa?X)U3EMYSU)=+LMkME~iWpAJnN@Ia5nGh1yJ zl@}(Xz~UdJGv3;Xe@7rDmVZbR240^BmR=w^d3M}vB16s@0B zo`nP(qNMBQozYBnRk9)QBFEe+(9^Szpamtlb`KXf+=*?S5E>#<&+s6PcB6~c&|=Do z1RD|47c_YGjRm?2EAOFsD$klwu$mkLD}K+PwPzlqH68#c~zH zG(#(gyf@F(T#R#l8N?MfqkeD; z2~lw(E(cNfAA(d*w9#uQ|1sr5Ymz>Zxs4Hli_p`xSg{AO?qGA7l}_La9Q}-_M9%?R zIZS5IH~{DaJf1o@ofn9t=g6jf|B7V6b=L6=+_o%pcFqg zOB6c0lD^3Cffyfo$anFONVP+9woa9H6b|nHLrv8Zh1GYwX1xFm>r-{U#E_06)?9(- z3~y)*dORYe1JL0zU8o$=Z}BHh>Gl^DV=t|!clX4!t~)odBH%Xfo6{-W>x~PK6R(S` zS}S~?+)ceWjzhQ+n6Q++FHX1EDEYfTIQ4Go9KJ`f> zGh@Wf^?;DlN?oE<6~%_eLWMC(_5iSv!l*oPda{UH)Z4>ZLhcEP4W~Z@4ih zXx(ZJepT^r)>6kQjQzFQpV`R_o#7(3bC!u`A_NAy=h`5O1WU{-hlH2tM?!OncVH8) z&p4Ttf#y*8%AVK@>sd67S<}o14cVxYM?aoOw+Iqoda>PlXAA-w|3%-vFlPf* z)f1Is0b{dY{I5p^SjEj99osiIeqyplCut(oJl>#LfYG{M7c5_aoV_nb@a*G`e+^8+DHGib9szX12O9dj{ zU9!w$zBEx#D9*d>C+7yjFtA8G$B6iuZ2~YO+$|Ti|JY%EFxl8Eu~HN7z&Y@)^OZ_T zWoP0!ZelAAFqGmL$G*QX-iIdN1#ElZi#ztUc{K)mSwImG3% z%x^Q5LcEYA@z%M_mZo5j1mE<}M10;v1&(2525WR$XEp^G&|S0eH;tyB48Xof!9aKZ zo(6iJkRqpfTY50@Q(|6$->uYGqyfnRkiI4oj1 zPX)U-FTOp{U=rVShj6Yv)=|yF0&dQtfmRxjT58i#3^nWsZ>w@Y`6+{WDe_Ok`WgfU zRY2?Z>0;(8tA5_)E1wNcId+Cq!56r*Be8i+`ZYnaP!>@kvDwb~RHI2b`ApnJgu&UM zad$SIFlW~jx4%qyM{;3iPe=2K?RT=;p4z-atGdIXOJ~;TDnbjNmUnIbI!z0(UwX#Q z)X+|1A^N#JQShrp84dIxhnO9h-a;yb6}L05f@&CSiZ+{2g{iVG!`i1kBFX43v8 z{qAfW4S)#*xPPnwo?QTSvO_K&!)-vyuWmlUmKLC+BH7?re^pC@ywK`_s46Vqk~Vr( z0qV2n>HFeM5u@CaXq;tE;5P?nv*dXO8Ov2R+_e&ulXZcCd;GjZ%K3HEbXHQm9`Dmn zAjXDY@?A0&z2c&=pnyUf$GE@9y$)G1D%L@tgd&{VR;VqvNq5!l^bU{1&o?QQdugkX znN5J1#|Kpf_3+pZ5aR4pa3vkB!;PyE@Sz}yB*(`kIn&E6?XzxWU#8*$y!Bk;( zVgQm)w<)MYNL1Ho-Dt$WSkdCib2^kx%Gx%Qk?vcnuS~X%f917)9Rca}s`s2Ww$a;i zHe*`F{`Jhj)TpWY)w4m`Sk||c)1b)D;{4tCuv&sUXgtBgF<+PE?asGM5>yGsdl1tW zq>|eK##-B67>BJD4!1o#Noq~6=2GE4jV0axLCB0|HfJhQ&B<(Ib{Rqx@aP`pN~+WM zV8`j_+F?=wsE6DA&cBtG{wj5xgYIHPI9pZ}bEg74&^H(aBWKdj-q^q8%`my9&Ts-nAzOZsIiRIqRjk<$*5R827Ui4Imaa3)VFS zRP+>c(42`;$bl%a0r}4sfFt(3^LJCF-0OC3g>Lf=3joUyU~kb^^5jM+>=L#5-|Gti z{BJqS;^4u$J9%e1pxG2#HNeOPSj&EuFv@~dR#sr0wb!lbb{C6$2ZUa0v8R-4DK%^k z4ssO%TVBr(`14`y4A$O&REmR|bK~?e-P>f=uqo0-ql}8WA~9Cyz8x~kY=Cz&jqX4I zQq{<^$Ivi^@A?0fdUlKucb)Bhf6s%SWD!@+JrMIW?8&iScf;~~)0*d61eU@trdVPcaqjaI;o}Ed?YsbgL_vZk zufb>{^Api~tlar8+oAzg_Mgg1pVcplSOnZjS<$J^jm$FTGlmQsE3HpXA%z@Dhgp)3=T|i#%UYKKL~? zTTE(CR{JLNt{5$eBXw+S%;)xk2Y?Dc3jCmpWo%Ks(GD(pNcIL~JAmEVKOnCe*o}Z@ zp$1Io_bx6jIE`BIwEKL>F{>fA04UHbR(W=Kwnw*C4xRe%=}425e>6MVZ*`&3;a|c2 zMybFeJbT`p*1A7O{gFpKK{aRGoCB{MUV;`mWAn(hZI3@ca{ZRJ#~OHesJY&9^*7jNp>Bl59Mm&i8qaehpG*73E z$8M33;Nlp7Q(sb>_41W{s*}o;ICRWHE*!q={Ee(l%5K-XswMtD@hdvutSeRQAYm01 zP>`AGHA!a6m$xwEpcfPuvLr8nJF9atMbSZW)CvJC!L4f6fC>PJ3z%1oDjNo##V+ja znPB;tYN2YzVIpw`bzrSEVX^7pcVP@5;|kDphA;uXP2QrNPL^E#-=$vhl9^z>eijGBDsOEMr{O+x zqIFsz`T!KO@h59(XdeqE?SI7wHv@xNu@3YK@XTvzX;BN6EZc@#MRPhZ^2^E=tv6t$ zGhiwZ0!tg5#J^DlYtwA;IjYpt3pFqKnb>rqQ3-zqilbPUXW?H}FTXx4!Q+Z>!X!cwe25US5B-Be>`Oc))tPclj7gd z?C8ye=nZ}T5H8RdiNiR%cikciDxQl>){Ly{+0Vffi`?&4pIU!R7R;Ea8J3#W?`vu! zdfH-V;P+5WAOtSN5vjDLW!e$X=9{Oakh!AeJv(mu^C{zBx}(4bN4IEN)x4Q7H#I^2 z@Sa)KHi?*3JHa1Lt@(O-vEv`C{d1dF_wn*B&m?}6AfH`E_baVt1wV{y)UynU1FZ!S zaCd}VFfw&@b~1?M0wOb@qR0=kMbE{x3A;CCDzq85sSG?I^!XL`O(9zzUHGFA zMFW^qm+yHBU!@A2O{V<4^bVZA=CLKicq6pa3K4;XVMi`3unR+kKCo;p09A=8_t1=# zOhK{9?we(D?Y;=yU3hCw1Ch#vhRyp< zs$M2%i_Psne;!yOpa%ffa{oE+#SPo3<6p^oqL`~aFJ&$#gw{46@MOBbpm!xo;f%Fr z7YNQ+kD$nuSpV;flolkAnz=Q$7UdnZz`d^6gI_Xnv1gDb$WR=!2dkG;^|$_q)?7Ov172Q16JGsAVZ8mRd6G55P4Md; zU=RaZAwajAi`#5f!d$fF1!Ai3~goN?x9}j9ODrkiqJ|K9!)LO)T+xeOor?JfSllPg_?+Gg> zTlztY>enP9LOGa}r*dkQ)W|%%d1kDQ+FGK7L$Y^E&UGXGx8*=-40gcXEzK4#1F9M`5gS-^Y1mo)-L~=0uYn8Cuo+#9|wf* z@z|9;|CmX{7n3CjrD!i$z-cVY;8xi|9}`T+9Vf6Pp5`q$p#_uCK(}LqN$H$+uP3l& z-V+Ve%)^Cwa(chCpPJdxK7x9dBvpJ2#_GUMrEB&bcF!^O&EI~vUh?b}x#)(9RAaXe zrGSmAc?cG`i`h{D$V>UFR=n)bhouoZqN0?y0o5y~P(Xd6Xal_jtgQnt+g1Vb+@z`P za6E}anqFo<45u1r>BRNVmXT{aGQun@kmwBikbu@QpifWk4IbvLDgKp{hh5oz<9N}6 z7UmaIj`{aaq#TwSnNf^W5hl6$!{v+ffz(8Sr2$)?C)XAlr}9Hua6VGI?bk-nx1NP? zJoPNRpiIzm&=rm%549Kg0g&b*PkgVGvcDd&U24Wfzu^Z0L5 zb)nH#;KwoGZ4FSYb3>4=E@F)+K#B+yLO>XdIKS!sDt}oAR^;k3Qiu{U#PpZs{Tbx^ zOn}%K+7poM?@l)9p}fHV^Iki|@V=$A6f@b6s1&;pvH7nskUG40u$cq1UbgFQzJRQP zJ&7UAdqs+^M7#(yZh=Ay5@OZHU{9vtAdwA-Tha6EPMZJ{cU<8ZoP6kF#`;{E;{xkz zEf+WJqqwcwgHZVtuh2x7D9qR}&Gyp6y9*s&WboJ; zZX#0OnZLE8^(Ab-d7S^!#4he~=;(v)TV5)2%tmCV@-TQB*|&ZfgeM!u=l>y6I#o$z ze%Wh;_1NNl)mG{9FAi1K#FP}t{I=3sfy8bc@~;gS=!#*j4(^k*WOdDPONp zHCLF$|Ddf2`Z0M8FFfQmy0yzPF{B0Tsejqu+xu$I%wv$Od1~;$Ezq0U1<#}{W-5$O zd2(0QaDI)5Ic({QE61NU^V4aq*u_g>6**UbBrwxAPNQ=`x0>7Nyslc?cmT3DAl5>wS0~lp9_~SX! zeSoI-TYk59+dyC!Y~8IJiR4*n_YFJui#zv|Hom6K$+eVVH={FU`cdm&M{;=e*79SB zAS!Q_Kjv|HnI7Q$OzW5xBE%Y=i11twh(wTbNEb)(1pp%P5_8@052ez6S=&?h(EDFE zA6mTAFf{tJ+i<5uqEE^veI&xCN^Q~6e2=l3|> zlC@pb&ZcW?O#Z^_fx8QQJuTeJU3Zt%yV_C9U9*bX_1&{eiqaDe;y{-QAR=Lt3nxK0 zrg4+TF>55+ST;3_mwq5z)7M{Lew`mjW_z?|Eyob-NZ1^!+M63oe9H}MBLk@7W%$RF zA7U9yq3c?V|L!{#pVFJZCoXddzLaBRaTz50f=2tPpIdcTf)ITV*Ag=lWRP2tb`|LL z1f@~0jLV1<%b&~j>MZ72MLZ4Nnzcv+pIH2)_!%+H+FBxg&tu9UY4De0vHr-{!vj_! zZEbDi3l?=F3eo%$wX{n96w_GdtPu-K0HXP(YEek*H>o1 zZczZqk`ZHQilXeUH@Nhm1}|!-R?yC#`!#AI@-H=wiS?_vhHFd$h1av$F)5u(u?^&9 zhbPnB*ZK_n{A9uLJC<(}xr|e_)Gj@naCjn_3=y`QQ2k4+OW^qftV5rNJ8@n+>gq(Ig_N_i#G!04Sf)|r(@+IK^3ZdWo zb*o*Uh%Sy(5;?sU^~7Fs{9ssZlFI(yv3r>OS6cYJwaA!{I!SzqDA=!Y92$Vru&TFt zlXct0UN3s;@AM+Tcp=38ma<^d8l4nwn2!m8eOTTn~oJ z!2ZP#N^mT0b&_3ytNdQ(@tP+*-eht+5ZW_Xu*+VJtE6**Vj5M{Ie86tH3{Y*Y5WKD z6>AGhnlueUeIijmn=))OIx;k&AF2p?zo%rN@OT%;-O0Kh=H|^KtarN48Mxw)<*<~* zp1Ru;0}u_xx@*lacbz}){w)J)wF?HY01}J2#an-C@+5GTe9hxc)mxLX{rNt(*mRm} zZx*`_KK0-reWq_6s)yYETrzULdz6>IrX(NA8=+?);KU_qcdkiB%B6!Xt=(jMFlUmg z&u3C}8Td)fb{_oSqA7I zfsgiCVrlUO5jrb{fG)`y{@NHC{~*_UK*5Rg2-r2mF$P|JsJ)sRSjDgzjkAPBe3LPC z=0g|mqw+kg1Gg7z-4tP=-74LtZxNi*&DFTTa`Dd#$AuBSGDXC?g=r8E^RnP~u=Y_} z%bt!4dT9w=e$R5gp#(}YH;Cn587tZhJtbJl0gtfk!u4iJ;1oShivOFh&-SilRQ(=U zsf_|4NdMx^uPslBBm30$6!i6944-gcO9KDPkrNGdJanK01MN!hVv}o^r&l0o1FgS+ z?-9$JzU$lX4gNIQ<8^|^YS^9E>gEjc3%9k>KHXcfT+d&T#4}=+QRwG*W;^JHd8$V& zIAU~Yhmld`zu!{B{*qWLA?P|?CGRFw&1`~Q)T0@fcY$^80zmNwaaY6e9>}r1Qr~J5=4!S$o4Y9?2$Nacz*s zKY1|oXTnIYdt5iWltUArB2k-8FsI+ECNmH->s7@G))vGHO=_+TPmX?;*fa-R& z9?5uof4RB|pkt*4jO)j<3%-yj~#&br6bScXhnz7e4C;ycV@EN6KL|bO_CCt?$X!3pZKZ&ZMFLgh^u;r3 zPrx#c(Av#D0^JGixssKdWmC`yCePo5-ZN(GOl;3Io*k~c;xbiQ}xtR~OQ-8U{jNJ?N zo&JISSQ5KUy*8!4h{4d&rT)j!wPIXK1yO81{Iw0+!Cxn#2aLq~tB5xR55MTdcTT}$ z`8Da|(`jch6_wQ>wJ8v6QL z3{RX9Kz{*r86>iI!T-BU{tFgpa$U8mo44#*g*p%YzIbtEKwl)6N3T<=(GYrTF~t)%!se?WL`AKht&i5^O(dmSuhz4 z+jj+@#HlZvez#GlF>iR;*Zc`)!8wyr#f*RJ)6BvWrYMW0gsQ$Ieq6*^8iXIMG;q!%=Lai(6?@5j9P_w)yQqeSZ8%$;_TuLkh#Uq6pJeQ zxH&NSknpnH;8ut^stjoD7H#=N7Wkl%J=hE@RklQbaON#G{&;OhZru;;R=BQ;=alOM zs;D{c$1u>@$);LW0_U8FUz5S|d1|L9tZrdzT9ap;DoQa0~YDXj)Iu3DAr!kg{;Yq3rEX(RSlG zdECPe@#=mQFNX31R9|aM=*X=$BDWTT+}%R}YY5|;Cue{s)IVUV0i4_JNPzyKYyIMa zdJ%aMe)wj85JUQldFkUXRtN>^K6=2+gYU&;?xsS;){+ESccJ1Jl!xWG%+m|siJI@V z&WILx*!EJWMxUPUzl{s=w;c)7HRIG(hN8Z3J;nFjJ`MMUUXzSYM6Q;%y4yy}Ca=p= zA1U7{sTn_h$E#Kvhq2AQup+Qbc|2-^kI@%KF%?XH%f2Mc)yPdyutN)WeY2Sv49>8%VrL5WQU(7 z)35^9U1WL?_I~}?eEKKQUXfgI+^P-_b;Va>o|23nlaLO;pwH(l9{n`}$EBifA@%)p zB#Q+Cs_S@QMvfs;$o%tj+iwH33IZo=Qusk?ZMW(1D2lsUfBE&6LP#Wr27yuoAy~5F zZ~ZZX5xtFrm=5M%3-^$eItV$s%@7S&=zQR z6?qOoEYtu$d;sVaMS+Vz)A&xDdgfah8!k-sWvUAjexeazDlo8<`qt2m ziax%5gbI`#NWcp^WIW(tL?p zk8pDFQVQ%fI+!|}QHM!c*9_RPQe8T;5vAvmeKEUg{Xu6LRpOzyy4Xsk?CxC&-M(ZM z91_e_GI2bTLZ0bdZT^g-{_Srmxz?`aQoUP;U{!#FMyl&{r5Kv@Lu&1 z{RM-)Kh9_Okk85?x1|bS>E`k3jU#x6$r!AT3QkF$Trn(=%hvB}jA`D{7xL#-B53c% zPX@v_`DaPGOW5Cr`~)rSi^EOQO^jX!tMd@+5#YAgOl?Eu-c}5H%lm6{+p8NR&pJXS z8ZL}qyPSUvi3=5HSDij7>yEhmuuS>3aKQl-&9g4Y^d^_SHP}Upha~0HeT!5D`G44ZQmY zqtJB#j<2^QV5GIN-1a#+Q+DVXy90N39TQ~t-?M|BR&X61goNCpq}da~>7~cHhq?`1 zXrt&(8G;6kbj~hOw3}008-t3>=Fa2u@Xw6at|slW^4C@)phjgKNodYZ%ZYMO+L?wU z&Ad$ztki2pXH+&LHr@lx3tXiyT~dgL16PIew^@gzI>FKd;IcT?JU!`t=3aLTPI@Sw z>k_2`q=$yf*vVpAaeDypHhbXjLW>-Zfuq?T^!SjBH@+IL)cm0ZhmUlW<__q-EY$K6CsHy0&+pZ>LXX$*$Emaz0n_HFH7!%&> zW8>;fMlreA?@Ice@R@{MK+6m|M_ru8QF&pJa4u$ z>l!1b;o2d;O818m1@lyP;z-P+qa*D>axb-7z<4M-fsFcf3BxZ&$rWy~znwFr-`(jr zQ5f`!bd2h`M!_n_UFKEppFc+eaV*Jpz{;O%i1|r!C8Fq4`hSUrm4pC=1mKMU0%DA1 zpalTFwy&lLA{q<6yMiVr1*I4MR0n& z*Zz8#+d@IC3Jeq?K&i4N>XXX)_Cjp%lr@42F3Ym<>Cnyhk~qe@Uzo1akV*iJ-;?Hs z!HxCcPeBxVrdNz~umJ8Kj5+jXBx_C@SqwSN`kFrkFP;~J8N>Hz;v+-kUNwsT0-dH7 zW7+B}I3Pr1od1d}J7%xeTA^pfSLt(XxopOBhS;Q}NLlN<2gT>}Q>tl?<9Rcuz32UY z9XS`q7FDzH?JRabw$rE~O-sD^Ei^yBK7E7v=z(VP^p78do1<0}?|ysgEtF!K!e-)T z+!`yWKI`RGlNBO}7;O%vm-}@Uv0)IBF?cHo&jRafWR6U}B3u!v$AlpW#`Gi^wdQbn-OE^J^O)p=+)|G`W`B_Q%G-|Nhiw4Q7(#9bo6G z{qr0V-!1CgXbfBk)Sxydb@j5lg(Zo3I~!kmW2fQc`*ucb91EWJ^?TN{O%4BdfdkXk z)jt?xJiiP{%%_7tU*Z9epXfK1i$6R7F$*-73cHAHJD4PzdWL89AOqDfDq;Q}bwFh~ zJ{cZlPzA(lFiXPKE5`A?3e*I=Mh@!!292y9c@b3xp3rvY%YWGHp}&*nv1LpZgo(U>Megt8#idN^bxbC8c5$b-YO?6*=-D zifmHSChFH9`mAC0t0%G;4D-{@!>@E5bbtH$1Y-o^=pK4Yr#k#;U05 zt03cs<`~)=bUe4YHoDB(UWwrvdOB}@$&cGr)M7SNI4DxHh#qA^UY2fFCdni!ex_zU zr$A41lISPeljBwA4qly8Noc zE~~fxSwuq;RY4sP_W^!W)QeS5&o8s0nsc;Y&ieE`wyWtV=YUwddQiqzGW~1XC2No3 zuu#uKU>DTWar3@mR9)RDrnaG0S9PpqC}||H$+{ndu_N+=y{BG=z?;9kdv)-jtf38c z8;w=RmRJ$iI&->EPdw#N@YJY;e<$-VTiUdHMoIHcOCuATjMO zwfV*}Bx9Fa^Puw&>1&pkgy4OJtuyZg*|SKqtcCsxB=(X<|MBi#Y5X zN1|Q-T;4~siT(6OtgIcjiO$;bN*R)@&$?Tg*loLSRK7s4QQT?P<72N%>;$N+JhXMO zf*aN1fBvak=K%1m)kT3f&N*e{++84F$E6X0VLo<=$O9BRx}m;4U`E~bQlo6JvbcY& zly`$|M|xv#g(TcsLCQzW=EX)7qEk8Gkzp1|%xBh5fZ|8n^CmW?S&Jld$65hn-c%|+ zVS0rT`q>Bo?)Wzr7dC505?X*KyVyAp74>p>-9KWD-YVwzUi;z4YL>;$vx%r)>@FzVH*q_&xjYY-z*tH(=A=mH_qO=($&=kV|+Nq zrBn{-TYvp1Gj^i9mAEL|q=fm`z?A`a%(Tz*|Iu{SaZSF_ej6Q9QX*Y~4g^G`K>?*h zLb|)VV}yXx-QC??qfvx`q;x1lMt5^xfA`)G`;$Ll@AE$AoNt}HDzj24LO43tjDm0o z&_^pRIgstTFvvTAP>eqNZ|ftJ^$K5<8h5xlDIu`%3hjKZ^n0^7kF^5YA4obEB9Y`o z_0{YVh0W|3$Lbd4Xeg2@eYEzbB><35FAj9sH$~_|+?!R-%o@5ANORqCeury^xXG6l z&1naDy~Nw)@HFj$5hk0D(dCLK=cs~Kx-DpCb{s_T6D22{iu2fU^W7%%*U1|17cua@ zB?Gs>#_E~6$kX)Vw92hYF{v|z@>gK+Q@E?3MJwN|hXN}N1)^{&0`{KL&@G5D8$lUz z?TiE}#coDPm;}Qtdk!-b@!GR;8vU<@f7#ge)K{vlqF&XQ=6HYCgsA3d-Tz%OM^z$X zSm-{6{7{80jXzc*HbgQP&HW$3D>(OBAvhu;g8gq!R!6`dPg~0->9!yUgV7me5=lu+ zlrJF~tvLW2?H(MJi0Mg&KeYT8~W=ywBNgOoxjH7tiW?LB*bKJ8@_E$`|RT@yN0!gTPji z7|#3Mr(yM z=;S}Y@#E>%$HCS9r8NfxGy|dT3U@iy3DK`+f+0Q%zE%?SA0@F+efK}xBu*kryLXrR zj|%KB@t@T*N3?IFbb+;oG%n4{x0NPCJ8y?GA1zJ_M7gam8R5wKm$=P%Yvl*!hgevT zOUHrEeQvT?h|I72MjUXI$Bt2nqzoO4dq9hR^7rB>b8=^n^~mT8f7`8)hwFt00XODv zZbNPYwqZx%tylQtdF})Zv|}4mj+z2%Kf$l5c@CULTx{3lnrL=9LC4f!a8yL=BjOGQ zW06S9cao18L&5WnV1<3B5xD{D&v)g0dTDuI2!Q$8Cx+pK()e6mbE7BGQJzmBxV&6B z`HyMhKOTWSVX;RsT{pyf)&s;UrF~2Gn@0r`oIkc?-_TkzFgwW8 zORjs;zXjq%LujxZ-YP}HcGyt-p!-MuiyJnyQ$jd z3Hm)BH&x73lI~j`5$aP~>okp6nGKlEgw?WI47-gOszBiJskcveJiqWgdtscvgGtRV z%rQGh0`#&BAqjCP{j}ioZ-s8`UyT>`4BK?Gw=+zM^v+EpOHtRRO70j_=<~AT+szTS z26}U)<+xHRhSbCC4j4Ui-9KA>{cB)}CQ-xF9TMLNlgqrPEC#$cHI*oCRv^}XqF0@V z4Wh4Pe`-35qpU{fEZ&Z4)$jw~D-J<`6JkG)DOB(B?R=00=v9 zB{Q&-#OE2@ikeMdHOWK{r+OlzMfc=kNDy3rAL}=FF0Ke?I%dQjtsAw9`4jIHh8U*u zyxu<(#$UpLtM~v*jZ(QCKg?M&0Xe_4do(5$-Cn*{4`FZ_<_elHk%SpcZ!;d+Q#y)4 z>{N_fTi-Qk8tL)d;>M(sZEwceh7%u-Z??Scx-|i4=%ed1l-09h00CP%X4}e1$mgtf z>r;zJ@Gptb_o3z=JFS^}&fieoVck_xZVjPn6kL#MfSAa!S<=|~oZU=&xD!{x@0Rif zFkqzchOYLzR2H;Kb^YFAZ7jE=8YALz3T-^H+Nmh*-kKn%rqJhxB`m6o=@1RNQMGZK z87c$^$?LdWw>S;Q3g9(ZIe&JRR-dnv{{kZ!O4M{w`0VrYxB@skG0t@kZOjHw%%dyLQuF4cN?z9SKF5 zylHS${PvrKMTXjirIM}h?rGDi?t2W0^#P;GW( zIg}8~{YrS1_LVx!2!7)iyynt4xv8AkTI14rA<#ZZ5|$4aJ=u0za()?2IC*^(7;+!v zeWT4h#1HsDDUSg5iy&?3o`bDL{1=2@uW+Yt5+V!$mu@qh>00E0!4RhQEPz9feZuF;o5t1+mow3VI0v>7h==^UV^ROHHh( zGbCNF<@Yg7FmBa+`K#H#$H&g~f(OCnsGZ3@zVL^lC_Vh|2&Xzj(^y5S=(VhNXL$1LGU3fQ%5)+x-KD_z6spGI?OD|B$9Y6H7`t}1C&2X#K;v*%nfpIiJ|krB7HI;WcU=) zmnYHVFlj+xr_ZSNdjBg)Sox5hy3w9XqgUXpkn25oS8STp^KuVEG2!@5@w3aOeM>(e z8Ux^S+kcGJsOeP;-lq&U(FXw zuNTgz+s=LQu$%mJLmoR;%oy~(3H+>$r`3$HK8tI6rhuvl(pPXzsh2Jn>cpT=_N)cz z$Hc*uFI@3T8-;@yyTrt%XZmbV`F;a+rr=B(ykt zC23p&)ypy`6ON7Pq@i0E-EG~xkjSCKij=U~th+)TULLU^@6JQ5N$AbQxudf9KQg-Ygl?MYE3^zAEfQgO(7+V2e1mLSdq9KwTDWg`EJimkQMg+r%9Qmn> zo4HcH0}uP1Hx%a@rN@RiZVNGy^l(d~Xaor2$t&5M)j{5D3rla%M+S~#zTJ%)BJR~ zTK(Au%{iqv<#jqkE)CXh1AYha*doZz-2$^bEbH-mEwFo;_^XP1VE2UjAOeGBa^D<@ zUG3POF5vIKED5+S@v6@J6Cq6?+`Qrlwv&p{f!kBeT4$*nmL!91&MdTMX_E0Qf<^|7 zxmkW_Ldl=uEbewyjkb1|TizkGIH25dKlOHeW}d#qa4ROC7e)Z%#&vfN2tTk0qrh55 zLqs(PJ!XLx!<_Ga88Qt(%YEpYVh49JtbX^kKN%}7)MvAFPXC_!qi^CyYc?w+OY5x;NV5Nh7qJ&(4+@-wii(1;`%2!(u7V-YYB1x47WdCY9C+hI1><8lV&& z_i=Al+6RBga>09xs#Y|tqy+(F>vg4>mESba7y|u@oe|y~HY{V!hHXK|#%}aDV4=Qo zb^LRlV4OsO=$?|5(`gQ5MY5&e8y=}o>~@cof2_grv?2JQlz3E4)Cb!A$#=$eCW1owFbJzpJwMN z2)Zt|O<=*n0rX_Lk%UiA%J%4{ZdNnqn_eTO?=_|#E6r^nxkdoljc$D8RlxV3RW;t- z_7O$oc0#GD0pxINd_js$*I<3l6oB$m1+vuD+SbNTe82NM==C82{p~Dp*K%wcL==_t z>E9!Y>}`t!k_+tN-gGvfg+6_tRprY49f*<5S1FDfmyvnf9P}YMPs0nN2$ve?{@42; zh4zTYrH4v-!&)Vz;Zwqx3l!|{LXF=pv>h~xo!yX*h+;YJayMttkDos~_@-&U$8^>_ zp-hDW$C*9ZX$KZA2n$prg1uKXdA_qQO)UN8~}U@_@mLU|Kf-v2+w{Siu{u$Sb}Qqd_Xj3rJL5ttKGt{k>fn0 z$oOf>-@eu&5+xBv=HpBvJWbyzAKI7h`b;L;4LE=ud0* z72pvQgSGb8WBa9YBZv>-D`1ZiN3lrDyKpFfr`7x4pmO2k`Osedke$|A ztPcQVjHgiQhE9UHA#FZ~A2YPqXaoJiR!e4bjOPf2n}69V>OKg>jOVE~-2RMjyhSVF z-jl^HTtQhx6*S=)t;ii%Jxr&|pm^vghwi8B($*P5IIM`lwhEv6sL$rU{09ln-;@SxU*t07dWhIpDb(}r%-Jzmk0Dg1{s=8AqJ4?qYiK-l=N}NimN2*A1)~LNzlnaV z{X{xDo~^yLHPsn3Kv`muEC7b8#HQbz`m@sjj62Y+*aP}4M}B(5NsX<|>kC7MVNyaw zsprKSuK{B|6&938R1KVC|<=$Pxnx+bdd=?87My zn1T`T+p4kmB#!=EVHULIW@ zaQ~i5zV9Ba_PV_B^6`oIw_Nt00|s{TB^Usfk;$fgVqb&a;$5~;PN$j@*gxgT#Z&Xi ztWgT2g4`QX7GqRsH)1UNO&;JHjtf_D;gA^B>`KeiR2M(sYw0b*| zi-7(!OQ^UI8&z#TXg$~{uKtYryu$pVC0D+;D=2`30M}GYv{z1DUDZJI!VQ%cTYs&S zn?xmngmvs8NMW0)>vb-B_Q)YHTt^g{htE(%I9<Ys9hr3@#YT zW|m$3%M-?`9CZfz#s*vSDZ_hUp_IH6+FmbHN1PY;XdOh{Om`ufPaPDd=!f{dPK#zU z{^^!RWctJ~>d|Lr%SWVm^*)hVDt`W|BV>T%KCU(IdW85~6y%SjCXc`XWP?CzuxS+I z;bf}j3*7gOipWY&jZ?w3;7=iTEjxs8)3cR>i*KGDEZESt{8gI=uEMtuiS#P@?0$!g5B5b zciXL#^_6aVh=xC<>IOH6*_oiXRTf{F>mGK_dz;7R{yMmr;tQaDD%-e2DII4hNQiO| z_z#E$U)KKF{PX9Jng#7td&vmLOp*TusSMw!!-w6=9JAyaDgKvbb2BL^p02Be$3kRu znMgYQ1}?)H8ppb}VYiO{hNX4JlS4|P_i&?-2()Z6f>HYrJSK0DUh?`HHD5nW6jFrt z{2;F1gw46rgZKu7@Abt`E3d{Hcta2RAbL&jbT}OyiL0>kN1c|G*1)GZew`K*>G6qm z(sSMbU*dVb`ztZ*TeTDN$~D>G9qr&P8Xfe$@m{;O2xm8ueqxZtF@0B#;`?)VCwZ78 z(RV5S1ET~@c28qU@hM(aE$tka_5J|MVJAHV$7=@Pz4`! zD>*sp-Mdq17V25INS+{ycIj);+)gpV!AyJ=9sL_rT4yBxYnf?>1-UIeq#lYIJ z`8m%tQmGnsVukN@qt)up-(uONk~t>dVAA%ukztqzol3n z9H2co6I8uvF#Iy+g^W33vkMW&TP9cns~s2Vd=}Uc3bj&%YyoSNuP3Q{uY%j9$1U&QtO6@$*?)`Ya5u{hcit1!B5XB(KzsaDj{TFhy2-zA8~3c5G-(6e z)cK3F6xyE~gRmc9ukb_QQ4)VBxeJe|8&+T4Xm>a?raaQyI{ZMPA_zAV&oBen-F6!% zEl)U_9>{$VlCfeWvOCcp&LhT(vpr1gM^|@2TlJEtf+}o~#KSDmE!!x;0-KE%B-Zsf z`YpCU&u+k@_M0>5@1BJ{!+=?)zvmv+BYF(UGD|l2NE;Y{@!6UIqL}dQ?*^h?ZT9E+ zG$U7&vhs_kfmnLY*yWZC6{vsm)qkOSz$*65df8i({7+)e;b&Qaw@J%|*n^!7%HKVjN&f|uJU?|QHef&Hnu zL&K%8HKWnU?_h!;H}tPWDqf&*;AK8PoPSL`_%m;u=IeGW1qKl#CIz>5EDL5ifeP712d{WVgJWp5Zfh0jK$2%CIZl6-Nc0T0Z>6aLTai*c6@qyO z+Ee(OycVrwzjF3_4eY@r_*Ii3An9h_=Em4<{Hmv?w+<|nk(lEBH*NwZHNc4K7!VKx zFr2(=VI{lh9nJK(?C$_9&HQ;zXLe z&#y^GTG0F3T-2ZW&Xy96%ca)@-@z@6JC*^VpFBD&*`eP&QF<+PQklc9W~brcCc%!{ zqhtBElcSfH*T>|UMW9+NHc$N%3s!upQ9OqIIKCkY^%(OL1++V-(9Z7e`_e#U$yf8n z7y|J~SVH8*QEFEXx!VD?Ff4+o)>=n+ae33brT3Mjt|@^dEiG|dOsTUWH^e@YKa$u_ zjGjO2LJIysK>PV zzJu<|6B4N5jWLYQV$I%E7~U)qNaJSHf~OYIO1QP8-MHx|8nLu$y*Wg)gxm-wQ!{)ezqP5?v& zH5i-z7)seDp10>JFKY0$S{H87getmAT%`&(NiFy9J{Yoitd-I^g^Y6kR1jq(BvyCD zUNI7vBo8DZ__PVDs2)5sig5@72b96Yrk@<|rdHPA5!YdrAEnmTc(OT3hK#}_gg~^d zPhr6k;Z6h14vrMBY`@|Ha;*l%{vamlm zNS+o9IR;V*ZWnv*p8nIy|FWg6D)_JW{$T&mj{V129sCK`RmC6o@FCSK{Gw1w{a`aQ zW5cATy83WursA<24;U?Q8W4m)XB#!1d#dBHZrWTeuRErGS9zlwH0LC2e)cSOi!jRk z%Dft)J@1(XDJQM1%N+?K2yzBZ1&RHUtt<@DzQf*a^K8iN3sMW>UUtZ24&LW8l#p;$ zkv=Sfe+1`a)K$8ukg5vp4wSkTvZdCe2YIuw5%<=??QmrHxJ9#{%+Ea1S#ETztk-9L zgMA5Qn-X&y+tREHiGO4>!CfG@=`kxr?^X@b(;KMhZZ!C4_7|CG(I@cpy~_tp2))_a zoPXm$P_n~8$!4^l`4`rBI`&wH#gw0)?VcT!zzq&6)SeFGHSMyq;f z*qh;(cl^Xumf-ZO&}^`5_s zUH$#(^3BNLO@~l4BEZ2D3X9-g6O?S!izv2<9S;94pi3Z<{RoYdkVF4EJO%7Y{Jxcv zOE4@LtJy9D!Sg%q!bK=XTou`fQfhgD}XOR@+)@3g|yk$oap5BUtz->EQRJ$=1`gh zq<^j#q3Gisg*?f`AtV|di6EcCtGGz2?*5C}&7ePZdS#b3Ga33h$gAlv!1njM9iS?- zt61ZcfT&N&<-afVW;R6ow_SQV<0wK8_o#%#xMJs_B4A zeYpGU6(DOpFIX7_MzomkOoxa;7u?GSQW>qW%3EsmKz*NTYP}ze-t6JIGf9S-+^c*; zclY`aAn+56 z^!4=ajK4Jfuj%6Jw!<%kfxGw?H7*5=a@`n2Ykd331b)W9X12O^Wfc60VFQsgT>m__ z178FNNbdCW@QK^#0x7xZ`!#1<>E17y(Hw6p)6=6ML*4yrXnYKYSTR*K6V=rd&}7a2 z^|e>7TG6p)l$jq0VJ}L<3>tIvumFN&{ooMjxb9C&#MY0GNixRFuYsix{s4ua!`Oxq z+W7Hr-w~49mpx()NuqcAeBu#<{926t>dl?MGwPGgy?aL%`G#()3->q%aGe6NW``?E zE7*E-3gq>|h>}aKsES!fytQDnUqgo_FhPplMrg%Nwf#xS(GFjOKkjs)Xh|hpR&m~x z)z#n=eT9Zv)4ukcJqwNPo$bvT!aJgtR+hI`{`>&wdgk07AI>ps)Hm9Q88-1Y6BZE>Iyec4Wy{cnq18&@rS#5~M)jvz^O3}|@ z#Ls5LnBK`LZ)k6RvE977=&VKf)H`ppFLXll?yuiR<_L_{ot2tD+phuuzM(A?5yT3T z|14^0P*(a36QO?mRtD$%3yp>B(xGtl!JWUDm!z3iXn8r%oqhRd{P~v%Q*aH?zd%*S z$;&fpSzIRsVxJ1U_DU$T89@WU4-y6epHV7@5OYU|-+|shDxBbeo5oc~4O=rL+`%R6 z2bLs~+f?9u8D>O1i8g|!{97P%bP`^GgO-jx-7W4&9DLwN3AqL>bwF+gNjgw3mXgWx zN4em67qnfQp@Ff9euO=n4N(sj#MKhpQRVM*exVsA8^|g`AC$E4#H2*|@`^=sbod{1 z-_c9S(dpIBysPdO4?HTAnL{L5gg-n5`1N-<9wWs1s_WEIju*O$$2 zMWB}!91EQf0u-K2L^>7RQa21k{KUl8S)Uwm6k6xpXaJ!lv|gCpB$Maiap7aok^bz$ z_ip2DED7x0%a;8=(`C)-!wUj+$u{&^bmB2D1PU~)&R=yglDfv9)-zzZFU`05cZKPf zcu#l+uz>mfOP_M2cz@~>$6>B|EWvk5b=RwY;a#CRlX0GwZDDftdJaZH=Ig$_PiKJmlS8-qs1)=7JlxOyy88MXS0_k7shi+|=yd$&jp}ZU z)twob1TN@=t&#*v&l4%k0M|1*p=l#{L!LzUGUIMb>3ZFWGxQyt5npqNwkbl>4Ce3w ze>r@OCLP*e{M2cisUBaGKX)54L_L2QzDHT-@`ONiIM%|lfn<-8*f`p~ZJ=6zqZ#U$ zf*dK3AdfkED2RCG=KhTMuECchAC>aY=B5;I{TMKgl)U~kJnIEqyQ<88&mHvQ9%yCS zw)}T}zn74Jad}A#xrym|MK_N-s)g!SPJFXRnFD6Wbiu_=%+1H7K}yrO3^sjGAj|lFa9+jdu!ZbmnHRomA;*evJxDujBxIW4nsImC*DgtlC%HSbOqTr>j477$K=xjT_J#wCR$ z)cVhy;Fj0DbXf9;;XB#ne)OOP);$M(r5cLngcT)t+`JDkm*{u)M8MSD&$Qrr)Rw(w%P%=Oi-AIm zwP=BUk2@ia&a2=8>9p&5z2Z+9%5KHTF`6!}San?~@x3W)R+_d!V~#XX{7@pc8i$Dt zR>Cv(N&PjLx`TuE1fr(?`HwRWa!HbxJyzI4YU@HNj+6b3=d5a=+4H{{GYmDz3hf6i ztTDG-w|WgPlz=0_noU=d;YRCEWwJAZNgEC};1}x7{F(7i8@%TncZpB6l`!lw&iME* zm=yF}bW7*(MmP3J@Xyv#pMTvLa1)ctpO>oi+jsRBKrS1K@a?*t5*c4cdt5$2|Kd8iOFUI{i+)8s8#t6~kAG)w$FnscU z+DVcaOZO3nK0ZhFBJC>U2BHG@(=UmU;?deO7XQx0^;&0sQkG-JVMoMmVI)($_DDi-AkR_VX&4;?o+JOP3#=HfP}tNO3}_bF@**+ z_$QY0Hy%B!VmyrF%y6h!i!aILr`WRL%58d$THDRfI17u-gMgu^@)!U~6U-8H_Ks?- z(s3vcg*f3}1j}t+*%(j|Yela1Bla?3tc7z@u(+YaTbN#A4w@HwE^ecigI?`on8Dk? z<`___528WOnr!B`F|PkS?SY6!#Y|!&!beQ2;e}~i-I}>eAa~~( z?D3@M-)n;{p8p2m0f>2-1dhF+~#pgD5R1Qi*JlmWGbTHOUeO&meS)`>phITF@ z+pj7Y6@R`P6V!gEFdXb+&-iY)wZ%l@3qDJ>8bTwWvcs=NZ1(!rI#nqf`AjD~o-#j- z@P^kdV0OyeqUbt7P~gMRf-k0fblpJV&Ics0ffR7;E6<&MYgHoFZMbbNvZ4Y6*|!uj z<$w}dOudgX`srpA({**fb=`muD4ZZzXx~MwZSVt@{T$XC#sM$^nDc$*PDh-^`q+ZSg9@%CD6VLe+fRW@79T z&b}(+34Fd_emhVvGi^1F&+@($jpZ|GZ9O#rj-l~!vkZSd8?Qsa##LoKRXlbb&ZdoS zrl(+TGI0*oCIL$u8-wVNIfh)6&$RmI?WJIs+sSJ}VR3Vcb)dE~ zk#E8V=jj<4J;PE=2F&LA_hw5oMDz)1vIoPJK?P!v6En~bKAg+=RGf}F-3U(eK2j=_ z_(?kDS~{2$(t$s3PJ3bYMWG9>r=HL8oYX4{hM(oJEi%zz0`2ih)rblC{NrG%!)xX4 z^(YVxdpIn1PyBD9eYn3%sUC;+sH8z3a5-DCo>L6W9)FV(ZINNJMEW%C+6Z?Kfl+i6 zb+a@{`ShAqzbjj^OYG|KP7}{4Ju{OQvkT0QeDFwclwBi4I99b+_U=Bq$;{lb3t%0p z+T~k*6vb`uDA^B)hAWRg$AOSQWEo?*0ES6ih14<~^Pl|?==g!6!Q|m&CaT)5f-2h4 zd;9ckoCvKw@kAJvmQOD;s^U1(>Jv}V{+hK5^f5PXK>WE-$INTDxAc}G;E(XRdWmXCGY$xQR7v=ZRbCqw?OQgZgX4&K5a-YTF5A5 ztctsphkPNcc+>Pd;fLX|@J^K5TrH^MaoGK@?g`OGL=+8Lvb;PoHT$H+mv)x8!HFl) zH%jad|JhJelCkMWT?UA_PCrOY8#lc>Brw5tjQe&7+hzd3{^3?pQ2`}Icz#SY*Wig!qFDYHz z66eIf8JO-h@Va*es4^;#P_C;*M8eZV37gMI%Qm2k zli$Go`O(j~i~2P6p4ic*Z-g{_#wQc4quF5BjkM|hq(OVPZIGo`OoY>wy8Hv7ND!|_ zNO$>t6>?ZrEC@MNt6u=i3`i#Z>15o64{b9&u&H^r<}ohfoHaKPD;ponTwhokPg6F3 zUn1`Db>b?OQ`O|%H^!=zQ0@N}0z4uKzAa{AJRunULlSmI<%T`NL?pt+NZ$%G195i1 zP|H-G#%MVhwUH`OBIHJJv$;(#u<$5M4hf^2KnHPd5WzASHrAq(uSC&#DUZ4jCi!FR zw2TbYfB*ry_dqsLv%cY{qNP&zSRXFd;`4dcR>R@oNQee z1kb2a(h_8iF5s5<;r`&kzaC4NqGxueO5+o!v|G&gL<~CV;pFngithsS`EH6F@@Kws zlA0i+9@UB7&#m^$L$_!<7`+(&kxtHD79;|k`>#>moNHD7yFUKSD_HEynjqs|aopU+ z?vFI{Csl>gq&nuZ7w9_hzu9N(6BYKzW(9KU5^OYxs@tlV#S`_|BJZg~jGzDvYwZAt zbi0(#K}m?cu)PGinysxH?mT;IW8Ln;8}d#qxn@6dUi?1&{*$XE)Mbk#EEKujw4+bB zrqYcqDh4XHJx1=NGxG0pHz`-F%qvk7mR~4=2ax-AH=%|-sCM=%CY(5;zD5bGmW1EY zMDE$j2Mj`lJWC-5s!q4bOIPzQ3SP1l%nkxAR&3u?(Fgt`{E;MB@WJqH7%aSwF1B~Q zT_3&-#A;0BMH3f9Y;zk9z|_MvceST8gh-cRKfQEKY2CJzy<&s`6QBre*%RtR0a?LX zn*~n_3=o75%cF&d&szvIdxd(OK@L(V!nMBidPVLtpn9-^P7aB~Iq3)R9ru|{0tUF{ zjY98w6xI*6yu02fn_X^YIQ)ypK$G6g0*He$=Z$m3X90?wo&0gBEdN=lJP4JIjM>%f zMj4(;Q+1hC^xX4URT&OzFFF=hD7|T0Gjs=r=RU+#kUOXFR zXU5p;qED}M=V;l10P7@6(O7>Jl^ZCv_snYkQll^>e>Zt?_br+Rf6CL^R=aN~9-}$R zwgltbbVDfP5p7vpfA_O5hAodGkG8?i0Kxzy3J~@EW>HfoD=&YiH#cQZ0f5RfkLBcl zU7QOv<{F?Z4w9&DG?2D6-gzK?24B(l`Tsl3{Ct<F*S{T8cc-ulSur{kNar_ph4%_HavC4N^z;pX@W7>7 zu`fZDCyucp@B;^}wF<=M6oOz5y($ zf;_-WK0g5Ru9A^P**|?Li@k%CbY@VcLG(ogZsSZ7AI1V15sKVQn^uZqPh;2PTw7#( zusogyDxue!)+63RZ$k4VMedUxC_$)I`^Jsfp#@X5_DaqCcVe{aY$vH#YEXt{qgNczQ_%7Sg0vt};=LzuI{|x0oV7IH1H;!dM_EW4ffoXsHMRL@c z_kv=gpAunhiRJ1H_|sQnc@Ne-qTK9qR3?m=a)vpB~gY0U`_nuqGja)(BC3I2w#okauOhnQbD4 z%vXaxf>;#4b?n8Gp6Su5YJ?YdV(>K9EJf6SH0edvT9R}X0#$7i z{D*C(oy!+P%cKlAQoTh-4KaO&cwBn37{xBFFLtJ{we(7M9L}t2nr8Jx4yfmau;6yW ztviA&=jkOdlXAW0o;?HW2qAqB&SuS;7RjXc-#HEVFIwgQqVZ!WQAJeGu@jZ(Tv#`G zOWxMn%f2tuuYA#U&Tz9TnzF#R*W}1~b2_sxrqCUQixHJ9 zXsKw1UHY5*`vd?Oid!c$hUcDXCAR24-OTM zrbNq+j`sF+Y~uLml^H|#e|=kZIRWQ|jqk;>$7M>u6@~B3Udwhn!NZBzL+}F-_AwA} zHy7|vj=>xgw8JE|QM9!(P0bt41o#ItT>usou&Ds?W6%6v2aDWI2ok-ub?iU4}O|Nj@PbkXy?e`*q>LnH#FsUR1w|1&oS{C@&)&& z!l3Wf7#Q&g!bO76+KJ~e4G#ioY3=CNLa}qu0Dlld&K8AXkD>~z1l3bNq2{5e8+Bf~ zf%JMwUKWtiUF-NZ-YVH8o&y5~#@VFE?3C+1w8t8U0r0^yjPm?*x{BRjZl+ZKg!XWM z3mnGN!XU@hR~26klCnvfLXgK6=~unjABH-0CcDj^U>~N*D?W~Ns^E)yR`MtEM*Z=C zz(sFS4!PfK68%tn{EG=WmY0otvRa&Ea1k@B#&+4jPM102!};T!uP;SCR!f+r#C>;t zQRg-7)0G>@p@Lbh!1cE4Of+{TEpZO3-ns#0z`7J`_N&oNZ|BLBWQeu}je&OnL@G3K z;`?{>kR6o*lh;y$mOfSbiCjSBT)%xw@P&W9v4>t5;0yq^%whs>oU=*E#V8<<{e}54 z!B=}?4EezWcXAoL+q&tabKwFvkdlG9gdm1NPG55yE|eV+A-PK!MorpzfI?4SUs0bC zRGb=cZl;x-ps%_)AP@$i{{L{Mhr6DKu%6pLFaITP?d?4vR#N=hoHFND^(W@%dhrEx zO}zv(GUo-nMhtRNgpt1)M33qcZcTNX*;F=Ssdt4Y&U`=)M;jT|vGJMVaskL6AWPRz zKr(Xs#p3&Ws#%sq?zcCS)r;quv5r|;iX{LXU#j+e#V-&6Z}Wd%l=x8=42|uom=PlZ z5$gxvZ`y3Y&;_WS`GE+p-*FOS0-$N58GU(6 zm6tUXUVtr=ZrHtO(kw+jXztA}6NvCMn;Bl)sLHIi4yC zvwQ|vr)%c8Qa=urLpdO+Yp@(igyT;f>oh^IoCdx@#>JW=mUnCO=PY1>v2n{u5ZuNO z$S`&Sl&F84z2f&(a9(NSG0SXJS$fju=pd<+M~jpWhAoniS}>}ghGAPNS^d}D+hL6( zxZ=Yr(LGfkNTr^UzdyaP2vC+=vE`eziI!#`>E&prf!8z zrJN|eB#KkkXtX82~YQ222`dW-33+}cE8M=AVtCcRT?>Er))eb=Y0mQnh)XV|o zr~htw(lJ;Dh}H{DdMbQ2S40X9=-^gkm|$BdRNci~O)e`wMdw-a97no<;Kp@_TYdi~ zjec;%U|&jt*%ROk!3+iiMV^Zi{~twzMM#@F_4o3|@{X6H?KPc2l?IS7n2JCG6mt=R zMQN|-dWS7MPk{fW2A#If+@Bm|5;k(YCmh3G>P} zSyr7U30g}%$t1_>)My%K;DM)SQna1bDx5OSMUpY3JQ-i+kM>(r?g|s_fQD_B(Z>hu zeu%f4kdVtoEq@yw9$M4~Zm|W{uiD_4n1OH`cKSTOham(|M0RgiwWk?)e z_xfWGau^B$i$}UIH}L+Y)BJb+Ku3MkXRmzyNtC&HEvmNXQFps1CN&I`2}psRGr{BA zRO1s}`Gk+6(Deg7oO`(|BSsrSMnDm=?>QhPV9c+k8+~pRylxLhGTLt7NAM2uLcBTO z2Xshv>YFq#Z4l8Ye+dLTyB>>BjWgKusiZCCZ#fr^8@cgAZngGnrHy|$(^v4Wx$6w< zgHqILqZuRX1+!b)=Zjxc6BVS<5it!5f2sRova1J?DJOJQnxJ z6TYDv_??jf`!-k;zFb-rr*NRl7h_(5b`ED|Ja$ zV(Q1?n#LhHWb+@t{>awaT7*_Q{A5LS6|fzH0-ChFY#xuR77MC9;y1A3Qz9w*Woz8B z=w$=!8}foQk{LGSSlOwXf^)Tfbub?iL5*);q>QovyzJb^6QLCYF(IVlR@wN=Jyksi z>!x%>x_ExnUh^N6$evF&1=XuNUwclS2okx-P;3V4b)715pp{D>+xm9NBTeg=neoFJ z1RutwKbo@TQ>mEgEFwlFA!`~~CN5Ua%bIAPGhVGo-jc;(33{N;1c77d-KAgqQts-o zXj=d%H!T#%qshJQ=AOSw^Sf+Qsoh1oAr$2m@Whc22lK1F!x!L{(#=* z{z|X0O{3~wV8S6#?9I!TCEn&&AD?BYC1cYBlx9HL3!vPGT!vkL+ZdX0)M zXNvR`>Ehn3&CS7b2NImTRjN^yG86sr6_E48O%>(n;u8F?!UNGSNwOF*bYeq*+#3+p zcM?LsU_%Od6(;RljiG-Yiy9kVO;cKdQQA?!_-qSAM!+}efZH-SVm zwxL@_rPM+zd7`y0ddN4dSQhwQO7`o{h9@()J%yCi%QMe)AI&6hQT|KmJYf#3bL}1ridP4&_Q% zzKvZ@$X0ig@tVjqhof>57F2%&Ck(PAq~Jm3VbXu+%vpto<*epE42&J2>h${4}9L}DtvX=z_aTLTvc z{b5`+LM4n{XuK#|ivnM@<`w^X4ywUmp=<|Ir2)n2(dCheu=go;mp-E8SB7Fq>Xso=S# zA}e6^iwk6bWTP&U?JE~G!O>bTni6K@u!*Ef$c**p#YLST=C7bBa;px!crlyvj~SQ3 z-%vfui4%W)k4sS1{2JZAD)caO)iHcm<(0WL29D_l|2g=ul2x;*|9@yY>!_⪻RV& zogytMAt>D~A&sPjG)qf&3eq8=bV;YMAPp)4(%rI1mvk=i-aNnap2OkbAHwc_@0hu+ z&&&uU7N7-g_F;-%oYGEbcOkQop>=rTbGZD?VmJcby2X)5m8~8@Bayk$x?<_x!Vs0F zn5FZs^#?IKZ);fRibjNU4HQaCeRna#0d|uj*$u~%{dpV zek>qWIE>&^1#v(-0-1|wE8_Lv`_5oWV5wKTY3B+ zvhly5SPq{0ptt5f8gBDQTJyb%-sLcBe)+XvF|}G({9Uo$@9VRBPaKSB#Ar+y44%2x z88EnFa28NcDBv`mu~;ji4K#!^|LoPVED=`z(@E@ zQ#rNRFG$o26-G3Wfix`0(O)=>Q%})92^G9`+a-Uzb_z?9iPBmqY2-q%$}Hc zizRK)IQ8Y&sdjmXuKhk21-?4iq+FG%ii>&5Vsm_ zXV6IJBmc`PR8FD-ZmxXSrfC8O%>wNO8b%#=r^C5|U2H7cs*+(G=77m)>5(bDU#_E` zV`Rau$SL2(UBzEQ-p9ZHU26|f(nhyqGU)bZp_VcP+>ny+lG+5L z-0kjc%HR7;$yQO$)}oJrg+GQ zM>opf?mfa)yFHWjn0fAi_~W_iC|%8E)X$4U3AnCZ17`@US@yj7u=KFr_16hf3DpS_ zyynIQ!?%YB#*1LLvnfvw1~V)Q4^6nY7UEyliG7mwrABi2XTnQP^%8B627!a|;QLRT z2>ZwVa*&*FMONWMsBim4u@Ou0+s(pxx3Vha$rT1^J~6oHZzs>fMrN+KQV zPDZ^H`nkeCIy1r@4Sy4^cjcJ)688_qlRzsFA~v_?a)#d$$(4~5reZ<; zm$JzzEP(lY2&5aAg5y1zR@~@9|~o+2aLr8g|^sA7hitb?w7V2*UP% zVIZ8zf1WwicI+ULo4aTA8wN``c;dx(4^0~$;%3djLoIHeZa&hz56JK&S$jcAi*oMz zV+8Lnh;+d<1Cm(q9YlKI5TKO|jQuadF$5*Q9fz?`P0Doq>A5l(NlK0Aba39u_OdUw zy*mNzXxfVJL39IYD-$1Z8(slT&H;(aHO?nrG9lf%^vjm-_zuCu1P+%6lrVn^x&ojY z5C@%qhRkAsX!;?Pmbkxh^S`^=1lZ>pFaBP{z^~VEUNju+y{cb-pwGa_cW7IPHb=B) zYn*j`lv7iTZ~H$k!2&iBtl46@_fsuT-xfLQq?6_pcKjvp+X|RmT!aqDT87;YLk(Wb zD(m4O%MBkfdSR)kvE>(cEe{VB^!!O?Y!r7kkCL6g9~G*XbbKtsguGz6TR`RV>tfVL z{&0joow{apQMani@g-4Rk;e>gV|Y4r-9vTJsj2VlAW6WRbjrk!R-n^3SVoXT102c& z>4`+$ir2W2vY;E#6}+f{{4Xq9tru}KwCP6BhP3FDb9N;z*dg-k>3Q>*PY*2R2sg_u zC#&d;d?xAn_#R*<&5l zHRSnTR#)0Dv+yIz>_P34v#UNG;Q_TF1X?G{k364BNw%pGM@_{GD(V`Ad6sB+Jcx4i zcJyZq^$(`E{xy9-8vILH$b|HiNFb6jMyR`hk;%$^r{Z8Q;|hC6blEBAqGjpf@*->* z2P4_sTaCf?4-#t-Gv~e1jM_m-mvQMZx0TbkZX!BSP?r< zCr$bx@c0DA z3P^wukv5?{fjflDbk1vHn{?mv@vtyors^{54Ve55a`6Y_2WS}*S8F7>BPT9G@T1k< z%d3%~c(5SAO(}V^LU4Hzbno@Bkbq1IWS=c}5w8X)xjPwbAyj0k)YYMqKN!u(7ayX2 z34SrC-~l<>^@j~A`UI)$jqh!&32xQfydE5yd8PZ@$oKgIpn~SGPOHcmhV!iZsS;Qox7#O#_n;XB>&=E>=Yys(w(Wj6B)AM83A%f6w;6PY zVd{T`2J*`s$)I>}jDss*T}~iVRc?%Tqt}-2I}|2UICi*w)w0C>G&QI}KgXboq^4*^k(lE=`glf)L0ua|eH}@y?lk?$A-EsO7GnE-g%LS| zceDnw1jVL*nOrk_@bn=T*lKlR|pKxrlnACFL}4tl+AxbXXluis1L^agE6 zOu?{3aZlg=pqbNyB%+cyTI_-ywA0WLg= z*%grHnciRP-P~Pt_U7K5vRWE!2u|bHk|D2>-&C-$$WiL=;-^&TS`-K_kN%Ol5#s2IKwIW14T859I0<-bC5~m1+iATy}Z; z?8j#%r5usTTw-cw#WVh<0z&TD=S}UsnO%kA!#>|7v?&V2MsBmL5nIXy_PAC4ivPB= zY_3Gkbqndf%D_EZh6yh#`Xvz|+*|~-VqMPyk8nU>2<}%f@5ujbO0PpLa|qql|5fip zk-KN>eicoY+n?(wd)6=nIGM5s8FrOro=a8H@+n|-*4H?cNOXGscsxD{%`G#ECT?yM ztZK4_X)4^^3x%Jsjkxhq;oXbsLyINwUH=@4AH#(rWcR3_dr9#xGoZs0%_(|j<*;_H zXm5Yew*Me+|A8+2Zp}4ZIk{lLX$9SF?@hQTzw88!%X?~yBw5yYjWQI9$cTCg$d-~{F@^{6fNY7?90y@1y6j@I2X zrs(*iLWM#iP#`^O%jbW10Pebuze9IqKgTRTkDWbQGVG=;6eEa~t;sIgfJ)>RPC@g5 zsMqDyZbAU)sf&5Dj6vO}WZ>?97!To-ll!S%>*LQjQC87}kKVPJ?>t^YI$DcoeuFmM zz-dlql5n9h#{Q%fT!b-k(&HLiQNeMF2ndSZXlG)*zP;;LxII6gmfQlP@-FwCgJO=n zV;^$%)}?E|7k%{IN^I{8O0xsK!Hc3s(fia*f;lq3kP(zmUMUNtK+kNL?z}5PO#G1(G z`jq|dFj6ur@iF!4m47_Y2YX3#_gUEVo~!mw8DapT97{s{WiAGB^>v$*z+*a8SD0b; z;Ifv4|H_L(r)Sr=X>Kb&$T8>>sLfxV+*8*LXb!lYo*OMLR3!>W`ryYBTIeVx?VXo0 z_WIZVsu$|EcI)!&l;wyS9TdE@qheS_SrU3Fj)5K}D;kF+r;q&UC2z+p&0)is++*Qt zK@6Q$OeNa4hGlqcJ zi?@|_gq>dLRRGm5D&glcP}?D90m0fssZ-=n?TE%R%8SntPEw^~#nyDeGl%LdB%tp% zolmY54{*T(u1SM#cTEGB_JB6OyK4`&E8Ut)>k>%lo#$KU9DvcBWcB%i3q2S_H-Vi8 zu#XOr#cwQg4Y*tscbx@oP}^6OUw6Y&Ptz0?%N0^9n+z9*7R8Ez?vHO;-7IQ}D6`#f>ExwOmGg;cW~vOUqIE0Q zwUyJg!1~ZtTF*Ms9kLS3)(ZUKo${++4lnKc#_b2-UB{rXQKu$eAh7ha=6X+@gU0|n z&!C|4Zjah1PRsbirwWvpFwu|tHB(W}NZI0@wySTu54}=_;(;sEhCqV3H@N3bp;%D; zblnS5{N`hGC=p5x9R{r^fTgQYm^9-s?v+L5@rwi=ksG|}IA8rZ00&prOizi7YsLxw z=#486C6JU0#%#0R*dP^g(RIBkRnFOd6D|m!S?|CY!s22nupF4q9iQ`+<^r4s~VEHIpZS&{IG<0k7W%|a?hG3u$1HG_|NMm^OghUT`ZP~k%;W@%h zG1tG54+{dZ>>y-W?6!^8pss`t{7H$~0%!>SJV|X4uqhDLywGjF*aoQvdK{U9NrNvW8%xJfF;;``R;LpY!CXy`w?evMv zI>&5Nu0aq#Y|~BF47Y81-pKJ=sP9w`M>9#ZWB#p^WW5-48Od9P7CN+gNf{Y#=e2cG z-HpwW8jbPS*VM4v#c}k?oXgZ9d*24nv(Kk+4plz~+2xnUXk+9C$}Sl;n~u&)@!_)^ zUMl5WpsZiHFrnUrU=qzFQueL*W4DpMjn?KDqpbiFJq*VqWtjoZ+%e(@RFdV}H9Fq||Nx@mBH<$t-X~IxW zo2<*@De8t%IS*qEzt^qs`1?niYaZh?D;GSij-t%^{a-PIZog1E?i?S0nAlS7R?#Cqq{G%*_Y3n$U@LDfMGuL7(j z30-P*IY1Ka9QV^Bj6Q8uW(Y4gQp1?*s{2A-E_zs&7}+l4S}NBaO*t90-Q+-SVQ4a3 zx4vdX$u=jlOJdhLD(uHf@Dy|%i&zzj5_vyEx863aBEW3(+qnlDK4j*_bfm>=@Z{P$ z%|n95e*X)(;869$rWfCej>*sI>*2ga_K!Ro} zIPmu*57xD^dM86t0wh#GD8|b!{cpU zv?SdZl}P;!uW;HbS^gAf;Up1@q{m3TBf^~Nf;va5cQ=M33w~Xa?-JyD_D3$|{qMTf zM^HD+hKS#~$eP_8tCnodUr@>GeYYxL_+x(M_rSxa2yt<&kSL6u>Ao&I!@<&+y8B27 z7pBHw#^M{LyBA6;?B&(qL}(2|~fnqsaKv6+7LMlA*_u zUv`a{Y4(YzkeorpLS?9{ZjXSH%Lm562~?Gf-^tHK49Raa=A4>rn-*BRi&elwB5FM_ z=1vEP!JmW9tokqhbj_9o%#i^5WxgYFaSi7=i?YdrT?WJFa8{$L4pJVbunT zJ@2M~;Faz|B|UOilurYiBlW6~gtagwF1o}-@Etp4eQ+)2&DTIG&Kk@c`v4E82>+%1 z0Mb5v$Brpmayt_{c_M6I>s?~x#gs%(quX&M?peN|#(>7G#MIF9)W#q2nx%pA1&%g8 z(-)GcuMBz#*$G=B9H;A6#mc6jwEp(x>S%=!H31ifWX2+cXBmFylwm2vm-dEZoC6?1 zbh*C^014a3uvJ(BRzD987jA6H?7=f z_WK2^&?x?4gke<#5VsWyR~E|cD7lV)xWawpPwG<$On>v zOUMTC|G4!J8&HTAiqn*h*ZrsAMf8>Jhgbry%5#71s#PTzIz7fBtz94!gcCy|M8yuK#EOfI>P=1mJK&Zb6>Bj43P;2y%H7t z{0h=la-j|B#iP@{b2Ue%OFMrl*wNq#s!>7D&^u>f5d)+|4uKA@ME7h6Qh>zwqCN0|ucd=u#)a7YTc}%GD^d1CTK*62`_Z}Q2v+j12@31kU zGVM*shdXv5&Dt*+T4;+q(7X#+#_8zo>llZCN=H#n7kmS(@Sjk5$J^793~i$!?qI=W zTynDtU2#ixvt6pE>IYUs(=m!sj1^%8$1u7nUl~=zXWfL&WF`i9!@O&9tmoc7ZvYHc zYU_5z^HazCk7)rq&VVg;~1&&@ij>;NSJ5yqA5NciB+%cR)$Dgk?yE=9R$4Jvn^WMODPFJlXg%xayqP&%=Y-MJ0YRk{qHSs) z%FAzO%ANkux#oYW-Q5l<7oUpW&=>S(l<$&v_X|Z`!olY(hn{K$Ta+JSogUsDI0r$y zO|aE8x&oJ+nm)Z^0Z$eZ-<8o#{Q9Fp6$owsz?Wk-c4~(EwaKIg;836kZku(yM6cyn zVOs3#*Sii#S#HCbm-vygKs#(OtRjiQ!)dG{@4$2^`x2~x(iFUm9E5|ve2P*9;nSfL zFXqPZRC5VLsj(m(UCcC(!fcQ1h}h}z8-1?O58=uU9^k&4zsN^qJ%Km`&DCMk%xoHT z=fDaulTeoBXP;$tGSPA=6*}r6pE%BwkKa{9h^+|{blG2kVRba`K8|qrHki~D{!jS; zl36Pfu(8J_TRGFycnZfbAIe!la}NNj0sWUZTaA}CK^&`(^y3=}8Od|ywQ`k&CF<~B z8T)3})7@sk)ZB#d6Ah73^XWR|X=Yq=)Ox(TX4 zJKjj%Pk^+t`P*;7ZNyGHhH1nNh;a|^(tgi&L;bCpgdqyB;((Us{OGMQ{iH)$5%!lc z+snEK`~MY7-w8DkyCF9TdX$|895HC)D*j1s~ z7FV+Odpq{+%|izq=QjD8rG%OtJ0(lTnM5cH70XHU)8P`OJ9Bfh(34A}$qRMx)^9?ue=T{F- z0PqT5m1u*T1AGJozxb;mQK)JC&F`w0&%8-#R@vP}XdXNg6BFO($sQZ+lj|>MxB_%l z4)0z2GBM#=e@tD+*!vpcqR5FtX5WlgkIbW?fl`7)qvb#Q3dMhEM%z)Z2vnFS70t4+ zzq9N+!Jbw^J1Gh^@DGlOAG<8nyS}+xi%)8sX+HZgL-9}i((g^^z1AP*l{d^?zlCVn_Td3@FuwU{5>p z2<%rRDi{wmma(kEZOlKC=$B>-L_0Bw&)S*sx3FJVOsQ$5mit8| zLjkt7dNkXr?jb_s{6!luTxf%UT=*xo7%l+TX*Y>H5x9QJ z>YA#yG}bHmUY6f$i_X(~>%6p>oe=`;CpM)cu{c*FB_4GSeO7jSSL8_4Vdhze@7&0Z zZ-Pv36R`i?UQ-8NG%;Wcd_yyISYBD6{U>FBsUH*Ly}E`-|R~s$8ihmv2O5 z+yHU{^be=X^*_d<1t0}*Fu}GX(D}3hf|$2J6Q0;!WS_l8yyr^^is>(>XGaZ%T$=d< zLmkEPtX_}DS~@uOfAcw4fQ|5gO7P^4sOt-&OJ)sOe^{jiPqa#R0KsG5UUg6j{o?Ur zcqF#5#_(n1`;hx+zFbgEnsxG1u53B+pHH_PZ^_N|V~_U(HW`!gDk zb-b(jXYi(;@v$tgH%m0JxcoCR&)f28ve3~`^Q`Zg)+kTH{-MO8eTTiWP!ig_X>kgRhqkC<*I0>e8%pgW z!-BEm9xI_6w<;gruM7wu*QF4=%(^O^mK>rXUi&~|mS92EVPhBJT#vh~!$Dbs<>?wK z7H#UY(`o4JI(gp8=F35IcRyWOFt8Cxn9>6Nb99P;CMjt5;QhrxsXFc0m>C9V9e57B zh!v1Fd<(jlcu-ldf8s6swx4&YOWS&Wrm+b>GD!nFnUrSe zT`us%0Nrf?x>gEN0~%{5j!JWrx^bau*}=XVvG4id1@>Epf*(L21E3h-6$>sg(0{R- z`1wXPMU(5DokynX`MJI;kr$975S0C2dO@qqK~{fuIS|K*j*J!BCn5?j%6fmD$_ zQ3F{HsVQTvVj*g}y9J{*2Ya|dtfFjM4{f6yhHHEw05KlWspIAoP>2ZCt>8g4hX7q z4iVsmgEv;VprpKijHqdp7@_$v2F}0J=@#_g7tqB`aWyc2N6?b6gY!D zP}==Q5+I>ew>6!2RNzX584lIBQqviV&vw8h?$@nbQnVzf^OMD+P3-SaFohtqJzb8> zJs%At0(82cR>S3)e+(#-t@8CejY1;0UKUUMPRYrv37~7npAV>;L0T#~#}|KAB@fU} z(z{~nJD5}eEEoWswHN1tS&mh{ZpVyOd&2DFEt;iVT5wuoe*2lB=B3Ns;!^+vbRw1x z9%vDuU&6u092Tye*|msN%nH+JujiDlnfVde`4Z?AL~Yv%nM_y!U>td@;zMFq)Tkji zHdvv`f#$SjkcM7>;!-fD>&UcRFplJP9`qA! znPA6JiMpS$Xg{4v_C}^9EvN5|b508U4BmbJ)2hg+IJ3KKnV;9|81RQLAw+vzq5gUJ zwaI`U-BpQt?)3q`f^wRbS7pNGXFELL9Q;GKybdX39tTFP;IhA)R>G2#7qR;HYd8>; zfJ$y!c2%zP6zDWLxJ*g4OHQ|LVwpoXhTq-vS^9C{pCnsx&(B>4gvY<8T)Y%J#DH8- zb!-yVqQK4JK3_r|7rO+M>!LV5F_Up7lV%EaBM}woZ9|sj^NFJ@ZLo@zeJGfUYBhQW z%& zt{&$*ODe%C{pPa!u$6#3&hN}ua{D*t*~8WDEFzgXbhw^w3R=cK0meq)4JCk&K)`_4 zSfN!0|NHm*=GFsXwrhI7gK`Z6Vdrj`2Ax5$HEb#4S!RHB2#ZS#=GNubCRp$NmVYe> zKqRo(>O~ON4FRY`(+kuVN8^}=`bxbmL$sVW-Fjk>4k|;oa)%$moh&ajjD2#3-v&;< zPxjDBmRHS^y%3PJu6kuf zdlUCuH@D&~Z=yqjr5Rd+9)C-u!`)j2G~!Nh2Mk%0fNQ|W(>0DUDSr-KacvA)X%#=E>tL0{ zSa8Guk#cL_AFSDJ`Pd2ygw>rG!zp1@&(jIfR z0D3fK0m8BMCBPg&)3ejEZy=R-WS-J7M_tx*=d&n@(ACbGD=lr|)gf`}cwPWQ^O@uX zZky@n+rR_C8q`Bn^Dg`S$AwETrXeUR@|tV61{5)9piLzpI_K-Q-J`*k#-!xmumc=Q zZ^xOE+`yfo)2d=Em{IIk@z1XSqr5ud)UdEGN_Ff87b?0f+WJ8|FExkOjea_C@^I%r zGimE`5CAwGcy)433q3AEr&ql(e3y;!{`V}ZogGbg^VC7N+8Pz>?>9&n40L)EuS65- zxtVB7AAQk%&7bAZf@!NLa^&AAU&ZT9mw7itY|RiCl(eBQ?TZOt2%HfvS<4v4Yp?Ee zUyiSUU5;A#r&Y~f&z%U9=U>~?oEqj-oG3}=X8sWIl9kI~#%>@GuFiPIjzox18~^{rSJ5GfVwrJ8hs}v*rS}d zoqI<+`aYx^N#)8r{Ac;_1+hl^{dYdUI@>#%`1v3Td3|~IMsA<=Ub^mVNYKUanfs*_ zp?Fa0sIEAzrR}80VHV@)UT`jn~8`weZ_gerWpfL4!Enr{&tLQRpd+JJ! z_;5XFR|QE3n$*#3{TXKkGdwedUXPGC@Mo$z|9zf25|FbG_S&4o#*@ol*FBg$L`(yq z!FSzn+d+54G%Ik*U7k*;A7w7zpiACgjRa)RKI<~3e*v~)?)_EngZYfJN&RoBHPX7? z=Uu$Atu`I9gTPK}d>k1X32Fm%7Yn*|mmU@8DD|vt#8!=7=9d|Mwl7GK?-+(&Ao%%m@|&UE z-HBRxzjQQpEwB%=v%oV$<;ufxcp)MoB>WWfa@U#k3bH3c)x51 zl^xw)hIh()2C%K)rcu`fOSmLoKSNFwrGJOT=q1K_!TPN*vrAMAO-NEO6R&0IAI;1d zP+EAI8%8uA0e9T%z{Kv_^tV?ssSp}2;+9rDSEA=2@Itinvy~KEM!wsN{t-UOp|69P zO<&(|7l6{DI0cj+D}+kP4+N#e@3R#bAteuaJW`}7klljd6@=1<+aziLzx)47k2fYo@q ztqtk~gStC!7dlsZVkm$|b<6_e8)}q_Ue_Ngn6f0U9JdO7Y>&5S)dS@M`f84tPv`?2 z1vCgG$OC*Hbm0{g3F2hL0e|hMh#OQK1g`hJ>D&_)E>&A``SJc?#HgENe?42Ye=#mh0tpU-K&`A`=WmRJ z1+Pk^C9f)7xfroNZ8j&o{4Q|hvvDB*DCBaL?6C_h7IC=p;iF{gOd5nJOYmRN8TVJ4 zcE19*spL68xLHIktsZ`&%>^eeh(SS_Pm?nDmlVM$f=j(B-Ic5#me0F$?{91%LPxuk zLo9;b25BIM%^S0Y1Y@XyO?|A>ic8J<6lTLj0EJNjsg zxp0P9zNfvvuDOo}@gArN0Jr1_3eqpCyzqu}@&-tav|=(7@K8X(2*BLHr9l~|zgri{ z<#qW&gH2kcnIxgDwSgzHXQ|zc1yeeovT%3!RPxUE(s}<-<+#i|dV{%u>9?S03e+AA z5E?s7T?ZHIg4_v1ReL;KD&}@j!V>?j#}@`TBT|u@Vi=ww7Lr<~cD7r*W7B$g!(-2S z3sq0qb$yp%i^evMEYuFIkJa~s#=A3-6pcIK**O!UN zeN8grx$vBnX?sx@2Mf9svUhbv8R6Lk}on#-{a)c{Cd@Y zV$q^wOaKNwD2XL$NpQ1=+(ohz#oOI7X8nS|yw2>M|{)u!g|b!m_os2+nb#D zoXh>qi=4ULfn~Us%wO$Wu5=ZlO$}iGZ@c@qh~VwX*9SoTv)pJ$T~Mkx+(pg;=kk+E1E^gM#V%<7fAw4|qlC6cjwV^9$WPbHS7RxBx|2!-KX*53?w^Xxo)zqO5tFlD=j(*1XAm~sDh_n?755Ne6r=E z>cC?%RHQl-F^Z3q?P@{vUqGoH|F~X1o*4WDe-u2^$8q>XNxrMbQLC;D%`RdHQI8Le z%3Cew#ne|PmMs5lmAM@wZ{9r}SN3NTO+mUIYA=i9tyn+Y{Oh1P~wGhux3&NLn^xS>1g8Yo#lPIZd_8|CVoHT|)D8Pz+-t4i4qI^&HCftYrm=LDy{ zjImG`2(Z1$ydxlfwyzrQ$WQG%p**7E>PlEfFI6D=j)I-_U2T1FQiwrf%SO6=as9?S z1HIG&Ve8I`yRm~gL6Ih*5~0Xc%G!;4KUqq`;W?w76lf=G>v5i=~ZQ5FdA3Z9Kj?N(lPtAn?OQ zNUmn)WIk}}l7mPFOWXxJm~;{dn1j~!q8SRznhgmJVrc!kyQP{t4_rheABOJo4kM3f zwwn0iikEyw;2A~nS@;I~44u{{HK@4-1-BS~CZCpXWSvB?41p6eQ=kIfB#fdQ{SW$Q z9Y+`H-kehdPVyXojZvGB%Ja@pcQgZK$RQPuXBj)13$dxx5~Gm1x2htd2J);ZpCHv@ z!F-@$zoE-meg;D{==75~YtbC{bDyS*8P9iIUnSq=cVIihWx_MS{LwbNQQKYX8t_{d z6C9t;E0WvY%Z9(F!C-cor0OA-nr4jLFTi;XLa3RK;S->NsS}?ChD!!!hB%#oe5wiK`?@d)n3oyS~n)|Aw9XeLG?9(_1k1>n0ZB-V7NLj`OW-Cz6`g`kg)t;kQ^mdE??b(3 zQW%apXXips3D=;n=EaifN}|#-w6^`}x%8oyGh0RZ=~f#j<5T^JVc}s8oIyv?Di)*7 zH=4`gm8LTE=hO@Z%SPj`!-I>Aq^jNR&C-g%&-zP9{Il7EYDu>jo-InR+GK` zQX_J4Neyi--=Fb_Jt#ZcZ0XzVZ}F^sCUn6?R8WK_nQmQA7rC{FOQf^T(g0i|cN#tW z{^SPE^?)R{=!araKpvO;IqhuFXJ5}M@|^fJR1hkRL)uv*z=}#wwn%)rQ*6Mmh#j8g zM>DnLBzJ*mC-@_y?fzJYYs3wdBM{u^(>b|(<_|u@w}W3AYl`kSdxlwd+K7J+j6r?4 zo7hDs?-?Y`li9H~d>q#*V|Bp0NDZl28A5b~(d67F%l1rt--392w5mpUw2 zIH+T&s}2}gNY{I1h~SpA#I-t~vJoOt0eOa8iuf4A#Kc3hM?3GnUqI#aFaCN>4@n(Z z^)8t>Z$?Onrp?yx!=(86Hr?CVkUP&iDihk{9qUiV&LeNR-3OJ&ju;aQ@;lxrRXPO0?Bbvnh#AMghM~}vQdN)-DR_nWMB1hgMdu97^j!YYXMrI** z--`OMG1&l9c2GTg<_9yp%A3CFNYVO(k#BF(x^zA_@%ze1IjP9=1RXy7YbX>0P#{W} zi7wr+;*)YDe8=eh4TA|h!wJK{5yZUh4R-XD*Amp3s|)5~c0~>k?+Zy}(UMkx89vmq zfW->|9LM11i70Lk4F*n@Lo6h1$(B#8k`7a6O3q|xyNcx*>M$&5&x;DQ$ryV+DMsn- z$o-0|NcA&?yyn|3h4^O+^-E6e@)!t9m?03Ofrbg1VxjFe=6G_RnPA7ij&bV!Ijq`F z(GNHxbTfbSDI{z2riiZY_BjD z;IJfv8rnE#NIw^-_x-n_%(jobeSW-8(ujoQ?vVy!)+Qqq3=JPTmD(3asoU|cup(N} zt(gfxC>FfmNG6sQpbdk4*Z5uwyltVTzd{`!kJhPq^_1Bqi^DgzR$Qd2bbo+S#m_zf z1PMq4fG`=E)$dNNVI?YLWb8(njqIn+CxwCdwTFLDRW@%v!g2)QsnCN*k4(BH2O7Ii zWvJxhL~4lU$%4aoY!^;g%z93~a-Oi`*uyer)YMBr?bhu=G*tHyZ*K2)tIE)~j7zPU z;f~jbgA%N@wX3Ca!BDz0?<80-lfn1nxVe-BmRI$7M9OMW3{z4=GjtjfZ!28#$?etqsl z7XFtzRqg*-0Hc9X&>M>4EIZA}-BIz64u-hXCbE)Jwo%(3ViE>TnYi_c#T?GDvfI_H z6Vx%Fgalq@cqW?#0ov%2a`3Rb6k%wJzP0Ds3NVO{D%{g@xBkZ7WM1Wlfb%Qs7@|n@ZAO3sNgA&6(NBmP z*cYG*y=^)pP*i{s(X0w{TJ#}62F#-m^7$EUMtMvwMa+AQ)|UPz>x1$T+@U9ECk*yT zqMI^iiy20{-)x(&Uv>@8;;$Z2{%1^oCwUAtRDbutlK{FNU~ym}i_uyDb>FNgZyDKw z`D^6?EHL-K4jZ71RQ;rco140o@U5j1G9mzTZ{9|)KRU6|G{OF}?u6qEx{<;MRI|sE zOcL%nTy|h8tNYbDvJf1=Ab#OB&^lQie+fY_$>+<>eYUQTP6*gaCb!3PeH} zGV3CJn|iChAnpN{BM95>7ol*K;R{eFHfD}DE#ry_D0RZLCmKuKeH%`#5U%SaD6u?bv5{9`>|2zsE1P47Q{GD7mk-M(N zVMFAkD2K)Kh}%E*Bz)y!hracoXT+_wvGkWvtyUyWsq(JZ(vl++Zqf4&NZNff^Pw2f zaluU0!#7JBMzt>0_o@2yK6wH8!Ny3END|V3^LwF-ERA~4cij|UW@t2<=a&Z2V3b1K zQcIiN#+*_8`Iw;rm36GdOjB3g0)yc|l3Bp^9rO+W{Y?MK=@1|}aH(^VarVWnT8s{Y zd(^sqdy_NdwW7VV>aZ+olsI|D!Sx^LSJ{~esaEE_21oe|-%N|fYEJFkWjCu?frXLz zVnRwRyQNgiuK@w^mY7$oMl%_Nyi#@CnpuG7emrD-Vp&ySr4F*#vX9IH&C@&z=(#hX z)Ep>=VDLmhK-~JfZIrjiKDlZo5-)lH>jlaQoSII~3VkZA@8O7dD4=}*OWQNh0N^IW z$gno$SOTk`!`gu($WMhmndHzJDFy28Zt(_nP1cZy4E<93#PzJz^B<*ubjTv`nIE_? zZD)bZKR2l%Hw|qd|5x*2CXD`o4FyyV|0H_FZG&Uu&kuJlY+LnGJgDbfW}|-Z=kq-{ zppi5$xh9Z_?RRR-KIiiD(;=aa%sB|K7WZMxRCcyGc1|y39Ou?k*8W72@5fH&Y;egV zEFuYiVYLRZpc)ZVncE7>1hgIU#PaD}miv5R%iifwKg6G5JkcQ8@RYQ--E|VOA{35S z@=Rgvo$V~{0k%#?Z*PYKD2R<39R)W#&XZuA>`w(7{*=LDnYCm`VCT<+NxS&4xSEbtStY_;2E@K_Iz*Hs=a80!}Yx+rj_b{oy0)c-y~l>+-s zV2<@F!%cr9m|Uq>fxCCWWm7+wVEjevk7o175_Q2Ya+e5+T@U})V1a@$*BIe|bpmZk zP=Zun$b&hf5-+KHfe#1-g9kV(4h@N=u-@9>0d4|Bg%V`?W!0l-DRoTB*}$=x#BfgL zXel+#rOTIbZ`w^R_8CSS%|kNL_!`AMwVhDL%dVQI%*)9&k=mix!oSMjuJNjnmVS}$ z1MQjO93MMmA?>E)!GBU4?hZcpmW10fcX>lxsh9h$sxNTPI-x(Wpt&*smG6ru$(xm- zMohD#4#r?UtxCwY+3d?7^^nh`tuor0C(M7{5XJaNcTG9ZK5}|#7%jUsEs>o#K8cxV z?_^+)RQH5#=gC6v^iJsqhkEmcvY#uqd@>~y!dU)~e1FN>XH=EkzA6Z_vR|SU4ck2j zixYIukXB;-*sm160vJZ~Gi^WwwOHr+;Xhz=B>%`jcaw|gW*uD@)q&$ER19abZn@v7XZ=qcC>+97=^E#1=gcW44+b?&ux;i++7gJC&u;H@R zF#dB&FFT$xa-9CTF#&4q@a!{eUD*tKG^T44q}G7fiF99yF`My9`7vuOT7^5^_sA0G zCVji?956St2;3Dk$3w!2P>SXPC+hG*q|j~+8_(?l3tfl;D@660FY(F2K(bNfl!b;)O7$-pi@7&E^I;FZ{kL zGc!FP^PTc#6Ygo2-X$!)v!o8y2#Q#v?k{r_nWTW++=31`KD40E3UV z5ADU+55in(fRF+ZpWBW+5T99%i7)v}^tuS)K21<&M@F-ENc)|A1?F=1T)WhSj4>rh~@mk?GDY(Fy}` z4BQxqnc@U?8+wFp{q`cS1d8BY8mh+ONZs_oRgNW66caK>T;qrzKnO(V-I6h4@jyw4 z+I-(E8tQZ9H-~>5>WK*iXv5EN^hQTI`BVdVq>EozF53nfjmKRGm$-5>LMp@ivfWng zHx>F$mviWlKj&{gDI&wY)tIwU8)&S#1vm}FLHy(ohyBc)$Q{PPqgIQ?uA9qb6^F?`~6 z`%&tOhFMCw#y0xDx&>f#0ecTf+u#d;LBkta2WQ`=Zpe@bjN;FuOiUXL2%?a0H0XKu zDWKt>cbq}dc_IsE@9)g61>qrkOu`N>ZCj-3{bfE?b<7apeoDuMa`3-LSF;c%{W4#V zguY$TyE}&tby1?{m8V+hceC^8Lhz^s!^|`YOW=}x_*4esO2m>jN@+=>@RKedm3N$$ zJz8tTE^5&Yt@4}4sWa?KHofn*>+j^7FL^c@SN^alauKP~g z4E#D7^*fYc5DZS-4N1%QU^tRH@gt6Cuw-X6aR^vGzg+OAW27<&8eVxga8oXnKFyUd zJyY?adp}(P=1hWWIp=nD&h^zKQFtyq`mr){Ip@F)YJsjhXwD;%`vg25avYE=A2=r$ zZ%2K;2Jv#qMEBGb**IShctC)RYEuvZGZmoxbZ@Fa=ww*+z?1<<5ul2|KhIO9FOiBZ z$k13KT!?c`642^_;*U7aR#}^l=nd z`Md3vJk@$4OX{r|1@$mS+Q^9V)43M5Ez5=3XH1_aGlDHclCh}Xzo{41uPv3h%b-%# zF5^vPkQRSZP~XvDKH6agZ3yg40AFC`Vt4;HoFU4m*%}*gl;8^#*?wkE8DtxGiTuSX z2iX$CBr-hLFMTC?w>c~>=v8Hfv#Isr+r`g^+4m%uj%i1`@{`1M(lXCk1*N8 z7Kd-ZnP8y2H1yT=LFR+GquiYjN0__kmQv5~u{B6262}Psz*#x8C29k>&{V?@DBk%2aPhnXcr7Cut zXFm9_?Sxm5TtrY|uRPG&NOJ?&#n5&=$A(+6(;>xhy25Oxougg9C2zwPV4{J7toEQx`A$%0Il-S z)KYTCcbu(P{bW8j`i^^-!@YQ3H-<$7=4G6SYoofQYVK7Zsd#mc_;|WBh-{9ar#+-)Xa1A z+TeKs?q{Jd%YAK<_)DK9N+aHp)o?TQ3l}IXAt-|o%SYLCKnPr82ePPk|KBZ;j}qkz z)^AOnnUqujmI1^akn0D^DZC=$oi!FcUibd#moYn1e|(6Rk!987zZS7sYvpAf*ohH6 zris&Qn*DcI@l0Ue6DihANl~}DC@qbbbO+&lmpy#Xe`k(6Huj9aB)8T?6tH)V?}x|!>g;gKm>v(aElddQh3pm!&K z@LTEO!QtQM;(E83aTjY^#3<2zwiaK*JyooZZEHPkV|Oa7HZ|kqi{^EtP~9^^eY2^5 zj`aI>4;^`*-f4HUyn?n9_+Qm_zAe|;4;qJEtWw``t)jIp*XO{%grZT}_`3Gbs%rbv z5Eux?T>DBTTk)gKR572>J?|A_I_1X@=S61jk#f)ms+a4);)1xtn&WI>ZoVMVDo%mF z{>*YOUUpJZy!fyOE4%u#s^Rz6wYd+kHT$ZrnqMt2*Oh3;gXk(b^x^yqFR#T16HCm7 zjlOd=wiRgYov{7d;A^&_G4u(OU|7p1mcNW0q>prPEzI zUYJzI?n{yl0@SCqXRmSkYdHqspM?rA-r{TemtY)1wyfAsj{8AU8b1GqgE8mQ(=wMr zCrMtREqc)js(bqkf#l@3JdLg+Bbu%)ULu*Kwrav`zcqAv9A*k!?nF@D)RFBdx%Hp! z?j_0tq-C9ha^}GmXp)9{(P1)E6&4k7YRCCaF=2%7KkWFKa+W&Mdv~pCyd6!G;8X=* zB`lVLjH>X4r>f5;xaMTkjwS9rpYW~2OSTc>UG@j-2<$fCAmPt}3w!?slnc;%fYixQ zap3v=L$61gZe1VWsbq^|nEJksbTMY+Z;Gm(r*}40PTSGU_^P*TeEHln!MRiS|EWC{ zT=xurzotIE)x%{BEak6NJRv0y${b{36CBk5NPxpM{Kmk0<<0oj2YC`-?Rkj?DpO4< zCtm-3O6M6tMFhPx@RZ^YtzTXu`QjOAf$)=0zV>##kNIS)clj&3FhpHF!DtcJTg;Qs@n4MQk@cbD52uXJXbpYyp=StS zv+W7(dLuSjvoyp7x;MW;j?!It8jnnXBt*@>HSyFv#|1}?_x(QDC*1k$MPpC`pR0=3 zzNtb*JLJi!jcWs~1l4tSxZC&7pu=%OPO`Ai2AOvo>rsk+HN3G)_Teg$j z$&|w90C4I<$B^D{({i&NO=OGZ+3?~_{oAM~h)Q^* zmh)|sD2O#S>9SzLkGD=`H*^bW?j1W68gf#Dx2B-3j+v&cZ{a>$ZV&J2ib;!@`&fRG z#RRYL=+DRjt5w|`6c3MlhciwTaUG?#soWIOagplYAH&IOcd|{WW%F8+P9?D=QP5%q zxGS*B92$>aJL+_nWnJqL8{Die9Xa97sY%$d4iJm{yHOX@!#2!Aycu_IfW+FbuYeS1 zFOtHxRmxK%7E)bYQ^IzeCQRb6ycrRX=9x(LN*IC^9tb@7kdl(F&u5CQM9sq9dk0@% zFk?ICoVTqj{Y9mVOSCDTkB_=fxh=M#kH_8?}h<0!z3;Z2J9zj*oYopX$YMJtd*O#h5a|Fi3%7>hv z<=55E3`SPgIEPZ#pHv)`p?N`B4kiqV7RrkkRrwO1aL23W^be4?I#yJhkIhTbmfH?* zo5Wh`5;l)TL`K4JA=S%W>0A5*G9~^?_5<&^^t5DUu%24lglHLBHfCS|oxvMD73LqP zO1lk;*Pl{0?GZ=$@8^Uf)_0b1s$}+Bk%wrt_RW&I`OUreHimQx19AGlM*c=SDUx4J zc;~V9rpjV$TfW?l*Es$xs+|Ix|2uv(B24qrLb)e@4ufl#`*PW4j1N<*L&3)8c<1~k zs0|=8TGCE44{>=ELJVd%JpibHu8N49q8frBAgB&%>A3j5QD?vD2<-r)-*txpvB9_7 zxs9c$_?w2hBXzjAhdbq-#zPDjP@(kkKdC%d-wpii{`T9hR-~)(;I|Z|}E#eSJ|&D&25& zUTP#NAk6sb;Flptk|ENp!n}Q8@%dGClI9JJm!L7~E0#!|hRW-LX~8_2B-?JRlyBSc zQ_x_{Y3quuj-sPap=WQ?j8pk`m`Kx33mN8ght2#xNePf#ELr|_CsHWFeml!HmYr|C z?OnJc{!LDTMSii*43?$6um1W(rkH#HH|;gF^y%xE${(!_o1&+~V~p6nr*>pv8xSBh zl2?B4Qi}%s<08!!3>);tMQX9kaCK2v+dJp!=q}CMY8@+6aMfsU>spAOTXG7hb1FNt zQ|xkruZ|l^EDb06uA|;SQH{GAIA~yG1aj%uW>N6X20EzrrShq&SF6~llVrhZm1U0w zDOmmS@iDr(#6m+MdOGV=C#}fGixCkKkdByobb{v}p4Mq5Z6v)$ z13{pq*#n!zpHw+VM~n>3dvo zmt?E%O#8OJ-Z6VXvf0Nudp79KGg@{b5(czR8fEiVXPCJ>vUwVG^r( zwlbkAQM$5HlkRYBTs8y`V#h&8h>`*Ff^T1Ve*L;k$bo_e zS}N@YL}zc5y94137b`*11MT=_{UhR2w~(78Jc*r?ElS$73Ej&@kVP)9?-wpGuc$mHcn>n(mXMcz+`aJ&}mn%EabuLHd$wpm!(cE?zle**5 z$Ii8D)=AoQplsugr|6jD=TABhohp3446W8alb5xEcyT-NhKteKx9Ktm?NdzJxM^~c zZcmW9k;JPEdS#`OWzUqjrB|KMQy%tkG7b(4T9=)oD7w|M1EC2v9MCv(H*La3;9T8Z z8HjIwy>vp0FF5DFqWPMZe}vN;yEH+MY*lA+Y3 zjoHog=V-rd>$A$8SC@Wx?L1Vf7p|_a?aHp3d_;Y?6;DAQ-tvC%Wog*j=)ZU+ov=DI z8HT@}TljbK_dld-CX2*@Y;OU5+Vf_DPaE(U7(W|2tm7|!(y_2#Aj-*ubj-KKI&~yuwPFJ5xl?WQYApN*%;%%D6Esr_ zCT#SU8P<^MzhO9ZnE8oen_i7R&J-W$<~?|)DH56HD6cO?^M3g7;Z)B1f#u6L6i2WZ z6z-I-4Ng=$>M|cB*69`f@P#F0(1yB0n9;?H7o}qI+s%q-^lVJKd4-?o6n&dDJWCxf zj!aCuk*gTbI3j20Ll8_)y}0HmbjJ|h{}`+EIKz4_YQWPfzp!vF;RE}2lAzt8&Dq?+ z{8C0&UrV0>%>k;PY*LE&lQ~B^{wCZSdHmgMWz=%1LP{oWaMq<_a|B~wZPD_d8e^vm zHl2%;qRC4-3%g$J$1!mh=riK?B(p0IIF8B&uaxXt%lE=VEIb0-4R(+6p1s9;qT$Rx zakl2eS0#C)T`pfGHm*gr%<|iln`KZGwoz(S6VzP3R-fi?)O?MMjC{gF^NRIWb8wh< z-Gm!&W{FU5Xk5v=!OhJ*Bz%-9F!aR6UV$V2Jbc%SMpkhjR(r1PEbGDTcUs#Q;i^BW zRto+ZfJ~}=kLWEdEI?k!nb>JuRSD%Bn3qVgeR4TDIU!-;v%|et6Pmb_`eoeNnhtH+ zzfrwbp6#X*#zY>qGn|EM0(u5G=tAP+ppk2SdPk@DA9q@hDU(!nxbU zmi8dwR5R5L%~E%n-!Z1gc}KSG-#U_Id_~osA8>}8N7IQmhmv`vblr^+f&Zs)rP>|@ zC7`jP2$CAAjns2t|4EEvQhY7gzKFF~uX8_oK39~&S#75tAcvzB;cy@ALfCS27apZ; z{JZvCe7zES7XX>CfqwtKsnGo`G)tvJ3pOHmTRq+DK<%?up~I67zoi(gcrm7p19@PI zlTymQDIeOFIcs+coDK;Ln6bactu>WW+T&ix2eutLH^PlLGm>1oz--+Qm) z2T26OI=}`5MIwd>0->QIK{@(ug`H&81MQ!)b0EC%#ztxAZ^KzK(Jt)h zBj}cHhBxDRUNM!3yE9=T=o@jXcmm)Kg=!T~S_qp@g)%z^WLJ|=^G)c zIcoBa_wQe(KTzY9NjUVPAd9T`Xup8z{T_4K^YwGDI5V%Kcxr_-pUgRrx?z4zrmhUf zinoi4i&6EC>Lk2&n-Kf+eRM$hU%TbOO%&?WpnKC$ESKf6*EtRq;i&tDt* zlR=9^9=YBA5KMn-wmmk!`#N@iF;y^i8JSV-d>1-r7G0x49ho#$@`p)1jsB+JJ*R~p z0R#phDlk`Av_Vz=_3)OF4=T~q!7|?tQR|l=y%rv+J>6Ng(-NTvL}ITX+8!DfINkKq z$9;PTQ>@)KQ#9k>acDsoVr5166rkH~0@MTyghP%B7~KkeJ{_L?ygb782fMPWM~5-@ zb6wZZ#;(A`_-k|MWltd+zhRGa}=D1py(X5g*}ZSIsT&O57q*N*w9m%dH@@OoFU4cJxN5SH&C!D#=syB;k;~V+RJdn( zrtqUjv5sD5{7F%7<8Z>gSNs)-2Cm3HxwcqSQ?q6hI&*EzjurrBNT`SB5=ho_uTw12 zSKdaA^RxReucV{5t?Us9M}meTE?4RDILbl*1!2B0GL(2PW4@ zg3Hb@|7IvFHN|PO;^9w31vE#Qg(EV)g3&L0caUT;e;NcFEe^V>jF5BDHR3iNHd!2$ zt9r?Czq;ri`ngY7wms?fW?#>8RA{f|)fTl`x+mWWxLw0RXcLo!&?CwllP%Vv6q=sr zqyOSPYYJ*qa{4K{rMt4Ks5Yu%cAbq6jc+oZP*a|UC*C>t^P=n%>Kc0o7;7F+dYU7d z0H2=vnJh>cX;v?LC=%J)e3RqnP1F1?K}octs2m^{L{i3kGrBO$Jd(lPCH6kQ02+d^ z%@w+^K8H)@)@94AFXcyCltMmXuc3=#%`SXdQed}X=HUH;j4{Jx7}6!U5A*j|rm$7T zs~n`x6-`{bg4rIvYi?wHpq-=H=9xD*bkaG;zvTV&poP1@d5JfzjN%4jdFN1>jSqF% z%+I0B?$-r5AHuaV{v}O34S`nO%>yZa)|4A)_#s{6HYF z$dZpF@-3oSh2ye*d}HZY!ZMefGs}{$@bJatnR+Qy(GJ~#-<4nM{ z#rlfGzrAsvhQ;blw(ad7`VATw(w~=f zXeds{bHM)?ln)rZ5KWrIveqgd#(Ow?{LJTqIe@_CSTi` z%hO*MRf#tq*Y9!KuHtR2io`0}1`n7XG#uD%db7nhn3nRWu$Uh_iodV}%L^#bCktBk zSERrF7~k>T&)U{Ce}CL%=EwHugV(;2v6SW?#gLh6;8}#`06t%V$m)~OW>!Gp0LgDF z{7x$_N~Y01x$U4ZqUNo==2L*W`<}Jgr~ZEe9=Npn4zF^pJb=!12ocT{z$K$9-Pqy9&&+YJZ zaLb9MwjLjg{U2sD9tbus0UKgaQa73y8mT30>2{OuM2mKJSfcKO8?W*f44TmU^gOG) zf1BnUU^mWHV|rSCIHLi6yO8(CUp9sd`$~r#`YLl->(%8woL*CqrR3O6J7d4Z51?Z( zRBu}0un%@kIM*S#LSsfg#$`yws~Y04d|u+76QU+5nTKl~zr?q4-U`D31uqhQ^@Q1M{(=T2D!A3WmkP41UShoX5^kN94*RrQ` zQg{&WGK8gba+c-B%pb5lPaa2bF$oCNsHkU_tF)Q%vz(}jM5>Qkycpw$qwMUwRojeO zXDW1=$WlHfYT2;Tz}F_IyAua-{WKYW(+83zFO}%0 z@rSF65J@yhSKf^`9N{DWl;U{pob5q3MUQ8q3q;v8-)58p)akaNI!)5`> zM4mD$*8RWW?v;HG+0X-$JcHfi{C+EN7_I7lqh2ND+bcU~XJCd4%3Zl&pO5Dm8W-NF z!-{z}sdoO_K+%6CB6<rP`3qa-R9lAg6Yxt&b)E&E5pkFPhdMJZ~eV&Snd82QdFUb2C51)aWKZfwhYxS zK81UW3Msi0$Gi<9qW)T3P$ zUA~U)r?Z>FsyLAjsgkS?r?)=PXzNJtkVG%MynZ_d&ItTA8ae%IBw4q_{U59{C#0oF zys&JVS{=QY@F4+0XR7bKl9*q#_oiAQDX-c8G6U z*!IN4H{Z-b?cLl$;_#>r;si@K?Vfi&D#B^)>{zjuC-aWNTL(u`q%T(nN61j2S05&B z6(d^4hyGpj@G-+ZjlYy4B{8=pWi6B+JM!!*#rwDFi<*&F72jg*yo{`ssx+I{JeA4c zXAY?f1M>%a=irnwF^teE9NRidhz8qceed+j1Nc}YM-#k`5O!3cj)M5YZBG`mhN&sz zHd63h5sz{T0RO3#lUz*?T@p$*oh|z<$}J4Yhvf1xMLQ=4$;j#b}FgEt2K_>~nhtW}9tk=n-U5d?wLk zdQ#Xn6mpth0;Dwvs+8?_+c7^j@0D$`h7b*)i2Vz6m?K-QWt8o;7Q>@u{%JU*tLB(O z)rBbgORWxVcT{AFc+*qnaNM^wx|B_y$KNbv9QVL|a{7L=PpcuF;_N|{c3nb#;cU_m zWgEzbZgEFK9yz%10B*?<{t_2PLoTIP}DV^+-wm;n!?Vb;|B+GP{@ds1y zosE-O0c~HLtlC;yI?utuVc7ybD#_OC+oSL9qsmx{-Q|!oUURH)oDfFavkm7YA!b-_&-p%#O`@%6D0SQ@=5Jm9})Ie z&BbiJiWld%BV$BZ0moP61c}@Wm)aP_@zh09=Q+DSy z$ea?gDBJI~S19jVtg1h}jg5q5tO3ob-B1Rvmd@*8>_)eMmIwTy{Pn;Q%x5s1%~pbq z^Z3};-M7GA!??kl0q!z5xX>kpKQgs#ef#^$4S2ZBBEM&Ner}~srxA90L6W7PA2W!0 ze8OU<?}nN%3(@RtTeX^+P1iQS+9sjsZ!4N? z)m4TTKSso9Rn*V?sJ1OLDt4IHU(+*rhRdEYbGu&1vot7_g2xa^$htVW-?5u1vTccZ&P@lsw4DbNQ)mPndK9avjlO!jT?FdFGt* zk6q+0UD6U`VK7kiBZZo2@igChCUyD zrnEdzZv*<7k#Q4P8IV;0Bny=SZc%^(O^{5%Jw)8w8WFJH%CUlBe1|v;kt}hE+-Se57udStRfQMZ zRTk^p5u5L@zU` ztwyaa#d*V-iV?l$_lW#bqwR9U*pA`$3K{lY&iUNNh>(E{)2>CEQBnT~b7{+DM|P{i zU8tiU>l&vMYa#}}_Wl^Z>55#?>OQ3X2c3)Wk-Bx=PB3Gqw^$@VT;LdmA_~1Yuolqk z06ltZ3zSnCaB*2f6Gjn4vV;GRI9+$Irond?ka*sIVR0^kEX0>ucB-74Xlb^AEVAA3!x?ED@$ef_W#FteuqSjDyN7UnZJ)XgcQ5)Uj>Y zMcx{I+$*9>RUB5$t(d0z;wpLRTU(iSZo%L5E0>)VN$&gkA9v+W=i<;~u_HDi;s*Zl zzjdac&cv!be!SKVdy<8Ogme_qUpmgB^I>;8MvUe1H?15XrY_RS931&R=P)nG>(1#{ z{^RhPvfv^jK;bXX@aCU*vdH^hb(U4YOAu`F1S}J9N@G1N9Ji6PG`9BlMcQUy zjetQEU#NPfyhEz-1@ZIY3aPeSD-W-wk37E*)14suWtH`U7o8jSg_e?bSL~wKh*w7= zM752((Uz!R>=iL>Rfx3&wtpnzAw4#%W8c=+K82pgT3P$SE>f(SAu7Qbac<<9;&{2v z?Zi&#zhGu(VK>6%EfdBvF|n3>zawh~28P`Bu1!E{8E`<*oCGExP{Zlh$zlZ$a;UL7}A zeX$^xC{QTKbhPm(RoY38NY?zprST-wr?YnJO`R=m?5uKDpG4jRGJkHO+-V7%O{*)m zvhW7H?l^_dckmu6a!;s{7fQqd;fKsmz*jc*yl?CTNfE*|K#C0H^^Y+a%Fvk71X6z* zzYAGuZ{fearOQ9yqshxGRE~xg<^a6G0RXhGHs9iw4K*mR%p1nWdHPmq zYY1p4)=L@)xm|ZiMF_|OxOY7t@*d#jop~|CgoM4J z9v*bL2j1>L5`0KaHNA6fl=UR;m0p4m#5zFgp!pl+F9)z$VJ5yGo1FIx2pJY8Bi_^$ z{tg_kGj zlDe-SqmI%Y9qk+q)hqfTrS<2t!O|czH72`rB0vgszE9zXQwrx6el*Czk8ENBJw$T$+*nThh z#(a4g@;zz$_nk7wMCDa+gT|5SXSjbuzaLdyRQcYeceJj8LKN8f^v!twK=a22;@cY8 zlVZAz=}>GE`MA#)Q!H>L%ddN6OJYKl2Rhj{BnUGL_f;Td;yTTtvcYSaffoy(oHgoU z$v9l9t&z+#VYh4RVK}f;_O>B>dy!MzhaVckq;W zCJBIB+dP5E537$;K+JCLNyy8W4tK*;l9feR)eh{Nq_3g^_VF_{vP<7@yel+lRmH5H za=P1dS|sF!XZyBIs^bq#k)nCotamIc&qC0rz%kE=zps87N)L(D(7xwLq&1moP;VK| z^g%xI$YuEET+%ewVU4q1^$>j)FFj)MVWKj*`HRvCS}w-XAD_8$+^|Xn!Mora1o}v7 zoEW`KhgVU#wnAMm^Pyh(nlgZuKuTxzoi)DClj?&)kV@NVR5TZ6Yvq)Ex2;}Zrxxeh zJGe7da{_%>q-x|3Fyl?KC&qEVQb#H+DP)S)It*^a{wuVuu$>%vmll8;ToX*_KGga! zh#RR2x#Y#aTzPSFq_gwk=Xsm`TFhbQgDSVYyeU_%Wa0RjKd*eVg1?R}bObD_Mf?ywg;NBLp0Sfpo>t}yoes($=0s^BWIdW=?U z3*N4B$~_|H{;~y5i%Gp`Y!wf`DvWbO7k}Wm!_iPCf>gwhs9{N+;ms~IWgRm!Gg*v8 z67WmD_^OF1O21uF&_cY&RhHt^&DK79fD8cWYKZJPJ#CcJ4+5A#U|44zg=L;llZRDm z^5MTz&~KikEAQ-x7c*12eH z-cBi8#!=%$DOV5j`P-U~1m|vBwP)Gh32$%}Nn1PxMF_5?>h5i$Fxe z#;{GPK%z~uXm9?qnUEsjy@fjZ*KyF}L8k|$wAvl6YM>&41m;gtQkA)LnZGINDPW`W%A z$g@d5!rjOx@^J$i`lL(rT3L&~m1(Bg@~{hs(4B)UyZSJla|HFJ>W9zvneo$G?pq^^ z@%K`@2OTABZ+TrG)`Ffs-yy|z$ORc@P4WYFp^z>2 zxnHMs&C52{(38)K;G+V0z~tH*#JJ~Yp8ZPskP1)8*7;6|b5dfD{d6kbL=qc3z6;X^ zl-p{L%`@Qnko3~zp^@fq00am60$7B1{>&?hl6Nl;L2(8(4X{FMO6?jh_gpk)ny_Gk zfILABfKIx&xcF&}vO@Y_t~4Iu?XJGNS`|yA-8Va!Y<#LDaOpGAY}X5z*fWYe@L>U` zhIbm+W#13_X`NwA%=8)>h|WY7n9hd3+K%aQEE;yho!;=~7SYb>e?K>|bEQVRME~I9 zINy8S)VjINy(phD+_DL%BzW1A$V@?`0fmH({M0zF20VTKB)79V6?f9eUheR=*Z2r5 z=H2|4RDTI!|0{jMwy2w$nMQ!uw{P#oNnt0eUSa1@PC!C8&yj7P3%Zrh(dK*Uo-iDe zYz<(K?J=KMzMUW1$ve{PJ}E3fNoSy;)?vIh4@nI6U)E2QYYK=Q8wW% z-=R{wzU>IN6gk(5FMXMfhRH5t8HV0C2}dsik6<7QXi;4(O^}ZK;IUzaDPPhv&7sS9me8U5O>g2X`SzjrkC!3QG7y_>-=8vdz4)HBw^|%Y|55u<_I$@59!n zWr6Q{=jtfXVYVd_|xEGP}9pTGy!|G!lI-4ZaNVK1Oo_2F@HNz5l#(}?^4A_ zqaDdS+pRw_niLDWBY{@+m1Tj)S;*?HgvD@de1r9?((se`r(Wj69xdGrS8yjOBpuch zUjz!qxHBSRW7K&Y`(A(h;W{e7#Z@h4VZ`qoSeJvV)71Lr*v(Cr@txK2#olg8yS zUD5c!Hg^@ZZY(jsqY{#vx$9ey6R@9W>X#T)Z9wW-H=#-6lZb9!fvTVJOPOE+` zs8VH6z#H51AejExmzbCh(!-Z$6g!ST^7WY5p18U)rZ{*E03!x@LEYnQq z?Ybrao`=6@BMW4v%@9ZbUkjjYZZZZ93?bbzw9J0uj35&?<;EToEZM`ubbwTfc7S`F z+@j6Q4*B?hat{Wx?fpmbN-z-|`HEl4%E`%56`x#PdW!Om@e0rK{^ig!5xd_yV2VoA z6w)OzM`5!*6}2K4OKV#6*4)pX_bK$4vlQ3)?C%z_EUmY~Zc{0)`=|7vCxZ6MO12W< z%uOoM?wfSaW2^pte|h2}DX}QJDt%yc%8uLv(i*0wSfJ>`?-~Yo(+m`?;NW1%N1ms1 zwQ?q9>-lfRE41l>t{DDYZoLaw%D?UX5&gbyh1q#H*CJ8f>(D~$wY!6mu3q6#tHw0Le7pVOB#juzC0%@fK`$+>~T0?a%3c_FCDNH2>Gw6Za3+F~6Rd?9?Kr z#<9%sJ%yE_JosKm6KX3;BL%|{4r;hf38)8T~N>OQ%sR5 zM8UiZ(}{m_A_QVu7e3UG5cSwN1@cZfNY)!TUseaY@J9q-4W2)o4l{n;O^qj1Ij2T< zD)7VCIS`%+B_o@nh_jQeIqF>X-69q?hD7m=i_F)vR=Eb3kQ;xhj%?=oJvu7P&CAS( zyjphBIP&9Vu_vgoHs#yiijxa>(>J~bCC?hw5SNH?i(49Jm62f}Zk3mF;&-R?yan9+ zK&Tnt8M6~)i?tL;<^*X1HnshLTH_Rvjv~EK@=vKeVtYyBc;r6A)IF&y&KvrC-bq*f zY%dOm9DQV^L*d6%&f;j&Kiu208xGQE<6^AYRI6rQJAU?ekWaUmE~4ZdYNB~euY3Nz ztu|tvZ&PbZ_eGMv3w*8)3}j)Y7N)1ek(SZEOz~qyQ@_8HWUbdRV zy4&7~{B9M0_%_fgomHIvrQuwIU&Xha>|x0nlxFC@u*W?EVs-6HApBs@xTrOo&G{Knohgsyf%U3$YA$y9NY2(rLalhB}eJvPr zL8)_pWXG26uI1g@us<5@sXNVI7K?{@2$S(N(Ra5>d`x|htWbzq;h|6j9P{XQGq5)R zDibglxANHg<=XA!n&JEpwxAv)U`tIC;6=CR#nc$uE6*&2XK1H%IWSF7Q+(>F)To#Y zkKak^NH<3`Yk4Xlj_l&^me$2k%Z*RtxbJ8X&;RVtG#z2)#(%MRWgEY zv)*!8|F_y+`t~M0m3NoXN6HWR|DLHt9Rh2ow|=~%+aZGlB_J#Zd)08my&gsn4et1; zB`4SjA2IU)e`r$p2HHE$&;Yrga5_75J$-V{|~eYi7Oy?+W_K6qYErcG$`{AuflZy0ym=3bCR@j)B2KM2mPTzD zr!w93ytcq1 zTXGuo;uw1nwu>kJ^Mtq{L1MRRGML>N&xrr*x1@h0Hg{aO4{9A_a2sHJ)R8v1*}?H_ zBQyKDn1hsqLTnEr`u0&c{aofL%MxcsM#dnU0r(utvw(ir(~?s3T>2go_8dKbKO~+? zBc=}&-zL8n>~h#7jd6KJ?v&&zY3V+eA(=4-hFKk#*{w%$xJGxRVOZ5xi@ygG;MMEv zt<11$gf+E$281LmrebdN@~pB7f8IUxzirWVYiACEu>tuC1fv=l5GG+R3rv3Ds~aS( zW`tX>TbzzvE?Tik@V7%}vR~G?m8E&nJ>_P?4Gt{JLXc@AJ#sFfV>VhKz8QTuto^~Q zvZpxoLi|`qTH%iCdCd7zO6*5;t!Qh931-*zrPZpn*iHGZVMAL%%wNFZmP+HoLp%XL zm7moHeW;#qZ#n-7}r#dQT2SJPuVgBca^AY9fu;^ zRS%DCSSukY3GRjPM>pA0N6*wo3XWZgd*!0S9{Z78aAKiq=Li%k?6K`1-$15SWuJas zr~9zm$QSEX^vaj*6zx18IYfh3x2=dD?n9A6zU}sj>L=DOYT4C^`|6pyEK%Ubfb}f^ zXk)bCUskCv#!UONqh!uyw#;YI0(XE1x_J zE1=5$&Kx^*;moVGEVkB|hD_P;7QLMQFx|X=>Ub4kkgklfgvOU{DSpJwP>3K`&j)*_yOC zm>zIPA`Fm5AsWTQO|8s+Zz0GXWWO*=5wJQCLw+}B?J)@An**{bc?g1VdoODan|^2XAKUjCT2@|y91X7P^9Z6{;f10&ol z7fQ%N=S-_=$eU#jm1hyznugE4ayL{~#gpH@=@yE}_I&hr)$>A#n5f}3!NJAtfPgUE z+5`Fv|G`XidYi*uG$8doy-0XFKnXwx3)be52qI`IpHQdi@SL${N8@2!2CFc8ENTd2 z4$DIQ{7$sa-(KZlbP_w~VRN58s3{fKHX;CUcYh^Q2wj#xSjeKxYuCfj>>v3m z95de;;5pIXT99JW;rR9TX1`5$$@E4LWi{@c{#X$*pTuCz%A0f1q_?cEPaUv5A_;(+ z0NV!NQQMv6%e;D#N4d+rnfKp*{2X?Rd57RcLLv!5L15PR_VzGGw_@8q9)IyN$652_ zQZ>{n>9&lIGr{3ngS4GVNW7K=rxSQVz$ErcF_kQ#Jn1?ZivrTqXJ9-L9JlJTt|y10E}1pc#c#SW?es;j)KLy>#^V-t@Mh zxKr?XPtLof5Ioj2K0Z!wnQoqNl=z>25n31!NKXr0oUOwxr>kY3%0Im=VSF9rUz~ae zN#m!sJ&&|@{8BorSw<$9F2k>5To!GBB68yzKEo}sGTq^xSiaD2g)L5g&~4FnCH{Ug zBu>Fk@Lja#tWwE0C-H?nDczM&gS;sxmQYsEuw#PeY;O`z$bMP9BK{>S)Q5~1cQBvF zw#PSwU3C*)wg0Gx8*oO2&N0*f@ana~s!1hJH-PRv*jpx4}L=;&`VF*sC%rhF#qme_l)C@n{o7hk^vM0_)9p z19gV5B*y4?BXM^&R)uJ^{Dv>AP$%H)I`2HS9z`s}Us`u^P)DF%fN_BaA6ROzUcJ0? z$x65^gwaEvmNNy>OqBu{yMD;xw&!1FbVSK2($UPIx6GV~UAI`v;5M=;Ry)!%NrcSh zu%;-6Ty&nF_Vs}5SPX{>T}C0s`Er@w8Fa<2SMT&7_lK_%g`2pDD}H605?7^1IFl6t z6qeJd=N>ih6#0Gio~&u{(wdiq+iBuxY$6RX6tSJ^SN_TKqK*Epr(+rHNH)RRdh{^5 z5-8%*!F7SrAb%URzq(&z*7$n7AFPt5I7YZn%pPY2*iuYWUUpj!!{1H(Yf0C77pfKH zu0`@mhf+@n?*3r97z|$V|Jg;X+vC)c3^osJUo^-~cQ+@u_{RG8ZjW~Uwra0HU+k~( zga&DM6|`6Ia$%yrbGD!4^ix|0rN4^(d?Im8nmL+CubuORd|qI#z_?a>xSe21-mhjK&7^oF^t_cw?o>v*70qrD|fpXDd5Q*Omh zYB&4-&JT_h1ZhaVR+cY%zFCEsPR@-Iu`6B0UOckr9kpUC%MA7@Z@<@cyuy`V$|d8@ zch$-Jjb0>CN7fuDC#W1>%e%8k?hkXf#I+Sf-p{GEjkQoNoqF(3G^5Va=8jIfGVBru$TUwCdbz^uAoiuMwKh z;0n6rgs#R$!dC>;PQkHL*iX*T@5Oql56{1(zZh(cCqC|)Uk5>Oq0ad!GFb2!u^udb z$b$58?&4bcw`0?4L3uNt8Uw-J)%;D8Glh4nsJ5ivK?iJ3`~F z%}m;@5bAHvFj&&dIm%*Xyf-Ct5zi#*wlBygf&t_BKx z9XD}I1Ku;xln@Qz8~#XvrRO!9zCMxD0ewfSwab&dFx&4pzv!QjvFVd$N$i{=v<@MA zpv!%6d*E(~%yZZ-1a9C4AZrR?3MGVV6AaLZ-k*0~iSL;tBFrHS7k6EeXUb4MCcZRRP za#$-vLf_|Nf5@(vzZS*bd5!%E*kAgD6F|tR#Eyk*JV$tn8AK?7e5nieu!6 zW3Lkj$2#`-->2{I-{tDMp66=leBPh?ec!KjnSS1ujY?=TuCNt zqo5KkJipxJ(&{pO>#z6vTu*z5dg88DRfL`)POQu&4klm($6^K|Dpx|`pf-AA7HUc}Il~}WC!r>~@v&|B0%0-z&0lcsk zDR(Gg&S*)|05IK(O~w;>sN_4k7u?a_Ne3>F(E;B&3Dg@{(o5`ATBrIuLT*>vxV>ny zcRpG9>%r0+_S~@)&-6lcpKY-xy2jRHT>mC_9U5$fgo*Vi>%4PUS?R&K3x6m8rh0jp z)aG%`5jI2;GfFuOMQ8naj=~6exxMCRy3<*tLP3xcev0Vr?QPwjRoPaG4fCAoqnG6w z0bfypal=p890)=vhTH?2R%l{L^%y>EaeGLLy@bun%m)1*Twfs6Y6jj^A>Ma6J;x3& z#xsO}qPlA%_1xEN{A*eC4`ahG11jwzsc0OK0i?1EcCOV`5p{L-2Lg=t(Kg(zh(l7* zClT*p@gsQ`;ca|)F0btNQOpgHf z;&!7uoY{FQQQ|GzITSy}gthNt{o>GknxzDfi1_JfKhE|`iFe8uWx5?VmFu|oj5P1F zT+dl~I8jJ2{^3L=tMO_iFbA{SBFNMn=R*fdJsQR9G6fLhL+#1ZP zaEfK(x>d}SKz1I9kAs+raoA@EyXvh4AHE0$LlLm-P$7Z$8+m_2y5%59^|0=b?OqN2 z(=yK9T{IO!u+qRKrqYWc1a~EbbH_yTMF<5dZ-&ysYzQP4F!cbuO)6W4qp0$*u&}bF zn&0aIVXGixhSNkMw{dbuq<{)?GT_HNhzsZI4>tAhJaplIW{3>hw4&cp;dE2!7|>j9 zIg2m*rM(AHT%@(1Gc%O1JOxCrx?F17KjF26D+yMbFm3OzqrV?c!z2UW_xH(bL5RO2 zy>8sms#1Okm)g6AQ)Q#Ky0wjD(s6$(9kfpTk(}-l$?NpP)y{fYmwWJY;T%xsFIKW_ zew>9NU7H81j_9>n(s)lo>q%9gDS zmt)=L-+QV^(-SnaOBtWo7iegbt@wY|q%k@M?;0H2(<;FO3xZ?@g_xU_T+K?AKM1Ns36y->8#@I@WCguaB9F5>S2F*4fpZc(I^T%!0yWrfP#5 zkHk>LFpO*#{Pvw5xb*^SA=s7M0Bg1Yy<+p-I15ZJ2scUlAOPQ|a`%tVPMW;0a#C+r zS9njs%%!Slu#hU*tVu!eE4&B))BHe$bu-#;^EzaaOyuKrO<%gt98FBH>j)#?y6{r5 zV$HkObKl*fiW|{ma#$+Jyd_|=K`q^>Rb0O0r>q%z^=etGH0sx(Ciffelv{+_TT3F5 zx!<%52(%bWnJd)7cUtutZFRLz%e0PJp0q#xm7+;1QglJ4yIg0@cJF()?GhK(o(wY= zqE~AxIefIcn2`{p*JXROyyi6P%p2obAtzN}W?BzOX0fK=W1qWUr<(W%rDxB{P;KZ+ zC3j(@E69TOk8LZ0%K)x0F0Ry7K3)(8SQ@|G0G6qy}R+%G0q%$oeXAvPuU#k$#xF7*>IK{y?;klwyjq{O^5u^_DJPVeO0HgX{SnH^(=4G z-Y6e=Z4bFdNJ6GTPZ4q0>O7J$E$}VT)Aw_0UU67)iL6$jW^~rl`fdl_S*ig#ejw!rO+_zj_fc!w2U6jN4&igA3xZ8W@wK2VEWqyGclN2uDM(D(flG&MBlNOAr6`z3JWI zFPaRe7v8$3D^6wNC@da*7QEd;E|Us)p5m9M8as(3(f!tWpJ&}TXV8n#BfO3Lp=dn$ zD^>U4O76v*k4F4wY@b=uTL&9HUiW!AY7t90rq{gTqe@|ONM^_1^5>xtr*6672nC@{ zu#?!9#?2o8T!-Q_E#baUk;|LjX*ZMfQnI-!7b4rK6C{N-n$*RTf)M0e&Uxh)dKvP?W|3G4KkOLdc%aZPt9dP_4^^jXMFn&}xrN93R4>WGm`c(l ztnTkPLqkN;2_79Z9K8V(pPS%VLQzE$TY!_pOF1yOffmqB5Ehe8%n!Gmbz!E!Jq;;fp65t`4M&A`oQ?Uw2aYN5oFxl|p0A7y^N@FcZV z!p_iZ1`ic#4R!p>Ppx^EEBwlT=;Bv)dvnGk67FTzd3UjH&8)_ z1l$TF&JY(44@Qx`Q7_NU`t&^W%=HuU9zUPwQ|&QlsqNc}CFgb3onvEV3~L$Q<0cjI z`UIby^Q)v#tAQ8rB?03E zw4TsM{@d;Y2Yb8I_%LvNefAPyQd3Q;YKQs= z6BAEu_wL|_ty>?Pd>8llg(^o-*v8#NuD4^*<2E`f^ba3%e%fLA-JG*-Iw*p3jJ)Rg z<9hpa3npt!IH)VxWUn`VGC1jqSQQ>$se4iD4%%x*`e9k(s z9a@=7l@X8u%W>ldJeNSgnxx4PmcQVo!!o!ffJFmb z1YlW?6R9FZ=;|QR8jeHbQe97(nl(rNxUz$-)Jx()vka=)Sxi?k?zdOGi+)z1P#I{x z0ZxH(-%J`2psggSD*<$awlH?dQb?1W7?ZQnS_QR*L)Ng-Q+x$_Y z?ban7UoCW>`0dqj7w$^6=gN$C@7)hdce?6WJ~RAi&2yIfsuF50)?Ki`Bpu&<>Dz^p zt-84J&7!m#a8Sd2+8v?t*{PG5u0r8O*7GXs!4=9O9mcvKpfmo#TYf9=08n|GK@G9* zHk0kSN4Z=v?YX-6A=%}i=JJ?E?ye_(7~F|~G8U?T2EmUn(H#KQvb!E=tU5GSF}IRd zHIgv7rl$^_Ig%|0KLpq81>bFovw&?kjmPxS73A+0fZ}PEZ-acO##(r;vYi;v=YFH5J3HRaHww`CH zptdZ_vAEVpHxRc8vzccu$NMJiY3;o-$6|+jHiI$NdjL{nXTn>}Kz&~mNZAKdes^IaSYP-^E&-Ef(P?Ri9tm)kuTsw>`Vk%Qi|4h#?tT&)<5M3 z&!Mnuj##ef;+Ev&prpUfXOjXEC*TNQ*7wLwEF07!uju2y9OTpLYtcu!h=DN`Oby&> zP(w(WWtrpE7x@#{+OoKBrY*8w?G;<>bJI7{yvTZcT|Nx!AW=JD|Et>&{LQ-$&5m~H zO)2XCX$YY6k3!=hzC(fH8sDk^1!2J_T(~?`zrGtAnrtH$2D$t2UV@SxLWUM9Y%6@t zWt35Ew;+Z}b~!vNI6fPJbT)&|I zjZ2`fh6u@g;*)=Q3PAU^z?Zow4dr-^I7B-*0Bi`e#SD1xZqGBdlA2iv!Guz-Q0~ve zY`!^^6Il`(^o}QR(l#HyBwy$gWLOjCO=1WM0oMe zVNC99(#kLTQyMh#*5?_tNVKouS19h#Mw5^M#(c8CnjFlm?#H+w4{Yu~$RASbIvyyG3wf>`>;SUR_~Y=x%s z)`&ce6@fcWKd;bebax2l8tE|Xx3#c2j6ds~!;Y*ru4OvL&^CWCchzUZZ#45puP3^G z%Z;aJeaUf8?SmG!TTW_hn9j=pm$n%>Rsx0!!Mn!O8SsHZ;v?{)&2?%@0X(aj29GZk zo_aQqI|9?7!ngOzTIY`oymIZGmT!IeA@Jdzd9vtLQai%Rw=DpaI8^Aj8Gn7lVmVv3 zPS#JO(P&7(Hrt=q@K+fp(vexuj0+{nzDRBTxX9I9x4qkOqkdy|R$QBEY}fFTX<=1y#@LBCh;(Bsv3SM-#yi3`r6bT2C!D-?I3F3vzpVIue%O?NdO(2Z;4!dR$a?MsxWn-utqc zX=_r@ujOl##JI9$yGv}|saot;deuAdjhp&U{8i)YL~xQxkI~&{?TrfkZ9Ne~NY7J? zJA9U?!PlwQFKjEOt>XAFqV{o;e62j9*~qQO+BpI%%MYb6n|_0iPsG(zD=^;`_L@6R zKec7nqPc_Ws=fS<$-=jE13oQ>ZsBlQWR^u&DFx>wR=L2pr9VvHupQCHmxgnYg zMN?3g%dI;Ah)$ALB(34k;Aaq~({%_9G!W`Gk~jYa!T~x7aR8X9+B$?DlJaEZC6SGh z$9cbo)%S*^G#UsQWQC%7$B(z?R-fq)ALlp5+WBYED^2f1Ea(b6Rv5g>-i_|}ud2Ps z%4+~mZ2IARI%!w$M+mcoJ$58Lm&MF`*!%H8XF{Z_?t=<7i#>k!!vO>Z1co0i84Qfq zm2-1jJkH7I_Kn}h@0Z4#m9g_XV!U+ZBC%B8y6jC9uP;jXc-rlK=gW93rrKdUE|}2y z)KS|sWk&aDYtVR}!b5b05#4Y_d?nU#)BM5bFkGM=j^^lwcB*aJNwU-$z4)x$BHvC+ zZo^&JWeP=Y#le)VN6C14;0tM#SEL*i1b_1X{IHxYbQG7k;2s6_Hz{Fg{B3Q8 z#JVX)###VQ+cwDhqO!d}aMs$|+B97IFVO@Hbr8tMD4?!FU3sA_{tkbn&|%qsMg~=u zy`{Eg>1BqSKB_MstE)P=>?(0@n{VjNPW9q$(LXD1q-Bn(R@iJEHvs)3?zL;?75FPxs4wH|@S^2MV zf6`Q|kZXAgig*f4g+Xa3y~fpNt$KCd8}0w0#|S++fu(vG zV%%CGfq&2`26Uj6=hq3*R*~D-mpBojA3N;1;Bb)zaY8ROZ41-{0nJo(OWUwpVTitx zE{eapbG79NL;Jj%g}yusU3|%s>IBOwMDl%1f&2s#TL-JDl~w|PcIEb}OH-XeHI9R@ z7F=gQIcY2EG1wX}Yv$*1LGU2F6e}xd;I09hh191{vmL#KKKG4opqxqXU}Lo+dHEinh5*IoK8 zS*SV`=@`o}CB}=DF+N!D+ZO$vojX|;Izs@LTZRfZ*nij!ILkKh?34HIMWC6oB+>8w z>ZE*}NwyT=E~j2QKuFk@pbGG(QZBarb`>y1u0Nf)@8~~SeV`xq3FcI0ruam)6L2O; zi%0={btaF@peD&3DzN|28dtxz&xxTm^8OX$|7gF~Qt7vwe#Nw{Z!wKa>cA3_grbk{ z&xwQV5%@C`%VXT{YcN?2;>lfQ(-_X2Ol2C%_D|Ie4DWcmpOwI@1r9HOUH~<{+b~Y2 zkK*<`ufrW6qhSGi#z?WSa{J%qCcqgb527Ymwh5gP@HNigF2ZN7(A@wtjwv5GCKOJXe7ddZ_8P$)(`_4w|7`6I6K^7|R>63gKq`JyFZHsDQ5jq9wp*NG+&#BRB10yi+}9lYE}wHhRu=+Q8!13d+qe|WiO zLIPmBIe<;T2qy6PYf3-Q)fV^u2=xJ&)!#(9mRB#=*qz=3N(I*sXq0R1S2g$l`{S7- zM`y4&oM{RN7Zg}fvtB-q5&#MsjwTpR<@H@oUR8Xz!nwnJ@)IbGA~pJ`J`d#FVEIuWUnw zY!mphOCvo5Tcbi02CN$+A`dHe&R^j_?~eIwXfY=;>h@q3BT|f3<-rMn&OY`oHfQU4 z$%=EBdO@TFV~eTC6~>ER76dsK20kXy#9xsEQ^TxHNki58r3iN@lI zJ$4m}wbb~YcZZiWUd;BGCAZZY`tY`J;3dZ#!|#1jXf8>5aq!}x6tfAS20XR@<%V

|=c={`b)HWAEXy0Us}b2m$Y>)o zC|})Cvmovkz=aK?I6Q73Hz4JQWbs_dk~_G1=3*Z9vLfEpF664>1yU4Yk|iYOgNRR> z0uWdt2oQ4H`C=@OYZRa6|M%SjKKR2w!RHs^{UpqbiNFm#)OIGg2hC=$iG|>l5>o-p|M})EJ3njdrmiRF( zekr`n@-;{j*Fgv}Lwohy$z|tAQt$?p?xjL~Sch9h|6c#YW4^qrHMvhPkWyko-58z` zWC81iL0kiIT>5LD|J~N#VSdCO0G{kp({PUNMD^>r>R{cYcJbd&&fW$e>1)FyN&XY*p<00H+oYC$6)VWw9es4} zPmo#sJBTJc$Fbxl6(slEZ3Yom(vdCH!-&ir$JKFzhUWK1RnIX9@0MnqlGac zEEgNq}C8%#fmTUn*uIRqhT%uJ=w+)cCUO~EFX_o3Y}Tu3n{i4TFWbU zb_|{QDDS1J_u;tSMwP$eQ5J>L-kA?beW`ql_G--;hu1R>cho_HN6_PqpCpCW%aZWbF57G!hwY*ZMmDhwSM&??mvyph}`+1UqIYQf<5!$a9( zfg1UsSx&9^9GVa%j~g4N@kiDzDhwhyhNAlc6t9)8xGs~|>0sz6k+V;)IjokIP9W(K z*bKuj7O9Cg_feXH>VHLImvDh;7x!V8PElQ5IH(+Fl3FyJ9{G~JA*PbYR8}Fa=MY;d?S=R`Lyp@ONBu(PbpS9RV zTjRM^>{?au2QIf4d>oH`U+ zsYoTD&+M@|Xt6VFJIO>NXqLwtBAu$FajTbB4nLH(O?_?(W@mV4YhyD3YZja_X#n9! zL_kG@FWgkR0PQCO9p_#lGv(ai2CXOe*E|K~ROvqpYOYBw3(7%O4Wj*cV18cc+Iyut zI#fdW>(cI~Z+Vt?$@^wr`ggWessH-is)`Ao*v=~`n1-y??UnCzMdjtMO;@Fp{Q<6t zw_w^7Oql+Vmt5}{WyasybLn0kRTX#7$~I@lm7{o9T|>i`S5$N(^$T$6NJ&Wvk#i%H z)jY238H_(#KF7XJ<`B6_B)Zzz*pNy1>$=q#!fjXW7iXSs#@Alug2UV~-YP=Rjtssj zw$=0L!|hU1$nYdwq_vLN4Wc!~a842QZFD^^ZutBrT-K|X{JG1LozAWBTE5Ls_xBv^ z1QuNbs?e)W7B^3?1pG9LtN&jNMpKuGBq7(b`I3Jk-R+Y;E_kYITiskxl3+{vdfUaw zRv`^}6ar`|fH3X0C{CUyAEeVOJw;vlZK5V6!yghrPn}q<2?*G_*mr^Rzb95nreI14ZJ)0o zGG&p;u%0_t=gz})Yu#5cGG7XRZOyx-eMC|n!IGECJWplHJjt)E%3&9!vp}TT`+NeP zyT|ql2Lwu@5KT}YM*M zU76Ou*6!D5q_}oHZ@Adk>2Qa7ofBnO_Gql(!4;2SiJkB5>pS9tgpJtHj5dpQfN{VW z=IppV@WK_A$^~=fsB3=hUy5ly_We_?p|*MI4k*X}8v%F@9%BEzi_p%5xu_$7SyrQI z&HtcKEtZzL@2dE#gd5CPLA?$3OVQOoz$flUcRd*o{+8rWM6aO7xaRajpi0q>S(_Kk{2 zNi2fEb)1&9Vj;Kv>p;Eu!)`b`Rw)EkWeO<;$00 zaDn}uz(gpcC`lqt(mnGf`(iaa_FHQ+XF4Oz+F9w*3REf5^eaQL;9m5sCqF+woHG*1 z27fx(e&Khdytvx_AyR@NMbT+_br>4xva*{HoK7vbbL4qkIai=ad6O33zV|}2dpazL z!PkIRuG)Y0V0Oo8-~8zBuAXm;Q>lET%d=)$uy`A%saRh)IlH!5|}SFsv+85!-|o&3Ezqk@_|N;pEW zMF?A5sG0rL)%B*1&#@6^{)A3IBTQr|4Ui5-&ipXuhx#=T4t!5jdyE6}2%uETWa%LO z;E&cx4@HBwJ5-Cu-Ty6jaL~_mERq1U0;0k}FY4j(*ECCT(8{o$XSp_kCyKGEJU7FO zqae@QtEk&t2cGUvpvfF?-7L@vW?F@U9vC`rTGx#bu4460quqMZT))1|65t`6of$y! z({ix41%JPRrZmdmF8hk2koltfM~8auA<*uDipbH+i?mWqB4X5N+$*K@?NqXGb-nhU zPe#DLIxXeCkzN~jFNe>}HMBD+EfTv#Au%2%9bx7kuIBWttHfejC`22wratvn%6}=9 zsuWVhqz0+Wg%#VbUCN1IG{IQ>-NTEPU9b#sUK>l{9jJnLohivYPUgkz5Y})d zRLJAZ_HMi{bz=x4G*b}q*7dBPhKXaHNIagNCk+X}(aD44-mj218L-qX$d#1tYdGs*(_0Jl!P0`nN9cj9Mh3(XXWc|jQ_)B z3w|Zgnq=K^q@s+XhCRP<9yTcx?pT6r@cyGM|9FdTr+dQWVGg@LAF`GVFL1r=q&#o< zW!c}h7eje3f!p~)+a0@i{pA9Unx|Gm=)G9gc^JTUSS7Ir(K>+ZGg8Smb@CcKUsW+u ztZ+ceT3Pf54e>r*VHWiJd-%Kk*sP;*@tynfM4gVky|!8(VF9m0T_)A{J?m{rVa3b! zD=dbV5ie7&Ya99!#D@GwmKi{0w&i)=s;Mc7>yqZk)Av0d(r!D-r4POZ-yFT?(+bxL zSi;Q#M|yqXG~)>QF^Y>PD^EY|ljGU_Z%3UXUvwMmzdm;#Ch7_^?Z!QF`(OSa9aynw z9S?f{pPwK|9~LkzE-!Q5@0T3tFCG)rJRoxFGH@h{2lUM9F-qT0yD4I+AV}6d0Couy zxJN>wpru`tZnbe^l@i{{F-E-DZVR)pDt#MY766f0m5$RVmdEPCh(w}f4%hK8n9fH> z4Hp*|*(1!DI&%brAovd^s$hl5X1d>^Q%{LyjCKO}FNgZPM!yG(4C)+yXWB=9{jsjB zdBIz)ui=-db=TD}orQ7{{#))Iux!dM^)G{JZvFZ!+fyDQ5ZmG5|3UN&F4!41y40Rv z?9wvEB6Jg$*XuoeB#rYBar>6D|3#VQD)ISc;odIF;bkUh4GZ%JmNvVDWtQvF#cGm% z^^!u^t`W|M=M4XPkFS5mcZu}4Vtj9R`lsQ#RqSaVU_3fK4q>_9SlIW;o)BYem5`L^b)EfNEj>RrKO~tR}cOX z(Mduzji$xq2BjT4ZBa`5zE$Liix!#!LT;V2#g8nXXltk76h8GjSS&9sRpl)g3n-@H zB7Qj*bt1f-l5>?f-*i*t$F%7FkQe%mq=pFt&O6canS&ky)>|0v*8{9{dG^3c5~D3= zog&cZc#)%#^KR1Pod||LJz?ZWrMI~vQ8)@F1~olr%|rWWJzaaRs=_oR3gBo6X_>?q zH2iF8dRfvYOfPgJWT4eUu;l~kwE@E*+=zdMhMFqI{iL4IVR{qV{S!Snku}{R6I>a$ zjEwxt=YnstnHvgjF1HT;e=We-A4%S8e*60M!nxKKQn{Wc1IWk*ZlS*h=d0^62Ga(5 zh|)IqJmOe1x_sHWp0;(mNL99@_FVneR>qbWq<=3gEEsGa33R4psj?rDlamh~-^c*5 zD3o+LH&+UZLrciO=$`of{D#2=TR7X6I|*Trt9M{^0k}TEesfQ>|AwpM6r#RfsgBOe z1bt-Hi+E_MEB)pAPrMSu|LW-KIu_;Ge1~q|Zfzuq8%Ynm2nnHw=n!dE5WGlEbp^Ye zQ>yfaRoB85%Q46;58?Y_+#F98ZZC-nhJ+$Wv9*rOHF;%Ug(87cd7}s~B6ZgCWn_T) zQQPr`NaervWt5i=QhBtc^A%YbM-^k#WGqX+Hlg(pQN&dm%CNT|;Rw22FPd0h7J`9` zWYb(2;71^xKISD!@2xTGY=K~^5)>Y+(jEazOSUtf5#PUmr}ed_;VSkQeEAlqOrbWZ z@w!*pDW@R8gs$FZqdHagY>zu#8h`N3@yfk1RauVjyh00pztKrNN4L=5Gu$)JsZ-yd z@C^*Jdo}Qk-hU^}^m#($#9rF*&0erFeClmnSm0CF&=~dhx^by0h3PgKH8u6Wit<_} z*xk5M>+Zk(u$8WO##^Zo>sL;DY>C`EM5oi9x&;K%KFG)+0(|-n1 zr=8r~=8Em+JePma8_VfaYLBZj*n5sVNh4e$6WW(g=Vd6+z0*;=xz`pupq)BtNH6La zKSf*6yA&1J!nyVnXAVdK$TK|CxR9tSM5q9vm?9BTt$8X(I|n)^xI9Rw#yLC?#d=H^ zr$ll3$a1`&SPLD$$6algEoA>JQfjS_dnN z?QT)R-O#pk*Hm324gUGilc;KJ<}$fo2=h9>P_RZCuLGF~}Jh zsWPDK+2dnpXP@|{c*&Pym9BDO!Yku}g!ntn{gWPBlWlTL;V_EBm8)Bm*afLdq@`MR zydk%?ZYSA#`&4XJ84aC--w}#Hf{JNup}CIP>Xf zTvd%dOq-}5G^ZHPmQYtH$$Or5=2V_Cv$f?Zuwc`jU6)ocDrkto{cX5;yLaY3?cHMa zc-Kc;RFR!kf4S;YER$~Nd9N*a&fqUwFVA`cx`n4tM-ncCvcz*6#5fR4wQkqrxAxRWqH%w{^%PQSv(mPFG(EW#t^!L|65{1uc0O1jS;NxQ@658=GKA{xdd4TIGU5z*Odj zxyD~2!C_olTFHwHgc}p?Wdu?*p|>7ZHU5jMdwT6c<)$jr(HlCpDGmQ!29ov*uytC* zsYV0iLIP9|%;4Z?b0TpE)U+wIm62ptoEgZHcQlyHyEulZt?1c~Ym{kb;nCceRw|X4 zZ%$6^pvbn%jbrb0(aX*(pJi;CuBtvP_KQER*V?MuSMagD(#A3kr~cN2^Dc7NHBfQ1 zp}1Zl?Z5CEKJ$LYDc(|Dq{<<;$C^t73 z(xuLz(_{dFslU1~e>{@Ac4a*S5$2V0QzUM@#DBJ`m`zfy^toBc!)jTKPj7l2PR$Rq zRQ}_5#DI-knt=;cp`y=JjOiSsr!kMhP8Z8KsYl%9f}u;P zQ$7--#l%T}=FAxfL-y}TkQyilGCF*2ahlc zQRAwAuThNhgq_j-p%Nn%Z_Vu)L+o1#xwxCA8&6WH3LDing7q#%oCd;j^3xjPiH0## zp!)-dPhOrN02&_*grJs5p8d5ToMVv6CLj9vl9yeF--n#)`ifjR+#BZ0-BN6se?OUY z>B|h7`})j`pG5X>UgfBZsto3fiCEavn@X+~R*VINNI{4UymARCp@X}3>Y?EUya+Hb zz%|5AoTGbDmPBjSvCa(4g@9jyh=Aiw_6ff4UPmV=4V2nk-x%2+uid*sz8>bPHwj6# z24enJ?QyhEtL{|?A!Oo-s0jt(_{8RGI#%gMQfS#oga5d#v1_7^?Wov13Yc}+GYOb_ z@EvOmaaYP#rd%K+zNUd$E^NCbjrozWOm4ZgYL;|@Fr^=Fd)y{tulB0akMNKV^Tgqf zJp8v#l!cxUn%=A4YK^Bo@21__A;x|8J)&K&_5;Mzhp+4stu5PUx93~lbYJB_HZU$_ z7XDxn`Zn;5p>z9`Rnwg#+weDx*5>{lZq^*iTjH&TXvv{B)q=9(H#!B4Hxo7}`j(;x zi_|f`=0>z(nbsnAFoH;Wc=G|ahd~l7QpW8fg=tC=`XDR^^$t+L43a~#vRmhFmq`G+ znL=%l{djH+Ys0l?4J8n|Q|9RaJb8EWq{Cl@80b!q!L*LSFhcy++n1*+i=(Vx33QS; zy7KZl3A4tUaQbTv5^Ujj|BR2jW2|iJW-|2jIz0`V?->bdVr;~U%F2SF+Q1%pP;-JX ziey)TH`y7R*-P=PWf}E6qScHP9|xBWAWu-9g3dW{2*5Q%J&1P&B|7ObZm*{wy@MTg zm4rO8g>t>ti@cDwV!aR4k^AIv+2^8Mf@%9{=8tkZotST0t?F(dXgI10+eSHyEpDUk zoaASwisx#Nw`r(vu()q=+1GAp*Pz@mO@qI9@zH!XJGOoOW|4)zRg)6NIKC*Cz?hv? zY}|LFu1CChv|4(zOl>A>&+w%3tkaOK@YU(&&mYXfUlw%fMXh)$Ma_U-MN(6S`E+U< z2QKrMD+iVXKgYmDltyK|^vQZKV}N+q?#O;I-t-fZxyVPRVaHRN6}T_hI99c!WRWUx zTLFEZ{s`D~7{R+dpXm}VlL@)2DM^kAOwSMc& zQ2;)a-S30}mAUR~iHM@Ast{0vA&||r{;dyDl$XfBTnmibe%1UpO z+@r-QDo)mCFGABr@&2{n;f&+Sdr2!+FMo*h6l+-2Q}U+=)M{^jEdA5p8DJ#ol;R>~ zP9ZgaAO20LRCMTsEoiVvO(j&$H*nkjk0^$*u@X0Q>GCK}`!rM{fe@f}3?BXjxVPN`%&$+lb5Ey|i^#tOq z0epO^>aC**`Z^tM*F^+c9?Gf$E(RtqkmrI#1+icAIx6t0Qf)v0J^)@L)Y=J(a}KFs zoCQb%694=czflUjEZJvhG3~9IM~Y@n8_qUs>B)YU|6pb?TQ{?5uNx1DOoomCyf$z& zCLuZs^kVP1UefoOj^c?V)hfuuB_g7~%rl!%bn|{zdw*UjTGarIB84z9*0>X|f*~~K>A(C~+5w|V%XWWxgtinnbFDE`lQ5+}a<&|KzJJ$us z?`(b6!f;aD(=nmZej8ZU*mGbXmxpXf<2u&`M-mVzk<>Ka){)WCo9)HtK5SPIPxoe= z?|k3Y4J_aG#4*y=aS%BG>f@ORQK6y1nI4c=F789b zGcYD3%jExvH8>@>HR(bDJN_!DWpgL7KaP`CNQY;%<=Qt6++#l^AN&shC>Rt9swQ^X z99RJ9bMW%2{=ITx#jepnX`v;T=d$!0#FA)YDlsDwr@_N8@zUjT5AD5KIk-B!EJ}j&DcxYSm+rv5^GIE{`Vc?(w!jsA|#8HLwOR{-Xn~YJa*oGJ7<%5jni-w*?jTX*z+4?jogo8 zJukSVThVvbbLhrQMWx6MuRnzwF2T|--uFXZTXEzc^_^4~C7#=;)(z7Ez1kON=k8DN z8`DzhxkQ^|=;_VtHkdgxaRJ1-MJ~ICRp7~nx&$BW|4^5N>x%K&gr&W+Jv%Hjz5p{| z#UbaB3+)UbHb5tk0h%DM9$9D8uuQka&C!A|6h8Q+L-B=s=I>#A(SEUj-qB}?PaNqX zB_-FPy#l;Vl00B=$6%{0i@M@8bNF5LZPjV8V6 z@MLN)UkX0~jt4Pu@qb!O5K#qV^B4By%Vp5cBq#XxF1`Rj)&<7tV!Dl+7?Jw|KHAUH zpMG>c_IKN|Q%|@c=P@6t=0c!6{4sE!cZ!YAyPRn)Vz};O+wVB&6m|!HYezTqj*VQa zW;d0p$I98;LzcHN`kQf^h!tHTQAcNdFSl;Z%eE?RxexPa!K)oy<(a{V)Bp`MTeY8@ z|KUhn)3%*nvG1g8{pS2$d-aP+`PY2#I4oB;yO_p(eWyOV8vEvPpK060Ti!F`EtnmN z`^e`c?ekFv0N5o1QP5MeMyBE$&cA4C*cpZ82!IPRZcC#f3JEF|EQ(3R#rTMeB&fz) z*tNa{=_|Clz{tSY6Fb;KkU=JRBoLNiQb{e5gaO|9pStmVWEpr^E^#+Tu?(dzG_cZHBsPIQ7iNvy6LpR6!4*+3=Rxa zf|U)+`>@8PqTpslS2fi1e_r$_4ZG*HpFHt@VChr@3vpLqdcZAfRKTc-*x=NyuF}UC z8Ak9B;4g9(4CC61oW39V_DZP3(V;J?71uE~z6U}C$dd%sbu>;A+U^8-UDp_2vR^gU z`XLuS_b4g|M8@P=i!NNgj9m8o&#+FHjbB=UH>70P=B!SL1uKQuh&kKyX8z7KZl8YQ zpovtqjP~}uc#F365#r@^)zLYn4sHeKx#`hIw-PbA+YHQxcPS-q7kM1P~t@dlkwZMSK ztUI?E0>#emveGEsE>)!2*U=wkTE?xm)~g|$0SIH%58c(@YiY#>o5yJ4HxNA*y77)f zLNbina(h2Ji#s}%UTJJcYy09W?OrWXrRP+YJ&4xVQsL-Ma^D?_+v+pp$A8;-BSyGv)<7=Y9Ne-b<-)^ zd<2e8lg0V@`RvYm$jgEYe6HE^N-n9B1txK>D;cN^kS~nd4F;1+CD_cN>E^9pdy_V1 zxF*>rrATQY_k2~Bgtvr^=#kL@r8hy4mN`F&!NAKEjcAWFC?R7rXqH1xC3nq@1U}Il zWa3Wel1vcFTx+q^W%7;ZXRDm}az0(8x%BV#?sEb9jqB3YpnAC}?Xg1U58)guV5REg z&fDd9Y7EFBN$d%{G?OWICoyCJ;W^;RXg=O1J4g`_`TVbwz#3nqv(I~%RrtmMHuwoY zM#MrPR{)f^!6k?K7(3hfiU|A}YMD3Y=_(5O_<~@Hq0_7txlwC}@J8+7i-@|vEH2+b z4$$nHCllAXTJ>>vR+=vLTTtqc54w*esnXw4GkutvyJI;ThFpICH*!+ulz8FKrx$&; z;t4sB*AER8z(#IgN#j_GGVW&K@VC|{F^8S?;~PE@7NP#byq^AG|L>Vop%nlpU%SBG zDLSY=rxAswX{m$X4z>;eo^Xe-!!lJ_4Dyo;21)e&{D$<i3Eh2h9jGOHzAC4$G9(S*Z%?M78V z9PM)?wLs^rMdSMc&?RhX#PbJJ{Hz|UbUbG4x5MpsfH$808GdR`C&1Ug6Zxzq%_5;yU<`&%s;xF2tZ7HfLAL(i&VaO?S;jwDBG z_+3!S!taAY6@JbaQtRf$%A>ymB?09IC!(bB&a~)n`Tg0=ur<&4G4Ic>oS+=1272_)O z7Wj@4OrQXy#Z-<^LB|H-j5;GibL8vVEcM|zyqU~h#A2 zwQkW$358RC1aHe5HP{$!3;gPgX!k4HH5>A!?qnHVo0u4vZIa&%ug4WzqH$~a1r@tW zX?tIMpN8DT)F{NLj7z;d0>B>P<0fHp3SmQx3ycr)7}xnC3^DwnoFi~%=-6a`%+2xq zUmS&6R)3XwM*U&WQXJv*L5i*~S7%w;e|A;xzhtXsa#i&769iC42xN+fD*8%2zlBuk z(@RQcAq*RI9N1xv2yz+f_iAxcsd)6Ry)q~MYFf? z#4UETGtkHIuHkl%eBZH>AL&;H`7<-4W?+`NaUa;|uI+WD84Wi5&4c8?cpt+rV2{9us zj4rQ_T`Mo|pRas#cTkny>mc>G^{Q>O%%Kcxq+zizO1P7@=}CdomhoNDyj{Ik;ts}L z7JnofeOqtBRc6CIX{FPd>0m~eyy&> z)*VDDo_F6bqQAX5B{)TpuQG6BJ)!wGNj)pyADS|l5P+xpa4yiH(5npxd21T_j7}TgTlEFDaKeNI_2{EpzOmrBf*v*lPwH?Ys<0L zoEnRLzMX54B+)+INBaSMouQmI_V&}Hiw>@B;mSAqTQNeNYtq%DPHamcytG88P0q~x zu*gdoEJ=qnEz*lgBFetg$=#_kNK9-*9P- zpLhcd=i;k;yeNfVqPM`F2(b+PEk-MW@JRUnx7=GV=uY|8YaNPOS18@^wJ?m26%MQ& zPmW!x`T2xO@a-AQ^^Y-Yf`Pd>*jgR7%G>@qSvqgFv-X3Jj$60r%ePTePjd#UqaLel zGK_QoT4Pg+-fK1gDxDCN)uq6i9H4uW?cQ#zcHY2Y){Z0&hF}iRf32%R%G@?Z(aWe=_Z30~{7Lytrm=+ySo%IlYtC+8Z*pEF>Ty?uL3Q8*sfC;^M+ zu(fOmHRwBc2DsdqaDYzwZ<%$-6 zVo!Z8baH}zOD*dWd`M*S%&qVTE>{EY12#QKjgut*teO3x_xXnh5@^-tdfJ&oua|+E z@{L+=2=4C*4J*sEm3APQx+vLy!a?=wb7K5}AHdZ^2Lp~?UVJC4NP`w(5i+Qk3$!mQ|2_f@^;4*lj?7Z@=)Df>%i$-W zjVu=UJ~ozCQvd$~{sIC0apBISSvxyBc=hU)+dErY;jOl5p~I@{Wyzr?l@`g=V#(Wr zMR?wn@VzbK|9zm{(ya{rZ{ne0jm0vH^JRsJMfJWcd_s{mSG5Pto7PWy61@$`{*)dr ze5R8mL9f@FyC1h1yo}qwZmT7r`K0 z<$btIi+uK&)K7+jF^-SdGdBQ361ZJ#p-{NAyK7h+UrmGsU%+*MZ~bz1c7|H5=Cc2X z_guhr!Duu>mSuCU{{im~N*2i~l}c_edV)k+F7mBJXVzkUk+uF!;3K%axBQ>qb5Xj# zzmLnX+}?{$DQQcyA^Q zd)Ki@xR8BriC5MbS_JY@1ZkS0R;#&p50i6prZF3)Dr6`yb*mzN}3Bx9>c;z_y4l z|JGK1nFLU79jL9BO!CKV`E>cdddYLRFy=!dGwNT~TK_h&XuK>7_GR!kuKT~l+nTeI zTE2ti4|6Tmx(sZJUg^la2c-)OI(oeDeg)@ zi$32+3=N>AiC#@~_m}w#?ZZ+nwV2LxPY ATE: %.4f" %(results['ate_score'])) + else: + print("==> ATE: %.4f,\t KITTI-R/t: %.4f, %.4f" %(results['ate_score'], results['kitti_score'][0], results['kitti_score'][1])) + + # save results and visualization + plot_traj(results['gt_aligned'], results['est_aligned'], vis=False, savefigname='results/'+testname+'.png', title='ATE %.4f' %(results['ate_score'])) + np.savetxt('results/'+testname+'.txt',results['est_aligned']) \ No newline at end of file