From 3b3ae560ff45dbc7f70c43a4ffa5b4771245d2c9 Mon Sep 17 00:00:00 2001 From: chunxinchu Date: Wed, 24 Nov 2021 12:16:21 +0800 Subject: [PATCH] RMP220 1.01.0VER, release for first --- src/segway_msgs/CMakeLists.txt | 76 +++ src/segway_msgs/action/RosSetIapCmd.action | 6 + src/segway_msgs/msg/BmsFb.msg | 5 + src/segway_msgs/msg/ChassisCtrlSrcFb.msg | 1 + src/segway_msgs/msg/ChassisMileageMeterFb.msg | 1 + src/segway_msgs/msg/ChassisModeFb.msg | 1 + src/segway_msgs/msg/ErrorCodeFb.msg | 5 + src/segway_msgs/msg/MotorWorkModeFb.msg | 1 + src/segway_msgs/msg/SpeedFb.msg | 5 + src/segway_msgs/msg/TicksFb.msg | 3 + src/segway_msgs/package.xml | 26 + src/segway_msgs/srv/ChassisSendEvent.srv | 3 + .../srv/RosGetChargeMosCtrlStatusCmd.srv | 3 + src/segway_msgs/srv/RosGetLoadParamCmd.srv | 3 + src/segway_msgs/srv/RosGetSwVersionCmd.srv | 5 + .../srv/RosGetVelMaxFeedbackCmd.srv | 5 + .../srv/RosSetChargeMosCtrlCmd.srv | 3 + .../srv/RosSetChassisEnableCmd.srv | 3 + .../srv/RosSetChassisPoweroffCmd.srv | 3 + src/segway_msgs/srv/RosSetLoadParamCmd.srv | 3 + src/segway_msgs/srv/RosSetRemovePushCmd.srv | 3 + src/segway_msgs/srv/RosSetVelMaxCmd.srv | 5 + src/segwayrmp/CMakeLists.txt | 81 +++ src/segwayrmp/include/comm_ctrl.h | 109 ++++ src/segwayrmp/include/comm_ctrl_navigation.h | 180 +++++++ src/segwayrmp/include/segwayrmp/robot.h | 169 ++++++ src/segwayrmp/lib/ctrl_arm64-v8a | Bin 0 -> 403440 bytes src/segwayrmp/lib/ctrl_x86_64 | Bin 0 -> 378600 bytes src/segwayrmp/lib/libctrl_arm64-v8a.so | Bin 0 -> 437648 bytes src/segwayrmp/lib/libctrl_x86_64.so | Bin 0 -> 426104 bytes src/segwayrmp/package.xml | 31 ++ src/segwayrmp/src/SmartCar.cpp | 27 + src/segwayrmp/src/robot.cpp | 489 ++++++++++++++++++ src/segwayrmp/tools/drive_segway_sample.cpp | 364 +++++++++++++ 34 files changed, 1619 insertions(+) create mode 100755 src/segway_msgs/CMakeLists.txt create mode 100644 src/segway_msgs/action/RosSetIapCmd.action create mode 100644 src/segway_msgs/msg/BmsFb.msg create mode 100644 src/segway_msgs/msg/ChassisCtrlSrcFb.msg create mode 100644 src/segway_msgs/msg/ChassisMileageMeterFb.msg create mode 100644 src/segway_msgs/msg/ChassisModeFb.msg create mode 100644 src/segway_msgs/msg/ErrorCodeFb.msg create mode 100644 src/segway_msgs/msg/MotorWorkModeFb.msg create mode 100644 src/segway_msgs/msg/SpeedFb.msg create mode 100644 src/segway_msgs/msg/TicksFb.msg create mode 100755 src/segway_msgs/package.xml create mode 100644 src/segway_msgs/srv/ChassisSendEvent.srv create mode 100644 src/segway_msgs/srv/RosGetChargeMosCtrlStatusCmd.srv create mode 100644 src/segway_msgs/srv/RosGetLoadParamCmd.srv create mode 100644 src/segway_msgs/srv/RosGetSwVersionCmd.srv create mode 100644 src/segway_msgs/srv/RosGetVelMaxFeedbackCmd.srv create mode 100644 src/segway_msgs/srv/RosSetChargeMosCtrlCmd.srv create mode 100644 src/segway_msgs/srv/RosSetChassisEnableCmd.srv create mode 100644 src/segway_msgs/srv/RosSetChassisPoweroffCmd.srv create mode 100644 src/segway_msgs/srv/RosSetLoadParamCmd.srv create mode 100644 src/segway_msgs/srv/RosSetRemovePushCmd.srv create mode 100644 src/segway_msgs/srv/RosSetVelMaxCmd.srv create mode 100755 src/segwayrmp/CMakeLists.txt create mode 100644 src/segwayrmp/include/comm_ctrl.h create mode 100644 src/segwayrmp/include/comm_ctrl_navigation.h create mode 100755 src/segwayrmp/include/segwayrmp/robot.h create mode 100755 src/segwayrmp/lib/ctrl_arm64-v8a create mode 100755 src/segwayrmp/lib/ctrl_x86_64 create mode 100755 src/segwayrmp/lib/libctrl_arm64-v8a.so create mode 100755 src/segwayrmp/lib/libctrl_x86_64.so create mode 100755 src/segwayrmp/package.xml create mode 100755 src/segwayrmp/src/SmartCar.cpp create mode 100755 src/segwayrmp/src/robot.cpp create mode 100755 src/segwayrmp/tools/drive_segway_sample.cpp diff --git a/src/segway_msgs/CMakeLists.txt b/src/segway_msgs/CMakeLists.txt new file mode 100755 index 0000000..7dc8e36 --- /dev/null +++ b/src/segway_msgs/CMakeLists.txt @@ -0,0 +1,76 @@ +cmake_minimum_required(VERSION 3.5) +project(segway_msgs) + +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fpic") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fpic") +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(std_msgs REQUIRED) +####find_package(builtin_interface REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(action_msgs REQUIRED) + +set(msg_files + "msg/BmsFb.msg" + "msg/ChassisCtrlSrcFb.msg" + "msg/ChassisMileageMeterFb.msg" + "msg/ChassisModeFb.msg" + "msg/ErrorCodeFb.msg" + "msg/MotorWorkModeFb.msg" + "msg/SpeedFb.msg" + "msg/TicksFb.msg" +) + +set(srv_files + "srv/ChassisSendEvent.srv" + "srv/RosGetChargeMosCtrlStatusCmd.srv" + "srv/RosGetLoadParamCmd.srv" + "srv/RosGetSwVersionCmd.srv" + "srv/RosGetVelMaxFeedbackCmd.srv" + "srv/RosSetChargeMosCtrlCmd.srv" + "srv/RosSetChassisEnableCmd.srv" + "srv/RosSetChassisPoweroffCmd.srv" + "srv/RosSetLoadParamCmd.srv" + "srv/RosSetRemovePushCmd.srv" + "srv/RosSetVelMaxCmd.srv") + +set(action_files + "action/RosSetIapCmd.action" +) +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} + ${action_files} + DEPENDENCIES geometry_msgs std_msgs ADD_LINTER_TESTS) + +# ament_export_dependencies(rosidl_default_generators) +# ament_export_dependencies(rosidl_default_runtime) +# ament_export_include_directories(include) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/src/segway_msgs/action/RosSetIapCmd.action b/src/segway_msgs/action/RosSetIapCmd.action new file mode 100644 index 0000000..5e7da2b --- /dev/null +++ b/src/segway_msgs/action/RosSetIapCmd.action @@ -0,0 +1,6 @@ +int16 iap_board #1:iap central board; 2:iap motor board +--- +int16 iap_result #3: iap_state_complete; 4: iap_state_fail; 5: iap_state_abort +int16 error_code #When iap_result value is 4, this value represents the error code +--- +int16 iap_percent \ No newline at end of file diff --git a/src/segway_msgs/msg/BmsFb.msg b/src/segway_msgs/msg/BmsFb.msg new file mode 100644 index 0000000..aa841bf --- /dev/null +++ b/src/segway_msgs/msg/BmsFb.msg @@ -0,0 +1,5 @@ +int16 bat_soc +int16 bat_charging +int32 bat_vol +int32 bat_current +int16 bat_temp diff --git a/src/segway_msgs/msg/ChassisCtrlSrcFb.msg b/src/segway_msgs/msg/ChassisCtrlSrcFb.msg new file mode 100644 index 0000000..d159dd7 --- /dev/null +++ b/src/segway_msgs/msg/ChassisCtrlSrcFb.msg @@ -0,0 +1 @@ +uint16 chassis_ctrl_cmd_src \ No newline at end of file diff --git a/src/segway_msgs/msg/ChassisMileageMeterFb.msg b/src/segway_msgs/msg/ChassisMileageMeterFb.msg new file mode 100644 index 0000000..71d1bec --- /dev/null +++ b/src/segway_msgs/msg/ChassisMileageMeterFb.msg @@ -0,0 +1 @@ +uint32 vehicle_meters \ No newline at end of file diff --git a/src/segway_msgs/msg/ChassisModeFb.msg b/src/segway_msgs/msg/ChassisModeFb.msg new file mode 100644 index 0000000..3745d2a --- /dev/null +++ b/src/segway_msgs/msg/ChassisModeFb.msg @@ -0,0 +1 @@ +uint16 chassis_mode \ No newline at end of file diff --git a/src/segway_msgs/msg/ErrorCodeFb.msg b/src/segway_msgs/msg/ErrorCodeFb.msg new file mode 100644 index 0000000..e2fa46b --- /dev/null +++ b/src/segway_msgs/msg/ErrorCodeFb.msg @@ -0,0 +1,5 @@ +uint32 host_error +uint32 central_error +uint16 left_motor_error +uint16 right_motor_error +uint32 bms_error \ No newline at end of file diff --git a/src/segway_msgs/msg/MotorWorkModeFb.msg b/src/segway_msgs/msg/MotorWorkModeFb.msg new file mode 100644 index 0000000..1ee2876 --- /dev/null +++ b/src/segway_msgs/msg/MotorWorkModeFb.msg @@ -0,0 +1 @@ +uint16 motor_work_mode #0: no output torque 1: output torque \ No newline at end of file diff --git a/src/segway_msgs/msg/SpeedFb.msg b/src/segway_msgs/msg/SpeedFb.msg new file mode 100644 index 0000000..e2c22b4 --- /dev/null +++ b/src/segway_msgs/msg/SpeedFb.msg @@ -0,0 +1,5 @@ +float32 car_speed +float32 turn_speed +float32 l_speed +float32 r_speed +uint64 speed_timestamp \ No newline at end of file diff --git a/src/segway_msgs/msg/TicksFb.msg b/src/segway_msgs/msg/TicksFb.msg new file mode 100644 index 0000000..49553f4 --- /dev/null +++ b/src/segway_msgs/msg/TicksFb.msg @@ -0,0 +1,3 @@ +int32 l_ticks +int32 r_ticks +uint64 ticks_timestamp \ No newline at end of file diff --git a/src/segway_msgs/package.xml b/src/segway_msgs/package.xml new file mode 100755 index 0000000..0de6505 --- /dev/null +++ b/src/segway_msgs/package.xml @@ -0,0 +1,26 @@ + + + + segway_msgs + 0.0.0 + TODO: Package description + ninebot + TODO: License declaration + + ament_cmake + + rosidl_default_generators + rosidl_default_runtime + rosidl_interface_packages + + std_msgs + geometry_msgs + action_msgs + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/segway_msgs/srv/ChassisSendEvent.srv b/src/segway_msgs/srv/ChassisSendEvent.srv new file mode 100644 index 0000000..1dd5276 --- /dev/null +++ b/src/segway_msgs/srv/ChassisSendEvent.srv @@ -0,0 +1,3 @@ +int16 chassis_send_event_id +--- +bool ros_is_received \ No newline at end of file diff --git a/src/segway_msgs/srv/RosGetChargeMosCtrlStatusCmd.srv b/src/segway_msgs/srv/RosGetChargeMosCtrlStatusCmd.srv new file mode 100644 index 0000000..a9eac33 --- /dev/null +++ b/src/segway_msgs/srv/RosGetChargeMosCtrlStatusCmd.srv @@ -0,0 +1,3 @@ +bool ros_get_chassis_charge_ctrl_status +--- +int16 chassis_charge_ctrl_status \ No newline at end of file diff --git a/src/segway_msgs/srv/RosGetLoadParamCmd.srv b/src/segway_msgs/srv/RosGetLoadParamCmd.srv new file mode 100644 index 0000000..5c5f212 --- /dev/null +++ b/src/segway_msgs/srv/RosGetLoadParamCmd.srv @@ -0,0 +1,3 @@ +bool ros_get_load_param +--- +int16 get_load_param #0:no_load, 1: full_load \ No newline at end of file diff --git a/src/segway_msgs/srv/RosGetSwVersionCmd.srv b/src/segway_msgs/srv/RosGetSwVersionCmd.srv new file mode 100644 index 0000000..8ea2df5 --- /dev/null +++ b/src/segway_msgs/srv/RosGetSwVersionCmd.srv @@ -0,0 +1,5 @@ +bool ros_get_sw_version_cmd +--- +uint16 host_version +uint16 central_version +uint16 motor_version \ No newline at end of file diff --git a/src/segway_msgs/srv/RosGetVelMaxFeedbackCmd.srv b/src/segway_msgs/srv/RosGetVelMaxFeedbackCmd.srv new file mode 100644 index 0000000..f1bf0d2 --- /dev/null +++ b/src/segway_msgs/srv/RosGetVelMaxFeedbackCmd.srv @@ -0,0 +1,5 @@ +bool ros_get_vel_max_fb_cmd +--- +uint16 forward_max_vel_fb +uint16 backward_max_vel_fb +uint16 angular_max_vel_fb \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetChargeMosCtrlCmd.srv b/src/segway_msgs/srv/RosSetChargeMosCtrlCmd.srv new file mode 100644 index 0000000..9c69946 --- /dev/null +++ b/src/segway_msgs/srv/RosSetChargeMosCtrlCmd.srv @@ -0,0 +1,3 @@ +bool ros_set_chassis_charge_ctrl +--- +uint8 chassis_set_charge_ctrl_result \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetChassisEnableCmd.srv b/src/segway_msgs/srv/RosSetChassisEnableCmd.srv new file mode 100644 index 0000000..b7a82c5 --- /dev/null +++ b/src/segway_msgs/srv/RosSetChassisEnableCmd.srv @@ -0,0 +1,3 @@ +bool ros_set_chassis_enable_cmd +--- +uint8 chassis_set_chassis_enable_result \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetChassisPoweroffCmd.srv b/src/segway_msgs/srv/RosSetChassisPoweroffCmd.srv new file mode 100644 index 0000000..df2e8dd --- /dev/null +++ b/src/segway_msgs/srv/RosSetChassisPoweroffCmd.srv @@ -0,0 +1,3 @@ +bool ros_set_chassis_poweroff_cmd +--- +uint8 chassis_set_poweroff_result \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetLoadParamCmd.srv b/src/segway_msgs/srv/RosSetLoadParamCmd.srv new file mode 100644 index 0000000..5d61f2e --- /dev/null +++ b/src/segway_msgs/srv/RosSetLoadParamCmd.srv @@ -0,0 +1,3 @@ +int16 ros_set_load_param #0:no_load, 1: full_load +--- +uint8 chassis_set_load_param_result \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetRemovePushCmd.srv b/src/segway_msgs/srv/RosSetRemovePushCmd.srv new file mode 100644 index 0000000..a13175f --- /dev/null +++ b/src/segway_msgs/srv/RosSetRemovePushCmd.srv @@ -0,0 +1,3 @@ +bool ros_set_remove_push_cmd +--- +uint8 chassis_set_revove_push_result \ No newline at end of file diff --git a/src/segway_msgs/srv/RosSetVelMaxCmd.srv b/src/segway_msgs/srv/RosSetVelMaxCmd.srv new file mode 100644 index 0000000..8a26de4 --- /dev/null +++ b/src/segway_msgs/srv/RosSetVelMaxCmd.srv @@ -0,0 +1,5 @@ +float64 ros_set_forward_max_vel +float64 ros_set_backward_max_vel +float64 ros_set_angular_max_vel +--- +uint8 chassis_set_max_vel_result \ No newline at end of file diff --git a/src/segwayrmp/CMakeLists.txt b/src/segwayrmp/CMakeLists.txt new file mode 100755 index 0000000..92797ab --- /dev/null +++ b/src/segwayrmp/CMakeLists.txt @@ -0,0 +1,81 @@ +cmake_minimum_required(VERSION 3.5) +project(segwayrmp) + +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fpic -Wl,-R${PROJECT_SOURCE_DIR}/lib") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fpic") +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclpy REQUIRED) +find_package(std_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(segway_msgs REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(rclcpp_components REQUIRED) + +add_executable(SmartCar + src/SmartCar.cpp + src/robot.cpp +) +target_include_directories(SmartCar PUBLIC + $ + $ +) +target_link_directories(SmartCar PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR}/lib +) +# message(WARNING ${PROJECT_SOURCE_DIR} + "!!" + ${CMAKE_CURRENT_SOURCE_DIR} + "!!" + ${PROJECT_NAME}) +ament_target_dependencies(SmartCar + "rclcpp" "std_msgs" "nav_msgs" "sensor_msgs" "geometry_msgs" "segway_msgs" "tf2" "tf2_ros" +) +target_link_libraries(SmartCar + ${PROJECT_SOURCE_DIR}/lib/libctrl_x86_64.so +) + +add_executable(drive_segway_sample + tools/drive_segway_sample.cpp +) +target_include_directories(drive_segway_sample PUBLIC + $ + $ +) +ament_target_dependencies(drive_segway_sample + "rclcpp" "std_msgs" "nav_msgs" "sensor_msgs" "geometry_msgs" "segway_msgs" "tf2" "tf2_ros" +) + +install(TARGETS + SmartCar + drive_segway_sample + DESTINATION + lib/${PROJECT_NAME}) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/src/segwayrmp/include/comm_ctrl.h b/src/segwayrmp/include/comm_ctrl.h new file mode 100644 index 0000000..71abc33 --- /dev/null +++ b/src/segwayrmp/include/comm_ctrl.h @@ -0,0 +1,109 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef COMM_CTRL_H +#define COMM_CTRL_H + +#include +#include +#include "comm_ctrl_navigation.h" + + +// Map table transmission value gain coefficient; +#define ERROR_LINE_LIMIT_VEL_VALUE (5 * LINE_SPEED_TRANS_GAIN_MPS) +#define ERROR_ANGULAR_LIMIT_VEL_VALUE (5 * ANGULAR_SPEED_TRANS_GAIN_RADPS) +#define ACC_VALUE_GAIN 100 + + +#define RMP_HOST_ERR_BIT_MCU_HEART_BEAT 0 //The heartbeat with the chassis was interrupted +#define RMP_HOST_ERR_BIT_SERIAL_PORT_LOST 1 //Serial port module unplugged + +void AprGxJniEventRegister(int32_t (*callback)(int32_t)); + +//-------------------Timestamp------------------------ + +//--------------------GX--API------------------ +int init_control(void); +void exit_control(void); + +int16_t get_forward_speed_limit(void); +int16_t get_backward_speed_limit(void); +int16_t get_angular_speed_limit(void); +uint16_t get_Stop_Bottom_Status(void); +uint8_t set_calib_chassis_imu_gyro(void);//Reserve for later versions +uint16_t get_Chassis_Imu_Calib_Result(void); //Reserve for later versions +void clear_Chassis_Imu_Calib_Result(void);//Reserve for later versions +uint8_t set_calib_chassis_current(void); +uint16_t get_chassis_current_calib_result(void); +void clear_chassis_current_calib_result(void); + + +//-----------------GX IAP-------------------- +void IapAllBoard(const char **file_paths, char **versions); +int32_t IapSingerBoard(char * path,char * boradname,char* version); +//int32_t getIapTotalProgress(void); +//------------------GX Host------------------- + +char* GetGxHardVersion(void); +void TracePrint_Switch(bool status); //true or false +void SetNavigationStatus(uint8_t status); +void setSaveRecordCmd(void); //开始保存log接口     ps:上层调用 +void clearRecordCmd(void); //清除保存log命令     ps:上层不需要调�?so每次保存完log后会自动调用 +uint8_t getSaveRecordCmd(void); //获取是否开始保存log   ps:so自动调用,上层不需要调�? +uint8_t GetNavigationStatus(void); + + +void set_gx_route_bat_voltage(uint16_t voltage); + + +int16_t get_cmd_speed_forward(void); +int16_t get_fbk_speed_forward(void); +int16_t get_encode_fbk_speed_forward(void); +int16_t get_cmd_w_forward(void); +int16_t get_fbk_w_forward(void); +int16_t get_rec_cmd_vx(void); +int16_t get_rec_cmd_w(void); +int16_t get_pid_target_vx(void); +int16_t get_pid_target_w(void); +int16_t get_encode_speed_L(void); +int16_t get_encode_speed_R(void); + +int16_t get_heart_beat_data(board_name_e board_type); + +void set_host_error(uint8_t offset, uint8_t err_bool_value); +uint32_t get_host_error(void); +uint32_t get_host_speed_cmd_cnt(void); +uint32_t get_chassis_reply_speed_cmd_cnt(void); +int32_t get_encoder_l_ticks(void); +int32_t get_encoder_r_ticks(void); +char * get_smart_car_serial(void); +uint8_t get_comu_interface_serial0_can1(); +void showHostBuildTime(void); +void showChassisCentralBuildTime(void); + +/* 暂时不开放此接口,由于map表只能发送整数,故此接口待修改:乘以10或�?00下发,电机板收到命令数据后再恢复数据 */ +uint8_t set_cmd_acc(double linear_x_acc, double linear_x_brake_acc, double angular_z_acc);//Set the linear and angular accelerated speed: m/s2 ; rad/s2. + +uint8_t set_chassis_no_load(void); +uint8_t set_chassis_full_load(void); + +void ackWriteCentralMapInit(); +uint8_t ctrlMapAckWrite( uint8_t dest_id, uint8_t map_start_index, uint32_t mem_len); + +void set_chassis_charge_status(int16_t chargestatus); +uint32_t get_chassis_central_Err_Status(void); +uint16_t get_chassis_l_motor_Err_Status(void); +uint16_t get_chassis_r_motor_Err_Status(void); +uint32_t get_chassis_bms_Err_Status(void); +char * show_host_version(void); + + +int16_t get_charge_mos_ctrl_cmd(void);// Get chassis charge_ctrl mos cmd; 1:turn on; 0: turn off + +#endif + +#ifdef __cplusplus +} +#endif + diff --git a/src/segwayrmp/include/comm_ctrl_navigation.h b/src/segwayrmp/include/comm_ctrl_navigation.h new file mode 100644 index 0000000..9a3d365 --- /dev/null +++ b/src/segwayrmp/include/comm_ctrl_navigation.h @@ -0,0 +1,180 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef COMM_CTRL_NAVIGATION_H +#define COMM_CTRL_NAVIGATION_H + +#include +#include + +#define TYPE_ID_NUM 10 //Number of callback functions +//--------------------------DATA CALL BACK INDEX-------------------------- +#define Chassis_Data_Speed 1 +#define Chassis_Data_Ticks 2 +#define Chassis_Data_Odom_Pose_xy 3 +#define Chassis_Data_Odom_Euler_xy 4 +#define Chassis_Data_Odom_Euler_z 5 +#define Chassis_Data_Odom_Linevel_xy 6 +#define Chassis_Data_Imu_Gyr 7 //IMU Gyroscope data 陀螺仪数据上报 +#define Chassis_Data_Imu_Acc 8 //IMU Accelerometer data 加速度计数据上�? + +//-----------------------Event--------------------------------------------- +#define ChassisBootReadyEvent 1 // Chassis central control boot OK +#define PadPowerOffEvent 2 // The chassis will power off +#define OnEmergeStopEvent 3 // The chassis emergency stop button is triggered +#define OutEmergeStopEvent 4 // The chassis emergency stop button recover +#define OnLockedRotorProtectEvent 5 // the chassis motor locked-rotor +#define OutLockedRotorProtectEvent 6 // the chassis motor no longer locked-rotor +#define OnLostCtrlProtectEvent 7 // the chassis motor lost control +#define OutLostCtrlProtectEvent 8 // the chassis motor no longer lost control +#define CalibrateGyroSuccess 9 // Chassis gyroscope calibration successful +#define CalibrateGyroFail 10 // Chassis gyroscope calibration failed +#define CalibratePasheCurrentSuccess 11 // Chassis gyroscope calibration successful +#define CalibratePasheCurrentFail 12 // Chassis gyroscope calibration failed + + +//---------The proportional coefficient of the callback gyro data------------------ +#define CHASSIS_IMU_GYR_VALUE_TRANS_SCALE 900 //900~~32768(MAX value for int16: map table ) * 57.3(degrees for 1 rad) /2000(Gyroscope range: 2000dps) +#define CHASSIS_IMU_ACC_VALUE_TRANS_SCALE 4000 //4000~~32768(MAX value for int16: map table )/8(Accelerometer range: 8g) + +#define LINE_SPEED_TRANS_GAIN_MPS 3600 //3600-->1m/s +#define ANGULAR_SPEED_TRANS_GAIN_RADPS 1000 //1000-->1rad/s + +#define NO_LOAD 0 // Set the chassis parameters as no-load parameters, The chassis defaults to no load +#define FULL_LOAD 1 // Set the chassis parameters as full load parameters + +//-----------------------Version V0.6 and above--------------------------- +#define LOCK_MODE 0 // Lock the car +#define CTRL_MODE 1 // Control the car +#define PUSH_MODE 2 // push the car +#define EMERG_MODE 3 // emergency +#define ERROR_MODE 4 // Internal error + + +//-------------------Timestamp------------------------ +#define MAX_BASIC_FRM_SZ 0x1F + +#pragma pack(1) +typedef struct StampedBasicFrame_{ + uint32_t type_id; //Data type number + uint64_t timestamp; //Linux timestamp + char data[MAX_BASIC_FRM_SZ]; //Chassis specific data +} StampedBasicFrame; +#pragma pack() +typedef void (*h_aprctrl_datastamped_t)(StampedBasicFrame* frm); +typedef void (*h_aprctrl_event_t)(int32_t event_num); + +typedef struct { + h_aprctrl_datastamped_t on_new_data; +}s_aprctrl_datastamped_t; + +typedef struct { + h_aprctrl_event_t event_callback; +}s_aprctrl_event_t; + +typedef enum { + Host = 1, + Central = 2, //底盘只连中控�? + Motor = 3, + BMS = 4 +}board_name_e; + +typedef enum { + comu_serial = 0, + comu_can = 1 +}comu_choice_e; + +typedef struct{ + int16_t l_speed;//Left wheel speed + int16_t r_speed;//Right wheel speed + int16_t car_speed;//Vehicle linear speed + int16_t turn_speed;//Turning speed +}chassis_speed_data_t; + +typedef struct{ + int32_t l_ticks;//Left wheel ticks + int32_t r_ticks;//Right wheel ticks +}motor_ticks_t; + +typedef struct{ + float pos_x; + float pos_y; +}odom_pos_xy_t; + +typedef struct{ + float euler_x; + float euler_y; +}odom_euler_xy_t; + +typedef struct{ + float euler_z; +}odom_euler_z_t; + +typedef struct{ + float vel_line_x; + float vel_line_y; +}odom_vel_line_xy_t; + +typedef struct{ + int16_t gyr[3]; +}imu_gyr_original_data_t; + +typedef struct{ + int16_t acc[3]; +}imu_acc_original_data_t; + + +void aprctrl_datastamped_jni_register(s_aprctrl_datastamped_t* f); //The callback registration function +void aprctrl_eventcallback_jni_register(s_aprctrl_event_t* f); //Event callback registration function + +uint32_t get_err_state(board_name_e board_name);//Gets the software error status +int16_t get_bat_soc(void);//Gets the percentage of battery left +int16_t get_bat_charging(void);//Gets the charging status of the battery +int32_t get_bat_mvol(void);//Gets battery voltage, mV +int32_t get_bat_mcurrent(void);//Gets battery current, mA +int16_t get_bat_temp(void);// Gets battery temperature +int16_t get_chassis_work_model(void);//Get the chassis working mode +uint8_t get_chassis_load_state(void);//Gets whether the chassis parameters are empty or full load, 0: no_load, 1: full_load +uint16_t get_chassis_mode(void);//Gets chassis mode +int16_t get_ctrl_cmd_src(void); // Get the source of the control command +int32_t get_vehicle_meter(void); //Get the total mileage meters of the chssis +uint16_t get_host_version(void); +uint16_t get_chassis_central_version(void); +uint16_t get_chassis_motor_version(void); +int16_t get_line_forward_max_vel_fb(void); +int16_t get_line_backward_max_vel_fb(void); +int16_t get_angular_max_vel_fb(void); +int32_t getIapTotalProgress(void); +void iapCentralBoard(void);//Operate on the Central board: IAP +void iapMotorBoard(void);//Operate on the Motor board: IAP +bool isHostIapOver(void);//Query whether a single IAP ends +int16_t getHostIapResult(void); +int16_t getHostIapErrorCode(void); +int16_t get_chassis_hang_mode(void);//Get chassis hang_mode; 1: in Hang_mode; 0: not in Hand_mode. +int16_t get_charge_mos_ctrl_status(void);//Get the status of switch for charging MOS on the central board, charging:1; no charge:0 + + + +void set_cmd_vel(double linear_x,double angular_z);//Set the linear and angular speeds of the vehicle: m/s ; rad/s. +uint8_t set_line_forward_max_vel(double linear_forward_max_x);//Set the maximum linear velocity in the direction of advance +uint8_t set_line_backward_max_vel(double linear_backward_max_x);//Set the maximum linear velocity in the backward direction +uint8_t set_angular_max_vel(double angular_max_z);//Set the maximum angular velocity +uint8_t set_enable_ctrl(uint16_t enable_flag);//Set chassis movement enable +int init_control_ctrl(void);//Chassis initialization +void exit_control_ctrl(void);//Chassis software finished running +void set_smart_car_serial(const char * serial_no);//Set the serial port name +void set_comu_interface(comu_choice_e comu_choice); //Set communication interface: 'comu_serial': serial port; 'comu_can': CAN port +uint8_t set_chassis_load_state(int16_t newLoadSet);//Sets whether the chassis parameters are empty or full load, 0: no_load, 1: full_load +uint8_t set_chassis_poweroff(void);//Set two - wheel differential chassis shutdown +uint8_t set_remove_push_cmd(void);//An order to remove the push status +void setHostIapCanceled(void); +void set_chassis_hang_mode(int16_t enterHand);//Set chassis hang_mode; 1: enter the Hang_mode; 0: exit the Hand_mode. +uint8_t set_charge_mos_ctrl(bool on);//Set the switch for charging MOS on the central board; charging:1, stop charging:0. + +extern int32_t IapSingerBoard(char * path,char * boradname,char* version); +#endif + +#ifdef __cplusplus +} +#endif diff --git a/src/segwayrmp/include/segwayrmp/robot.h b/src/segwayrmp/include/segwayrmp/robot.h new file mode 100755 index 0000000..e7fef60 --- /dev/null +++ b/src/segwayrmp/include/segwayrmp/robot.h @@ -0,0 +1,169 @@ +#ifndef _ROBOT_H +#define _ROBOT_H + +#include +#include +#include +#include +#include "stdint.h" +#include +#include + +#include +#include "rclcpp/rclcpp.hpp" +#include +#include +#include +#include +#include "tf2_ros/transform_broadcaster.h" +#include +#include "tf2/LinearMath/Quaternion.h" +#include "comm_ctrl_navigation.h" +#include "rclcpp_action/rclcpp_action.hpp" +#include "segway_msgs/msg/bms_fb.hpp" +#include "segway_msgs/msg/chassis_ctrl_src_fb.hpp" +#include "segway_msgs/msg/chassis_mileage_meter_fb.hpp" +#include "segway_msgs/msg/chassis_mode_fb.hpp" +#include "segway_msgs/msg/error_code_fb.hpp" +#include "segway_msgs/msg/motor_work_mode_fb.hpp" +#include "segway_msgs/msg/speed_fb.hpp" +#include "segway_msgs/msg/ticks_fb.hpp" +#include "segway_msgs/srv/chassis_send_event.hpp" +#include "segway_msgs/srv/ros_get_charge_mos_ctrl_status_cmd.hpp" +#include "segway_msgs/srv/ros_get_load_param_cmd.hpp" +#include "segway_msgs/srv/ros_get_sw_version_cmd.hpp" +#include "segway_msgs/srv/ros_get_vel_max_feedback_cmd.hpp" +#include "segway_msgs/srv/ros_set_charge_mos_ctrl_cmd.hpp" +#include "segway_msgs/srv/ros_set_chassis_enable_cmd.hpp" +#include "segway_msgs/srv/ros_set_chassis_poweroff_cmd.hpp" +#include "segway_msgs/srv/ros_set_load_param_cmd.hpp" +#include "segway_msgs/srv/ros_set_remove_push_cmd.hpp" +#include "segway_msgs/srv/ros_set_vel_max_cmd.hpp" +#include "segway_msgs/action/ros_set_iap_cmd.hpp" + +#define pi 3.141592654 +#define pi_2 6.283185308 + +namespace robot +{ + class Chassis + { + public: + using iapCmd = segway_msgs::action::RosSetIapCmd; + using goalHandaleIapCmd = rclcpp_action::ServerGoalHandle; + Chassis(rclcpp::Node::SharedPtr nh); + static void pub_event_callback(int event_no); + private: + std::shared_ptr node; + + std::string bins_directory; + std::string chassis_version; + std::string route_version; + std::string connect_version; + + tf2::Quaternion odom_quat; + std::shared_ptr odom_broadcaster; + + segway_msgs::msg::BmsFb bms_fb; + segway_msgs::msg::ChassisCtrlSrcFb chassis_ctrl_src_fb; + segway_msgs::msg::ChassisMileageMeterFb chassis_mileage_meter_fb; + segway_msgs::msg::ChassisModeFb chassis_mode_fb; + segway_msgs::msg::ErrorCodeFb error_code_fb; + segway_msgs::msg::MotorWorkModeFb motor_work_mode_fb; + segway_msgs::msg::SpeedFb speed_fb; + segway_msgs::msg::TicksFb ticks_fb; + geometry_msgs::msg::TransformStamped odom_trans; + nav_msgs::msg::Odometry odom_fb; + sensor_msgs::msg::Imu imu_fb; + + rclcpp::Subscription::SharedPtr velocity_sub; + + rclcpp::Publisher::SharedPtr bms_fb_pub; + rclcpp::Publisher::SharedPtr chassis_ctrl_src_fb_pub; + rclcpp::Publisher::SharedPtr chassis_mileage_meter_fb_pub; + rclcpp::Publisher::SharedPtr chassis_mode_fb_pub; + rclcpp::Publisher::SharedPtr error_code_fb_pub; + rclcpp::Publisher::SharedPtr motor_work_mode_fb_pub; + rclcpp::Publisher::SharedPtr speed_fb_pub; + rclcpp::Publisher::SharedPtr ticks_fb_pub; + rclcpp::Publisher::SharedPtr odom_pub; + rclcpp::Publisher::SharedPtr imu_pub; + + + rclcpp::Service::SharedPtr ros_get_charge_mos_ctrl_status_cmd_server; + rclcpp::Service::SharedPtr ros_get_load_param_cmd_server; + rclcpp::Service::SharedPtr ros_get_sw_version_cmd_server; + rclcpp::Service::SharedPtr ros_get_vel_max_feedback_cmd_server; + rclcpp::Service::SharedPtr ros_set_charge_mos_ctrl_cmd_server; + rclcpp::Service::SharedPtr ros_set_chassis_enable_cmd_server; + rclcpp::Service::SharedPtr ros_set_chassis_poweroff_cmd_server; + rclcpp::Service::SharedPtr ros_set_load_param_cmd_server; + rclcpp::Service::SharedPtr ros_set_remove_push_cmd_server; + rclcpp::Service::SharedPtr ros_set_vel_max_cmd_server; + + void ros_get_charge_mos_ctrl_status_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_get_load_param_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_get_sw_version_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_get_vel_max_feedback_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_charge_mos_ctrl_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_chassis_enable_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_chassis_poweroff_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_load_param_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_remove_push_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + void ros_set_vel_max_cmd_callback(const std::shared_ptr request, + std::shared_ptr response); + + rclcpp_action::Server::SharedPtr iap_action_server; + + rclcpp::TimerBase::SharedPtr timer_1hz; + rclcpp::TimerBase::SharedPtr timer_1000hz; + + s_aprctrl_datastamped_t timestamp_data; + s_aprctrl_event_t event_data; + + void timer_1000hz_callback(void); + void timer_1hz_callback(void); + void speed_pub_callback(void); + void ticks_pub_callback(void); + void imu_pub_callback(void); + void pub_odom_callback(void); + void cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg) const; + + void iapCmdExecute(const std::shared_ptr goal_handle); + rclcpp_action::GoalResponse handle_iapCmdGoal( + const rclcpp_action::GoalUUID & uuid, + std::shared_ptr goal) + { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "Receive goal request with iap_board %d", goal->iap_board); + (void)uuid; + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; + } + + rclcpp_action::CancelResponse handle_iapCmdCancel( + const std::shared_ptr goal_handle) + { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "Received request to cancel goal"); + (void)goal_handle; + return rclcpp_action::CancelResponse::ACCEPT; + } + + void handle_iapCmdAccepted(const std::shared_ptr goal_handle) + { + using namespace std::placeholders; + (void)goal_handle; + std::thread{std::bind(&Chassis::iapCmdExecute, this, _1), goal_handle}.detach(); + } + }; + +} + +#endif diff --git a/src/segwayrmp/lib/ctrl_arm64-v8a b/src/segwayrmp/lib/ctrl_arm64-v8a new file mode 100755 index 0000000000000000000000000000000000000000..34f71bc5a82b92528830d819560ba1996aec2ced GIT binary patch literal 403440 zcmeFa4V;x#wLiX}GXso(0s{sLI%fcdz!!W;ogn8K1_cF`1}aK#bB1AfNnl`RR3=Cc z*ey)2agwW+-s^J)ESaq4mKBrQ9I$@ZvRj1SvX`4@(9~{LsFh4Y^ZS0+-upTGJaZ0c zfBSuY_y7MNeR%d>d+oK?UVH7e*M56u^JNPzk9nT5znJ=_lGuBE0qK90>N;W@z~#m2z(Py2cCNj@L%x$H$0c%xd2ZWo;&e; z8BaYP_je*9r{TH70F&nZS-d}G!b|af1kV|GDF1dm{P}n`G2r|*Abge+Pa`}7PaMy~ zc=&q=&u1j0)K~HT5}x&VD7i=R@b@5|9z2iXxfRcKc=-Dwo^^N{@mzuDD|pu8*@Ndy zJU8H3gC~J!3m*Qyh36Z1*d8Ck(~ai~c(&ttH=b5Jci}-(s*CV^9M5h%|B8pd9eCJ2 zTk-reo&eA7c=-Do9=7|}@!X4N8=lYOiQ$=tr_k>c0DcV5NAX;45Z;gXxA9EF(~Rdv zJa6S!VvvWug-oLj?%*PM#utIVS@6^d;s_^xHp1)^_IC~flkl8k0eFvc!i9n-0XVi$ zf`Pr$ye~EHEAd{4=X?{t3h#*~Y+s8In1bgr1EAeF*Mvu!cP-v0n6UergGjjnRGar~ zyx)VT(!^KceKnpsJnuEIC3wFB&uTnPc;@5buMN*E2`Tjv^R}-Q2%K&r7vnt~&vX+X zXWs5>f{A<(?;1QQC-GD#ya3_P;rTG0m3aOE&tg3M4bm_5Pk29orvcBq@LZ4Q(|G<7 z&wY6KyBp8Rcy7Y89M83QCgZsV4}Wv1O@;Ez>H{;K&eGl{7p{Qud|pD{$! zxA;R0KhGHcfhNCq82HLayVMq;f0p2nRr3r#R)^nh=v-pTwe@bxIbS%W9`m=|(0|70|M?oMb_#ri%KouN zAaMgPhhPioXIT+=m*wB+iEXd%8Ge3X^zbD^|Ca_n;a$4iJ&+fFzZW`V)xwCLl%avB zhub_YAKM>)S42Li2>w`=Fm$GB@@lf7lQnv4`8?0Sr<(pnyUXADBJ}HvwC`L)=fQ{` zzEp(H2MqpaOuHB{sG&vh|5^n8r6T++DT05Cfsd^6rJnYm4Mp(3T!j8o!++BB7dzH8 z15Q0W`~yutVG7t`@b?(`SRdnlfsa*(jGg3o%wGmiAwB$B5q`Q2{dE!fKWXT1i|E5y zMfCX}AcsQz>r+MK^K;N=ef`^gaI83T$ZvWP{2vy9ziRm3ZtR=&E&goahm8I&G4vlP zLT3a7OMYIuzeX?<2LHJt_)`r2k$><7)7rPW20nF?rZd^lc^}~Hk55GOw%*{sEZ#)U zPx+T3?RB%Eb5E)6*FclsCk=d_u_s_#eqSrX|34f2AR@N|MasRt2)v~T{h$bZUJ*J0 zxGki&Qvi?SiT?H#p?|Nb*U*T3?gW8C^dA8}+kL?oYNUuif-ZmaiqJn&g#RBKI=->n z388{HXc7F=i}a%x4F4M<{qc1}f1T+se}sPX_nRX0uP(y>3GioF-yKT#BRJ^grCC(zboR8jljT7`8;9l(gIF&@S6ZQ?b0*G zkLuE3b)kXp8LI1rsQmU8DR-{H&qnIigo+fB!?q&u_Zd3dBlZ1s5&Q;&zu%OLZX&-I z@o%AW?^Df{x%>`&Xe!;1+NS8;%~d*bDXJ{9j^lezsJC5 zXms_xB699D`1=h$+&}qM6~Vshs}<{*Nm{e}dqTRhO9dwSLH% zhR#Egdi545x7y(QW%>5)O7I&uJiD*=0iSxZMZOWZz$~{YyQI8ussYri+ z8tH}jf7;;hkCc0J5&Tz8xwr4~r9``~^5-IaRu_@yiCBoBUhOgdnwn?9hXG> z*ozH(|8Om5i$BlMc_v~fCl}%80|tMb!JlW!{Zf(kYBBhSPtsZU!>}< zSbSCevZj`%6{}j?npzfLRlB-*ZPVh0rK_7%ef^3x&1>sh+ZtNh>g!egl{ePc8NAxn z4Xv$BtvY+b%*$6dH@B#D%{Q^Ib!{tKni`g|$QjB+>et-R*0iDihPA7k8?O(6A8B5- zHjFePQyckcYH3;9To1&CwpGnedh^<4^{uN`tZi5w=FwF1Xll^1rq;HW=JpV=k(qC5 zSk;yfDTvm#YE9F!Jlv)Y$k@`IqE&Nv0yb1Wr zSKrXOQh~k3b?qS9ux#0?7S+10W!2iYET-&&2omvM`K(6)mtB|>>s=l?g zv0?3U)wsI3wTZcww>7O^t+7FC-3@K6{HJkcLyKB-JrNp~Hn+5?w&vB%H#N1W6-{mH zRxKlbTl4j*ad~S~+p5-eO-%w?jdIsCtpSV(_+Pa(BGS-?(9%_Fm!YCfP1h5JoHevI zQcOTy)_emh#bPB5d@L9K6f(2Q&Fk9KnugVABhp2iqRwlYZ){SmDS2G_(WaJW5<+Fw zs^&(>v9%rQxkla4y1J=pomzfV%PJ_wa>|NzV8PAHmo>C2ibJZ|*1TLbv^B3%)SA_X zGi)$H0;|`pY-klJG$OB5M{3@zYu?b<*wor8tf5-<^=vQG3Dz_~J8xWWTc)L{Nv&ya zYi?P*s`2{PISp+MYDI0++P0R4)tB9fw_3A!Wy>-N)}p>k8=&ZOH`EKDK7=&3wXCjR z)3C0-am}(;wPId#YuloxmQ@X_XDEhi8`fU27F~0BLu1pNCeff3wWvVrs@7|kHLtns zhSg0iOFp=O-FGcobPe+?Xj;+G*q&E#t6HxryZf?WNokULZI6>Dyo+ujluN~W7yTux_5MVeZ4O~MMyP>azG zqY_wA-@1l2rm>-=9&}K3byIC!?c#>jOPgwzwrU>Gu=QlDp1rQVp``__ZRAr2$Te%5 z7E-licrMmi&lMDlFF?$uAbp_5N&;%u3fG>KquIj z2TIOTh9)hB1rkw(QeEA=qF!>=uUb~$CIhPUZATNeW;CpItFi(T)EsK%(IgtJ`EWGR zh*@c^YiTp%sxmpy5EQ1Voe1384fNic#>TMsnsx;HXaL(MB030o9$&N{mr*XEH9@OE z0ifW}94Ipi(8@eOGC8TuZE6!7)F1Ykh)@F9+*L3)GH9z6(kvYRG3XgSwGphrFbApB z-q6wlE-t%qZ4)e|wy~E}xu|6rfnokv&|)+Z&(-d5nA&PSsG5>&~BI^;Od4O zSFI3lh^4~fSf)tj{Y|SEtXkXTj0(~RrM(99Vr>?j5u=b1IiI~H*8vO@995;o#4zWv zun+@+Q~nyMDvfe2+GOs6D`wZ$pMTDI++fM!>wk%1({t~b!1TYld<^NB zeV3Tr#I*krrvEE3lywTr$(3x&vZXT~QziIM|I4!{o;*62OUuJK8k^s~HD8R`@^dK~ z%71N$IHh>_AH#6*^C((ezI86ji9C=y4YB_+u3;KGM-vkb(*g{Q#1qGJcj_+81WQ#C z^9TNjzZUQO^pd>vn?Zo-{OSC$Fn!$Xvjy&90-{TlsERvq*3bT?I`DALg2WjP+$?!Y zmP;JCUGrgr@4&GX7XIcra8pG|Tj;>el9<4kIPeogDoQ0B_y`BS(t%r?=OIX^%YnxUFuy$x zywU>k&N%Ri4*UrRKFNXaci?9_@Mj$O6bGJl;8Pv=OAh><4*ZY&#^$fM>_EH9QZf~et`pzJ8+))u)nDe+^!WcZH5D%X_4{1#DULp;JyRr zc^Uhg=fE$uK)e?^@EQlc#DQyx=){BrpX1=Kbl{ge@O2LS3J1QyfnVvslMZ}=1K;Mr zuXfoezI~IsI=AfjAfBz}GqO zkq*4Yfsb?Gtqwfyz}p=7R0n>81E1l*Z*<_7IB=egvOnK}w_70I^Bnj_2fomOZ*t&E z9Qel^c*22icHk==c+!EdbKqMX_yz~Q)qy7+_{SaiHV6Jm2fp2b-|E2cao{{>W`BVL z|Fi|-{h$Ni?!dboc*=qAap2rrwZDu5zuN-we!_v@fmc}~c>50g-41-71Fv@A3mv%cz?V31y#t~X z6At_`2Y;mlpXJ^K@J0uI z$bmOG@WT##xdT^6a{9l@ftNY(k2vs=4t%u(ALqc=IPkawU+=)DI`Equ_zVZW!GT}m zz(4B1eFx6HO#7SXz;CfYycas~e{|qW9QY?3c*22ibKol-_@^BBItPB61K;4lZ+GBH z2Y!bG-{!zSH{E!3xiUU9Fz`yFil{vpa`~R>5FLU7EaNr{y z_%|K+I0ycy1CKlKZ#(d#8+&#iEm5hDcxuPdje8%=l+^!($%g=6=c(g#zaQ}qC;lPC_c`$oBYx0{FGV~yUCI{v z%MqXG#6N=gY$v`J@ug0@1@Wy;{6@q(ocKo(-{-_{M*N@?-->wbtX%n@KzyPT{}kf0 zo%kJyFLmOdL42zdzYFmWC;mCa_c`%@Mf{)>??60ucCP%-BRiGK_6eNOz_h#z#~`w)+vlPmv!AwJQGe;@JLPW*?6FLmMv5Z~&=e}Z_2 z6aP8l`<(c%5I^X|4>|BQHt6aNe1`<(b+ z5kKg}W0#}+8M*QYBRo6F&*@rB1vY@vTn$9f)^0@lz4s=fqD({Gbz`ht5Q5bto}??!x|6TcMkgHC)l;<58{3;&q5`b>ivh4o%lx(pY6ogBEHm# zw;;aNiQkBLhZFxO;`^NV&4?d#;#(1qU6?EX6NpcA;-5l%wiCYt@ug1uGl*~1@zYfD z!0C8?U7|XBOZ>irlT_*j*xig$OP<41>Zv6o`up#GKOWlOg_rt#sRzHMSM}nL=yw7( zStaK5A@$*z{rzLDy>0-!GC3<%IYFfahhe3jtiD9Of^lr|UX;;*JaMJ%IP=k#OCk7& z`I(P2l*wCpr1s9rBQ>|-xpNEhc7O)Fw1<7rh~_`K@!K+vyf#erwUXA>O;t%;i~Bk1 z6IaQ)#MW6=uMPA2j&9s1V~noHn3SjdKJfMREb2mjJjfy4-~X^3m*T4WCmffaG3l1y zqZ=QU@`4K0okp2Kh2LEZ2jo%bgn5qqHJ69w zZbqI#a@8|gH`eg*Qi&S#<#(tZOb>>t9Z#L4cCbt-KYmVXzU9kz_zH4mJZH3QixXk{E*gX4XrfV?}Tw`hmU-704vCYpUZcf$>$AKi*HA{ znve5S?Sw;DFCPwFnxM+bCv*`o zYE%IHG{V7WKUN3z#lnL}PFE8j( zW`Y-gS868kuy&J=1N!V2f|Gey>U@VM$ffE@&-4?cn}X+G6t)fVDL=~if>6d6rQ(D` z#ur6p{6FU8-T zdIB)YYAfDf8>#gewr85OPjY7JEY$mOp?;N_71Dj&(Dlkp`)6mRzDgL{?azj$l*_*H zx~gJ%%aJZ+ppT438NutOosgbJ_-}2e;h?nzWd=Wme*6^eaHK?R5b0M;RqMZJbu{~) z)UDuwZLtk)A-HIRy*53#G_}Q~Cv7_I*r$JYEPgJL#H#j#DCu(~!j@Yr|qremW zhKw>CZ_p1`5e6B3BPyfUw2V$ex|PxQ8Gg;k2d7yU z47ATe*U#mf@87?|6+KI;rPG8 z@p0PSP&V0;)GOeDG!LO)NA(I)yUWmjzD^N>zb(^7Dg;osjh8;E>Lb44vLm zwfI6qrvkPIc)Hy)gHzu!{B?uY2;iKA=beRc6GKv8F}S!(tL3o0fE)lDAO}^J3QXSn zjU1LBUQiA}S;+tWz@Z%IGc43RjSl6IEla(QbjtKHyrZ^FWRX1~q;zh$p@u8{b z4XyKw(Ne=gTJ44w^^N7?9e8-oI=V&drd<}xlb?i|Ucnv6X&dF-W0!!D7!%|;AM|Yuve;M$hw*&2(Q>Qsjomh{hsK*7!!|;1don}}X zZe0?&GB2<+CZaC%-{GfwaZ|6PVxQ^z)f=#XW7W}~Kd7pnYgD`Nog9`5#`;HZL4H>T zl9tWUA8+W_K%djV&sM7I;$?}`u?ui|09v%cr1MME*ZNjlFjk$2w)q2Lv()JHHJSEm zeA*-I-|^w8KJcVa&%?lrfGa8eWqV3iH}sfYq*3Q*0CoZ5qBE@# zoe9cQtC3Efxt{zYuL5pVXTEpT=uBdCDgpfZLUnU&R3mVxGrg=^vudXX>S|!&nK7xkfCtT)cGAcWx&Ku5fpfrDxvA3|f9b#bYFj7ZRlEJbKRIvq z5jQljC#-3>HYa;>sJriQXpr{{k&o?5*`O`O7RL~0+R=^Qk+lli3B_OhAz$A9r~T8v z@Y1|<`u|Yf@|_QD8mbOeAKmy!xE_&_b%l4Nf+<*+nBw;Zqg9{4vZugqnQ-FNR50Fz z)%XyJ8Irz8XG-%IeeZb$*jo%es!*!9( zs!H(Ur{!oTPS2I;pPS=F%}9~QU^DzY_%fVB@_jqxOnGPVJ{2+%UjTiE>nw5LoD5jV zONHN80bWMBuhD^)ZBv_WMSfdg!`nx%c1V{rKocZ}-t! zmHGkNW*+@5=qPz=fFD-Iab|)V&3FPlqRq;apsNN$&l^>h;v8&+s@m14QW($nm+Y$T z<2yFyGI@JG*3l4GPuKPhj#Hn|KTnsjPhf1nO3<5T%Y{tRDEH9<9T zhjm2O@pGr3{;_1;^f+t@MF55Gw zkNTf2QB^ONlyshnFl904WR@B0JXqp&dMGbjQr7v6N-ZA`c|>-HYx~Nks~xy^uX#|H zq=KCT>%ZxIBiG57^`$}ky!RM7_h~sOz&~MN3{xL>-eUMY%e2=aQ|7EWeP@8i^WgPy zyuWyk+A(~v^j-AXn%&Tw6xS#18lv!tJY|M=1v)>1?6j`wJ+D06+Z|lw8|360ed;mt zf$!679Z<$nlp$p!tl-Oh*GFDszbqW_PzQ9@LyZ4|xSIY49={@6Xi^9{P^A$>3%4@m_ZEP}h)Nyh@jA=pA(N zP_Ga#nUD93i-)>}cv#brdKh{?bn&)>-pHs7z8J1a_f!w6>X|u6&)>2Bv8@kdUrA|7 zDV3_&q;^XfV@4Q;|H*JqW2{}uR5MdA9!8#>s_&ib>-YP8u?0%=6Q3E5FZ)0jZSjhN zeGIBEt3r5v8a9*oqlu5V!uwIsVjHkr_OITO(VbrejQubGufG{4y7Eefd1q=m4Gx`N zq%(gO`5rK3CSU_4KkK;@<*|qzd1}BK2H__YZg{J7=H4fl6X9Ikf9hS%Wj;XNDg*lv~Z+v5rNKh*K$ds3r7uV?eH-94L! z<2ez}NxOSCs=l7ry!M{omQ-~Ze!S$Rso?QgY7NTb`$@ce`iJc9=`X``!tS0$UVDfe zuZC^)QcHn@FJRVXyr3nx*z4};j{&y?Pbr>3yL&E1InSx~o+rIrIX?2jChokrrn`=1 zA>4&`8uX+OqHlE|Z3%1#^@X});U$}V>6McAoG<6-q!RCzgH=KjfekSzk4!}j07saB6m3N$A|W*0eh?f#Y>PsXEPSf8aA<^2Ndlu@4r zWAzyHHH=+$EP71rmP*1FOi|tNWl~$b!>gGzJ#Yqs{0`J18P8n z=^q1La4zzli#c_vI*AHa?^LOeBaiqM$X|&t^ZXZSqs*;YtbfoFU{7v{@gLWOvW>k=^VMp4xgq{0#8$pQHyEZY$Nr0M|S$?0y|^mg)H?N`G2`@@Ur*y1yLq z(B90~VBi6GMB5)y^M+$Dlzx+{;+rzN9D7hqV;-qT;>1)l@(KN{rhkp0lO3F+gYj2v zVU2;=GUpiF8roC(Vi*(1%cTaM!Mwf%a$(sIpdK4of7X5aLXoHG^M}-e;VG7(u$JJ# z*A@N&BkwjW>BCjI)vE;NRhACzxo7H#Z(iir5$g>XfgdXq$gYa~Yym&_V~x@3tanPX zE-?sueeZL||3~$BjlBC6!r(#16xLT@823v66Imut%Ck4mVw}$RO|(4;pa)TUNo)H| z87fezQ#8+Ex#yt4u^R`Xu^_GWfD`-}CVMCP9~Cu(RGt$+`pY)H)sF z{Be%p)Eb=hh-BUOqBs|7I*kUWVOX**6UBMBR_NSfa4Lr<>%JMq8L8>)1kP4GY2bW0 ziZemuJZ|Xp0_TA!&JT21&jDv2=?qQQ-KTN7Ouf2Pm#$X{>P;LEJl|Kg5PveNjpBT~@9|GIN`*6ns;9TPfq=#Qe;dM=neCA9=)q~Tu*Ev%7neQ+oC z13PG6upUNu3~;`^hfSOBn$s7q=Yi%F&>-!fkv7(%1FY9_OhaGCSgPjB9D;M|;FQ!X z)`?-PVfUge(HF-3Q&Va9`T^2)UG&;*IJRQGB|MJ9x*yh;jUOxaXppsoNK^26VMFEo ziKixM`xl&=dLHMX^6l%O&iRnLE=${2OP@5{bwA-3YwIT(-eU=@t&8o}Zxu{PEl`%0 z^;L9RNnWg-|CO>qo?Kq6p|jq>>8bZb@(Lf2xf)kfWzQn!!Eh!q1OF=zhCNT~QyPD+ zj&;bxG3OfdU`1%{jnLO(fW=`KE2gmjwk!^B&EY72RuJI#Gzc1i^3G^Oz0O6V{(P6exydt#|aLg;Gao^!}(6V(L%yHbs z%~qry04{v8X*+?N8_x%Ker1;0vGX~sv6OhJ^dwoc5!tZMoq4t%%eL5Y2K9R7Smgxq zqUHQE%0YiDA7kv$@%rz@lnusF%Ero?HpR;KM@SE@p&hb&L!qxO{GWohwQCOjwd%*& zYE_l3*7Jg_r3wE@jr2qNHptpY1GhE|`J-#@U21`27wJp6K2E~)@kHeSySfN+aCJ`V z16sC!+qf;;)!|2R*2UJz&SwMo9WFhEpS4e*wO=JiVt$=G@YHLfANv*dmKmQ3`2lsi zm$^W%)A=J|kGxKd=~$P5--`XEO_RjdBF{+7p9cDwiOIGu))zE39(FOkQB`$deTid6 z&@b&Ky!?aJANZ=?cWQKdBD`z7-@S9AU)2FS`U~tyOo06fJ{jBHp~r#!9_k_W0sq%g zH_&f9J3mL-d`)*hjx5OYIlneW@UhspJ&4vZ<;zJEQC_{gKL25nEhnjH81tNtec zUhl}($uD z_P)CBjDxSnHqE|w_K^?WsX*69UeLacW7W*F)&?(V@4;(5Xz(CcJGy|u%?#nzaP49Wv^}L zPk@VYv)tMk%Wupn!;><+X=>&8Md$-^ew$@d&M31x9N!D@rk0(Gv)?)XT-<_X0H0+z z^xNG$Zrx+xD?U0|=WkNuoic)VxXck=o~ew#F+{n;ja;!zu?b>GUy zwB>frz1fzHSfggXPUI8aL0g(JPjDKz#yv6DmVs_dNi+44Fzb^5Zhn0-(x&e!(55G% zO%=+|wQ0zwrmb~O!sPQ7!)FqFRvMjqht@g4*@E;N9X_)TpQf!eU8@gro*(*vcdorO zzr14-)xrOOEq*Kf?lk;jfpW*6Fy^t3xN=P+{Yr=5W63oDZXvlo3%XH0i^)}NM^2x% zi|yE;ZO7gcZ98Ux9{cQ@ZIkDakGeA+b$ry+(QT7nq>pmyc-%J8eRRIt9_-(=3%d%` zHQFXV?mAJg3$}NJHpW*ubEy3lt$PJ!v`))ti;>Z5Jiq%EWVF-B=m6HZT8)fOcJwxl z^e13Pt*y*BdK>Lu0dS*wVC8dN0r~tcqO(>$$D>@4*9LB!ZvF_nR9fRm8Q(?$0{>x%Je4}Ec0L9Y?%S;w2Gi;ZL%_~8f>|eFe9o})E4H@m|4rPx`v`}}FMRbSb ztXe(68OyYt`w?hH?Z??~(JoIiJe~?3A2B?-`pvc)>F}6wcr4gY!Ds#$s(Ia2fY+#g z+i|m)JZlZFe>h$3pzctfuDxO#{~ET;_QmY+cwKi|0iQziyP*KTQG3OCp6E;Bj8t}r z>gyk&+Os44_KG9p*YC!hPtuY)Z4%mDr;W{}Wpo&G}#t9--ukAuhZ}? zACopLmzLCNL&CHn>u=2wzG4o9;_k!(eWaZj+;~VL5S^I3-enVe< z?7>8Bor_T&&&&^XWF3Z*7Aw zK5@qStOeU8UW7mDa({(t=Xsng-q{Mj-Rgzym#@=rgAWqGr&XJVFXCKAhf7Cu9Am!= zE;caisq<__2j)6EFZSDaUEsGv8sUT2M$r|eMXBSss{m#dlQD|F#iMa{p1|xyx zr}2D69DgR4Yi@(k@9i3&oxjR10MtrrX0=542a8LLBP?-D#Y$k@n+UJMQfX+fvWJq>p?Y^OH%~ z@8np$+U~5c?f2prX}=&jB}Lvaw>_G_j$Yc?ezEm|il1{oy3y!1>kS&J)YKVw za*L6_={lonatA9d| zYa`G<8|Kt91rO$9QkFTe>RP_$%ezVB={GymJ}IpIZyoy>K4^Q z@%!@h(5yS7-(uh9DE4iR^6pd8*etmdw;6qSH15d_(tTWD8v#SV^j+9ZuxFbwHa6nD z5$_dv--P$|s$KYo{M8fs4s`Ii++*yX$Uiq9_xHr(Y7ftRRHFX03$xfRFX9{;+s$nk z-eq9BB;T3Bo+fyP4FkVX8#a&a^CInowqZ06N`27xX=jXmrTq@&>Bu(5^&{*f`FVX? zug`^c555D}!)(30xYjEVwwL@5C;vS;{`EZ6xAV|0Psv&NE)`5GI42xO{(Exv&FU4# z6n*9bK7^*UryG7d#~xYZha6+R=EGCdwOkWtrFP=1+WEhSkAe2Ez6^b; zY_+QDovHVNxUL$HXHLzQ#HVo_7e0)yQi(tBZQ~rbvNQGGQ4+e$eI%Q=K)#R;^Kp&a z`fZk;GV7!gXa9<{TY$4rh1$*H7nD=t6!sx!t;e=?ZmnMOKa|_Il6bbZ4}GBTYro51 zkGHtsRnCNNfsbeLjX!ok`woV_ZBy*Cq%H0;eGY)F;$GSs4x3GtQs4Vh{5smBPML3hVW$A6x<5!x}u>2mQE8 z)=qBntFT|geR$Z!b5ortD`+)1%?9Us2M6DYNk`;jby)bJEl%QWA@(f7J5jI$=tp~k zMniW+0lLAA)NL#qWeR`bVE}*lCd}4jm0id#n>FiUp}u@v^Id89{u=ovt>_q`N$EvS2*9&9(XsNa}FSYBn1!}N!_;k`Dy-(}XPDf0sT=oXW&3i*D{_A%>Pmi88; zp9|l|_M`0a{2M)n72F%y2l~e=@qLlnT%NCSYr+tF+0YZ`Wc>zt$PkcNkw0 zJabGRTdbdCitF2%Mf!=AN7O&uY2^1C+!6egk>42dXXKqm`m?Z6R(^pazX4+*aPxIo z&rf*gCMvgqcIepc{J7z>2Ye<9@VOW1Uw@N)W{U86<(uMD@4tT1vvbzH=G?A^_e9|R zkMr(uDb8Jcsn@3Cj8YH2AMuE)S~$eamDlCXy|*jGJ@_I%{YD96pZI}0>Z)<(|2NQ| zD{=1KromQY?FDuV^aPd^TJ4H=Hn65-VW8J;!x)p>D^}}uR0{*0_6tFmym8&f!yQ(R zaXaA;#-Rt^wmE%?P5zznm5EF0!N(Txab%F%F$HF-*pl+rn3~4BEjHYaZ~`!tzuw1vX5nW$>yI_1OK+*md^rfeMW!|lUKG1&OC8QR zV9QO-XPz|p7;NQ%e1K`WA&h$3^^EOGXzFuewhZD9M_$ou`Z|^9oA^%1F4R51*^4;! zU(MlK7|u!K{?P?E=V@SNfbl#-EDQeyZ#Bm6F6laLl!Qn6-KCTT;Dc~BpYOqC`aPsn zzsVbT@2bT8PmJ3*2T;~ofqomMukOjT|CT-w%eXJo{;~}RnfBk=@UBez?``v_Egd4`yneEJzsJn z&QA`XcCcg^{Pz=ZU$m_AU;&w`tl2wbouALNix0@~OHLhLcIt4*sly+gIvjRs zcGCv2-0$de_p^QF{2l2Zaq_CYVY%MNb(_Vu;mtda@mZ-~<18r8=N&8=!np`&;%uHn zbBNIoHEyr=n@E4cUOg9MIG&@gChyI)&D6cRZCDPzefdJkAjqy1WtBj7F_h<-@`iNY z>69nqGU$5u7+&ww?~=gqjPIchq%o*-t3$);w3_Geyujgkp~LfHhvy}RXV&Ywy;`5h zzyF@pizS26{>AE0*16OvpWnL_J@4`#8|5&LF zf5(4pkPScKKc*NaFTs0KgZ;$mSvhHu z_u4u2g8~ol+X*gU9_Cdxj54b#+SK}0$iw-V!gCSm+w{Fy%OL(RJAR`qmIIhB8}wlJ zs%X!ccM9^7f9soCUy%32dd^ktb+xdC2xC38FF+jS?57XbaV}`WKk36A3O9d$Z46^w zZ1>SyR7&n2Um$jLzxVW_B;0DD^lTHRQSoQ)u3-)n%W5(7`x2<%;JW;Y^RVEwgvSuH>ER=2~JL z_Une1`tM%D^ToG&>%T->!8Hkd6Ypz)(=T1lG~VyRH_#+4F*NlM((IYZaP5Qk4!-Ls zx{cLBbo2>(~}Z|``9`!D%r;STvH zqh-ZUGHatJrT&*KON~f<>`j+t*7<0=DHGh^TN^DSgLC4NHZt`kl(Cy@BaEZ&jZs`% z_r$1F2XJ|BR&c@lk|=I=l%|V)>AQh@r^UrsbQN&j@xqQb9Aj<;9@|s_hu=fCX$s@F zw;gBnv2N$yVLKIgNE>6%)@NVQZN0_n0lr;!URYlK9PQh$T0Sh?$P4SD{T z(pU?<4RivoiJqmuZ7Frnj!vBdxajQjxiP7dIz-$V4sK#h>LdrZ24%26a34l+F<+`g zU(j^Nq)IIAksMu)>4G~|pQRVv#L20{;8l14uBDqVV?8ewoO?hIV|e8+^&NT(`zU4S z+>`EqT!r7evg1GcY&Xvl1h6sD^91*Sw~7gBeewjP#j$>Pl3I+$8N;z%&EOev*h2aa zWnu?(*w`N8aK6WP40o$79&DQU#bLZu`}|?NO#A&|e7Kn_P=_wm^Nv1bDx z+WH1%oxeC&?ZDsW8OZ1Dj(otU`16JM1YQYv7akBU<@}E2tFiFiOX0hhz;}<9JEZe5 zlzWXS*Moc{f1LM$&9}PDy0pNLB`4&eoH$3aG!*2-xn3BDoMgTye2s%oJ_tT}G2Y5L z?*eaAqr5%wH}Hl$dAu?1^2T@`Z>JoWw`TB0J=MC3?`u7tf7eIqJmWI0YL7dgHrg@-3&H%^tqpgYWC`ZlcH$-^}A(3LCa|HV!z}4njEZ zrorze?JuH_Eeyvrd)Hg{P2z{+OcvkZ6S@;pb77}y!#vhj7082oYLW-{2;Yr77Zu5) zb>iX_`ZCAo_j*{Xx3F-0j_Y*Hlg!@BX{q_v#+WpW&$2fpWhPHc{qzNV{}Q%dL2q0; zVr}ymnTGYBkfu64brEP5!u4Sre~5Wkh>QD;(~IDiVSEQ&`L?d`;#Z{NMQ|78<8D`( ziqy$Pa8Kd7P>wFg)k{ zp`Rq@l3qj^Tn~)ShcO09`nhJkuvq#{1JX4guahqHDd%@;c#YAsDEzh}@W+byE&S#J z`Z2~m+FXpe_}^-30~*VstCxF0d)gc$At&;? z#qtZ^CTyell)N@-LmN>S{>kzWT(eJ%^}H$OKDG7bN;_8qzX#t*?Q!p5v+Z%7k2(WA z?tAQc$P_pM=Cwun@TcbSQD^wL-r*zUIh&6=7r4BSi1oDtEW`UX%k%qMS+4o60n5cY zBj@Q69ernBxfg;~f_D?41CT@AI}nz7uuf_kaQUr9)C+C>H11aLeUN*9dha5iwoiO3 ztCG&sKs&&E|2^PqC-`GpC3yy{%kJ#21~_@ac>?{NHNbyNIAGOyvuy{ImzbVcuNTikdB_*NXYPIejyiQ} zvhI&Hj{SHv^bflf!nVIRV2p;m<=b(Td(Jk8V}<6!$rIWL17qJm3Gx$u4U9J8)Y-;H zICzw|i#HW^B)|XYazmTzl-4h- zZCM{KfcF$>Z_b2g9;|(pa~RZnhmY?>XkNuJq5#cr51?u63iegm-+upG|J@yE`yl!0 z1BnlR=~aK$ldr~4{mrYs-0i+H|86(#g5&(vlje^2ZR+JsPt{;;xC6Sz@uDL%fUOjf@(gvXQ90T>1J2pYJUQ;kr&CalkuySh`5!%ge*akcGsn+g=!_Ej3)eEb6#LvV)h*#; z=yWiE2je?2|H}OQMP(T|pBegJq_H}mMnO47&SvGwF?)PD_{Yls{PFWAj+OtV{QN~_ zVD-tlgOXQ|m-Fcql0$GTJ`UyQFUp6xyR4jhZFzkB@lDdv-zNyq+!`9&MXwGEjqMRz z8OG&|rSm<6yu8Yz%?)u)J;Hcs=OW)n$fI#2zx<*!v@G(z<6v}C*W=@&o4K;J%?;xm zGvbkZRC)Qg9Y23Ea-S)$9^>+5VRRy|{NPymCmcV2=2-dT$IqWVR{qJy&mX;qmRJ9& zUi(+Er*3SPZj*adcR$v@@?iHJU(SgF_W|-~1jnZl;G383dAvMc=N-SUnPcT&aQyt) zW946X{QL^v<1EVm;^XI!A1nWoURBw34?DM%yD*r0DIa?SW{sy7=MFpS^<5Rttj>KK z&Csj61atGOSzAeB{+h)%p196n%bQ`+SzZ?F1O3p6Eavnc_N(}&o>b#3(sRs9IN~}T zb;TSQ3q@lLexKkoAN?};>b>VCyAPtg8hm4`68j1s_BAbzhjWmY4(HO~N%lFjXb;6S z@X=fCS251=vDUK~f2VmY<;b-_zL}QW=P`H3dhpFM)T0CEUUxz+yR5EajVO)1_>*u3 zSK5nloZq^Sd&_Kp#5)k@dB!g~FryD)9uIe_hJgm=tL?+V2hQ)e%ilnPj9F*Mr_a*6 z4|tN!GoQdu12=$vu|C+l;aURL5bU=o^`28;*1~2nFZBR($$)2rxqelz@GW-0xR*FL z3`=_knC}PmT6O{O(g+80by*K_{}}nurhP$uQvPO>imM-!U$n3M{T{n6^;P`c=ieJS zv;5bU;ls!M7|d0<&((7+%Ep?R@PT$R;T#{=8a{xRMmR8SD10EF@NsPcK0sUez?X6$4Rl!Y$A>_c)uw*HOCyYRC}~shxR|(7zv=?@GyS)p?QFi4I%~jp%g&lA z>!amzU#n1_?7%$u+p0UhZ`wUyFLQE?%CO4F@Xg9jbhL=?+Y`Jjl=04Ye%4 zZAV+a0H;26P?l`#Wms!*<$=3nBE!tt17!G%DI&wLf6AT1A+WO*uwg^;%i}saVZ9Zw zacAi}NA|8@m~RN|s>z2k7b7g~YVB}H18{Gi>Sh~Q8tz%7H2$_nv>n6_pnOrJR(oFZ+;8}{r~I6K-f;!hhxUp+4xYU#Tzj z9Y9}?_iS%>yeFLFy`<~$ekAj1e96Z#fa5*Kz&OWzl!b9VO!GLFoBY&i+Oh=dfp9r} zoh&m6?8Ui#^McTW5Fsfue1Mu9J2E+5zdz&~>(Di7f;U=Slot z*kQY8Lf&R*yI}L!K1n}A+d{i1mn)xTpuBKA83J5e?w5aM><#GV=g;5ovinUeH^BY} z_G=WYD{IUccggP-`U!^SA>uHcc)UtvhkG`Rn=uAwU&KD{SN=Hz?BkthsvTlynSZLj z@L9Nb3!7VwzQHz&L%%LXJM`bLs`@cDXJPL|KQVtWVUa-wGRT^7C=0w^ zgtPGLN#_U9CE{`n&vFbe4gI95Ea>*$51-VO*^6_WEVB}2(jV>LjB+t%XN~Uwo^3c+ zF2-}v9F+xLFT%jhm21Yo?952Hpxe87V7VoxT*a{hdmVay(H;K%qBPGTu`i&X%h`5@ z>BpT5IQ(+8u;y^+TXO%6urj}j-}#mBaD?ALnE7U*f8j3F75eYEcJu7L_P) z{0$-8hn70x@3?lS5vC7A*)E`dA)ok1&8Q>yS|WaE8ahK?75KkRqAk+>-~q7a81}x< zzvGZO$x7ho@@BVT-$_&?kb~XO?h` zMqcO}^1Y(4&)$Ks)C=jX7yeF+%z1uh-aj>Ow)xSG|8DLVYP%w5(J=Sv!JMb(Yp@^S z3pU~q=Qg4P+-t&_vyKw|xA7+b7xqpe2Ywg5XFlY?e#*H8))P!v_zEbS`9?Ot!#8x; z<|3PiC>!Jx*~~94n;6c^v25BW)}3|ZdIx1pnN?C|*O)TEPsq1pTP#fM3uxJRE!y}Q zBNu%8R^&xm)}9>QxJUO1${u~V<6g`S@5bL;#n|`2ozQRE3Db7g_CJKaC4V!I^R7jZ z&mw$3ex`0K1>FPhc#zNbEz=*^M?A_)$3=dYrkr~BukPU5Fs%C>=WQEJ9f6ldIJj2VakyzqspH1Nb^JeFpZ_#E zZr4GyEqFp~!Q18w`~S0jVSBEC>nX0UX#3(Y_5<`O`V-gNH3fvz@DVFz&g4z2gpGX{ z(sF0ciu-?ZUenO~Kwcg*e}?T%!-wgB4cZACEw%@9xzFQHEY}QZ{{z^-G{Ur}aoR_` z!B3wz8F@!*_{Zr_fk!n}jgqkiIQ(`6#*OYYZ3N<*5vNWV|Ft}~#$?tWX$QGR2HEVS zkAN~*zE3|I(O@yJ>Ca_O_Fb|h+F`hZR(tx+veIz{2;@BfVv3ZkQHTo zg4Kh`rVUKJJ;bRW(hhiU3F+&(Ksc{2(Y~maQ??{uPT{;BaQ^LI%E8X-|0Wt^-Ub>I z@@YiZ0qB$bmfwMeTvcLk73#J=iNA@$csMsm%t)cF_AC5d_UQMnZl44lh0JVQh)r_V zPQ-_Y{@Jx=`W)E`_{wN^ghkK9M?Y8FWLXPFI9s7@viRu0rA^MB3!Civ=*{qz@jV{k ziqBdpbg(aiZ?uZ)JYWUxkkN zQZo@o9-NKt9&d2TcSki~=(FygjGP0M{Lnq5qh6!9b~6AE?L!#SI%ywhKQ8+@+RNl& zS!vQYe)sj^_pa?)v(q=~;SXJl{%7hf{qI`bB}SXu{#VJq4w%#p=Q{-#b;KHT6~@V` z_$D=8;TsTb;6Z#1ErUMd+4f8u8G%FIji z_q}k3TQ-Zo(ATJe4qp6E}Y+9AdP8-Xi#@hCS`5)FXt^Z+(DDjRDTR3f)- zTtd0i=Mle5iC@M(_QSuj%_2TU0eOdO*$&O$7s*@5R}6WI=Xm-R^1D2-{mIkrB6Oqm z40&>Be$UDKw)yd>^Z)2IZFhfr1oUczUN10xsqWp-Md}~>SD}7#zDZY*^WP!|EC3hW z-?p}hd)$?*>!t!_z^P&t}Hw)*Qk>~sEm9VRovsAg~t9IgLO6q@N+q9Q|=K$?P zT-eTbi(}g}{JuBmlF!0#gC8h!Nqp1x0j$}59^=&)Fm~`R{A}2x8rmex2cLv5FMI^G zeNsoju>URVG1Lk0QGOBXfb~y)PrjRXhC86M;#&e2Yespv;`0KY=2&=m%Swc07wS7r?EF$h6$SiD9kF;&a`L_>~x=O3L=0+OWw3 zId6Uq{}w3V-V))b@1n3B2Kv0zk3Hax?{Ap*4e-U>b{o(qfNT3(5E+Z@93bG@EBu&A zlqKu}5VgXpfDM5z{=bo3l?$o+I>K zoQDMm@`9d)J{7(p@K0~p^Cr6Q=J^_!n>~m9X?~Y0YwGFKMwxnMt=+ITHnMjuHd0`v z>sJ|lqAyNby`bU6F-K+?y6s_I06O07p$`z|;Vyurl>laZjhxSD_RHLLg3Wnzle#&S zHOAerZ6GIx&G=A0%cQF$_C3rx{U2~Ps{?ezK42~SQN%fC3aaz`&+@a8muur(ug08B z-mr;cr=LST1&+8*&z*-d_8s~E3F zUn+DSDu2y8XPX1lrdB4Q{|T8qgt}W>)nA*x?}qsR{C?EoI+4rzO00!S9QiPh=b&6Uwn_E2741Bzg%zF41VW=Kj?_?%DIpZ3$Gc@ zh34wMlLcNc!l;+XJ8#WlZiH9RjqcBppAzuHaSmaO$$EcI`rVt@qes2uOo>Xy-qIdD z%l&`4N1y9|W_`r=Ka4N7uUTC>1AGR?{u@{w+Hgz|>4&uWu-lTq5;j-PSXD!guw`7s zGwrU&C-moUz<#rB6ULqlBTe*A#eRamnnsxAvM5;VqdUX%UZent)x92^V17JoAVItb#ZJ{_#2>d zzR-ka3}+bqQr4p=7mUAtS>{x<+pwV4@DxWmuo?0#4AR7U1KY3x{ZsZ|rT|7eiZL?K zVd;13FIZc|o{O~YM$`de_>sEbm7xy6rHu$S7N`UG@2K^=)99@ip`Nlq8&7b-g_uLfn3i@GK`1bz@nl~A~ zftN-Yw1jWj>$ZH~bbP)~boo9GpLVZ%tI>I^&B~r9?aa}QdLJnC6EmPx}E-6Zf&OgV)hT(e6AH>EXO)vdmQV4k_TZ)3(Vgb zFnB)F*SG>HSaRi~+{| ziQp&Ax?%jM%}|?47Ksib&NgBi+n-@ohPI}s#4Ix9ICDZdLp`k za;Jv6q0jRl-T3#>jr%cIbNkuyzk_bP_x}>z823L&H`3_a)Q?fBG~PBR{l#X?rHe(&yY3I5EU+ zeSMxsU_P7)WVs$}E92g9e2+8F|FH6K_ExQr3*RstJD-JJw&Ue5Oqk;(=NixY;&WUV zk(1nw;u=r3rpnfV-?Q8K3ykB;gS5jqCz$j93)pDu<8u72@H7t`zsH*}$M3NwOn$i5 zR)O;116>l~r-AJ@7HQ2G3+d0=@w(agLV%|cmNYwF8$3TUUSCaG<1wGbyftC`qbmsG ze3tzE6#m0c@izJSH!WRXisxP>jpH%f80B*Pj^n0`&!mHIt&kRUXnh06dW_eIcatvH zkZLe~_Lfvm!#e9wreW;t2CnA8=A~a;Bro#G_u`pvR5TyweW^s8bdC7}_86n7>cE&i((}wF-KDtiJfR^L`e_89Z8G}irSkDvZaejmj-v@yYS^a~&3DAyslRw8x}% z1InLX$>>4wc0S-Sy zr`fU0;6=x>cG3ne=UOtSH-C3k=oZNF&YL=PP+x+Ck&OM1k`^Wh>%Yy$T zV;$q1<5i=*>oL|@T?fpwKFd7l6Z6m0djfIT8^LG&XX30k&iwFPJax=l0@+k+z1T{< zz?mwcgEWOS1)BVZ?k<$iZwPmwOsr*ye)3zN;IA9LU3jjAI(D9sz0gJ+d=C@-G&IvF zPwL4!SRR;$Hi=`-ng$P&2fQ+!eDExXD}x_HN60JrBfU!D(=&Wxf6w9bk|KQa{7oAC zvHq4vu4l6jIs2S{u7~`u4m3ld>G%p%$?uJU#oR#g!>hsk(504 zESOWa@iCb%N&gjg#HAr?O_Y`4gYCZtwCML(e%_6^_}WNA-|rS3arb)&=YEf*t8V%! zTx-{H=px|s*WGh99M|9vg=waEzKFDTjL>cN})$;fBUQmD?IsGHk&ufX?X>^|>+KFPV%{TK`G z&E0pQj=KGVeS8<%W9QwVdoOI){ooTg@WU~WitH6bFArX;s-DBR@;vsi*gh^TyYIwv zfzbIXNyq$S-Zv88)Ox~g##zo{1_S*``vI6sRtf^)< zn=sZ;vl|iKnEM;I*_#ljyeFd%Zq{q6(8a3kO%fi;v7#5@YWOHyxEC71?M0mHuiWc& z*I#>Y%3z(eQr27nA6n_Gy;7gKUz^{)j;$LD{f_8S_zjett(I|&drzJjJAQ;QD^EY) z#GdM8@FC}GK=&=$uR5#Se~bO14A{RDdR}kk;hc>vu+Lgy_RdTm*ob59sq&j8f3H1N zwq0&b#c8|ajJe$NanQ9HJm(Wby6uboz>~Qk`X%!3;2b>7@f`6b z=%?VNobw9mOxpBi&7U1d^KA$2v-Vxd{tbMLIel|Y_%clk^|Cf4m(R{e$R}-b)R(x> zmT$*)ytyBvX8E7_8u-Vaft)X+U9;u7b*3K5+{Wbjyql-Y>+LoOxhboLg`$HiE}_ zUV4O{115Q=OUe@;dcMpDP=`VI8@K#EPmKOK?+i>w`X)7=Yh3($ejUi)TQX=G>w7EK zM0&u_Nv7T1dRd-WC&jZ7+~Z<-W-c}(3Jz%BHcYZ!Mqg-_%(Q!CUM4=-=tZH@7W-3bWOfz^R5AUkn3+k!`GTfV05hm*?+7KCPT!Ab-!C@(Oy&4_v-3gm6WE6I6QuvVh529{?S-~jpMlM=c@^$d zh>mfr!S_()yePsGa9)+T38O#aGXdVoG1Gxl9&AJ7gO%rGIMC?QapwuTXLa%F z$T=*red7!GCMet0BaZ!P;ISS!pOWvJ0GEA<{SS4M@6_|$w9B{jb*wv}{<-sBpjQpw zbT;a2&wH_MIo~AL*P}LNqT8l+kB#dqMfTWex4G_-SH7{Sw{suE?y*%T2Y$!G_&M)F zTl~S;Uh-3iI_7wF>;uL!xn~9&v5P*Hu@lxdRFZeXCTkm#1|PUfDzfF+fjc(c)@S-h z$9C*OIGB{|zT*eZ+y`fIMYrPl?Ir6pC_@3BMjqNW*wwmwkyp#Ouz%&Y`3a$nHSHwY ziS;JU--L7q_D9=RfyIYjxO8Q2jC26!BQ}EZ$yyJ4*&dAJ+v?I+7#<_{BgHn$+}@m3 zv*{jel*rZ6!C2lvzkxEqSRngwpo{TjeU@*er>PUf$N4bW*K&qwXYIX1fzQgptvo#7 zTU?G2c8_bEX;%;OvHWw6V|no54{$9BeBNgA3toxA2VI>Hb>;m_j<>usx$nvRHVem$ zw_^M4y{%e(fA4Rifq6D{$KGEEX+*}4IB@dDuHh~hcAh@7Yc+{c}QwqTfRzPerX zc+N0o#Pe)N|aSg^$JlJOesP8>FaDk+e0CDfy(%uui}mBeY46 zejs%RbUd!@XkNNuyg@SejoiyVEFq!c#ADv4H)Y~pNsXAbNk3AbXYH!j>*%2Jj9LiW!pI%@9F!X zp2xCnlPO2^Iq~Tt_RZR~g|M5}A8JOJ_*+mu?OqbT-}@ma^lKSMydw5Z#z$k{wjvL0 z+cM-Mtu$?@@t2B@k62gPiLp`U*vLcO+6jM+Yk1_H`tu6@j$C+;0D82A_AGy_EI)e+#I+EEIV#-Y0M zqaD>XkuPl@XpBT3DU`?MC&_-3&xg#9#IC|8cllu7`@vi0L#2xG{-*gz%nwcHR;P*hB)+M-P^$%UlkMQ$Qt;3t=2M=N$D)v3;4>%E{=sIAPX zt!Zrut)1G@{%Uc?@z;4YQB+#()JI!ME9L+FuD$oU=ib}|=)d#%KR%|Fvma}(z1G@m zuf6u#`<(lh)+M0{G!MW>9l-s3#^$(g4ZxolyjU~Md$C-XwLLllzLLKIz;%IpV%$yN zM?Hic;rs}4-PLvq_R!S<(Fd*TS}zONLRYB=Y}=M%f1tQ-9lsUBxgJyahI){vEU!|! zj{9qZL)j?cLJUjhV-x2i^0N15IpAoc9M~uJEBBj0>xLhzH6#@e?!}1@fc@L_UPMZ$Aq-q2p$tFGjL~k(OQQ9r5-YZ~UMSIAr=26tKT?XUp)N#P$UGD>| zFM&_Y?~ebGFggw|V@2I3EZQ8`?b$A*(>mVDcWjCb&QA#riS5WS5nWe-M3f>=Qm)atugpjONGP57O2gLf>W{ zhZB2c@2CMUKAbh`PAO$vV+HKB9qTmTm%Mn#<$p~_5QGykMY%a zB#prj^>=2^Y;NIqg@=q>_M*?F{XyuuPkv_$GH~yur^>)W%$w(8(iUyxejV&1&&9m+ z=}ySRtHW+Q1aU5wn|Q=X<>nlLzmd$fdH^=Yey$q&6z!YZRKHmASOb_Rz4Cnq?87l0 z;$uVa`j}>na4vq&L*NIN4e`mfgWtt7@qu5xEqi<^ucB;=>odxTbJYeB)&QD;mHH~791$sXxgD{6JV9RhWlicwb*;;17Hd#(w?JC z;sbbo58vBo{s8x$cs>NYeEvv3&01zhFX^qPKU2S8*mnW{IxqPw%Z=-K;|$mrJhUCU zx?TBxAw^Hkour3$$Ltee!ajqoqCEoiY2zhGPLflQw3P3ezxJ@&h6Fz!-^^j^?Go9`H1xVM^q z%#r^BKKgBZFM!{ONTn5PjeIlN2ih4Mh=X?r`iQ=8My%GPuj=>3#1{Zo6R!BX$COAB%XsKedAqx_G{uf zgD5k7J2)R>9pQ?1+nZWJzoC%}%Mka^fAG!0zDxdGqAe77{? z!1EfmO4}ysOJWL^#1ulaFz?yFC(aO^g70L227J4}F9!T#OKxz}q7wtWZ}f!rKL8g; zI(CD$hqN<_uA$fy(cv-VI>@08=M8*!_0`*Io`sy57atybAX&#ueh%U%>Nm;?W1z|G z?PI_AKJPuvi$XvCOWT{&xaLaIM|f~Z=i{0Oz{Qc~T`21H9NI&}!{a0K z5HkB5(z_UA0lk|Eetu1P4O0L1>3#th zN7{TtA?f!$_Kngn_hvJ7d=C1=eUF8`44>4sV;DnMFQJD!)c1?i>R~7ddPW)RU*@Pe zJK9*6rWxxvWFoS7(B&WR6S--Tg+o8!K`jfw;qE+O)Of$`or@2SEQ_gp-w|_h5dFD4 zLpEnJ7yB_6`=QH=f#W|$n3E-oFemr8^!KIy27=7VJ(?H5#gWE0J%-Q8JtOmyZcbK% zrqh{|+fQSho&~PdIk|{(OR=N%j<%!sdHAh%(}}rypXL{Eain9_ir=dtPg#G=e7$dE zp8pZ=HS)LUIEEddMRevKw=e9+-E?C9+@t#i9DdJ3&T(n`lIG7nBll_S^&se^J^pj% zPaN%NBe=$}?;wBIP}}zS5WahKw@Y^)--*+(O7E%LcWWL1hxcg!lSWtW9+`)9y7Kf7 zPES{UJMPqTx+0CPJO=#q6AtZi`N4fpH=WRnU79z*#gT@7iHzjlm(ht`BlGqPyqD_Q z@Y`MdkfEEFzQl&#uKNO99BIf|`bx6lw~ySHvEj|&Ey;%Obo)~K5jEBc9o(t=1za5I zSefcKNe6e1((hl;hF29rpGL9aJ*P3=-v$4vwxJwlNxy9~+m%UTthZ}9Y=<0>j?GRp z*4syx!#{e*daH{c_j=rPVyw67z5o|TIyNKCSZ^JqlF!m!=u(ryvuy3mKoz+lRF%$&WvZ zK15gG=am6h(8|rXJbvC@;5xDOg|snG_=4{F)e7w2Bu>Enp*IGu_lrCDu7QaoFh+ow zvD_cR{#<-}>WE6qSjif^M2{8LjX2UqN5n4%ti%bHq!}yV=2?nsSCKaQvJU*XYcS~H z{w2uYkd0m1%coVpXxQF<561zpaV<~pek`eNYOyG?Au21fJk?uS39`n))`pmYDliTJDL!Ap; z$9~PZfQ55`IPxWkrQ4Q$mDK684;f#5hW^Nq*ieyy>~S^ij305ZcK8lyipm z7-y6(ppG%8J0V;4u?tV$!{FYk75x=s?-T=!oNb^T&%HR0r5~;Hyx+zA4vnAZKlG8z zp5E~4-swz<`4nRwTmQ1V#<60Z2M@yr!|vdHBYE;Xj%PP4vw2sUHVJ(3E}o>p2hX`g zx17q}qkg}<`^397eD~=|;2U7f2WJ;!7>{Oq;G{l!aY=jY614ZBy*Cas=0G#X)AYsI z-C@Xs`Q!WsBgX}MIF6MI19=*lZ0ZwWg4pw3=!LU zB7Sk@pRh;y=%hX8Jq7#fVi+ z#(4+6@%Pz)l6eMX&OG9I2XK$G@7eDp>)2f2VmJZLV4&glj2lU1M-KvPQKDM*a;rsZ2iL-6~4#X@GM`U~EyUs3j(>>>S z(zugC7|>zvcahd+&_h|)>-nJhhOVmb@t&+M_}PiAmb!<=xuxHClo%c6pU889(yb_E zi*fSm*;U~E&@|sr><3n_9gQC0T%?|U3%nm%k^vrl_?;ym&v9O~1};@H1dd&l4ckpy znuKo=WeHsSQ2y%n=n?4L5sNYfF2c65-I8T}bGG%CBG_wsl!A+b2e8)z3D-a|}56dXK6Ynx^!5*dogaD z=fuHpbwF;LM!@-wg?HNdUJPk4`h)f8Ue5X9W0pLJga^zUAI>;Ae=P9A_ZOMw`=@Td z$h*2SAmj3m6&v2~tN8thK4QJ&qsx z?!(-X?+%LIZ%Cra$p7n!`|se5Yu8+kInq~<$JutD!}YDqroG2+74N`3UaQx^J8#9$ z;9f3muP$5Ch4oao(=gU{{Udf=cf%` zCqwA|8;v)F`z5R|L>~V7Q0%pg-VdIZaUQ}QZTjwgKF%4YVKe=dJJK0^PZZBF_|^rV zWBJY!o&nf2(rE`XdMVczflKJFA46TPsn`8Fm@}q4tnF^pjQ_xx-cJEe;TbD<-TXf_$M$}c{DA+P@FahHmrVNe$nR&P;EaP7wqK>&i!Xyb#~k0~kn!cZ zY4cmVC@%qTHqOYIrhT*>=o-=|w*G69jgEQjhSovxQ)MkO?|QLs%r}nZ{TvIVXDK>7 z>q4@LVN0ckn`LNQ=fqOorb9bKisnt4&QH*dnY@{BWSf`9)oVs5hqRb zrvOKqO86TmDBs8OB)*=KdHp_MUEXSSI+odsHEv7nC2Px}ePf?K^b0(HfNuali2d9i z{I}h=|Il_n{>#9BWA-1~DepHPsbL>W(D!S0?;@tJvWEJp$N9^KVt)Dv_5mOCNOZ6^ zIP}ki!M$bPVWu3gL2>0b5%L2OMSOqd^LWOqgF~^$qsia3Nh8z!z)4*Fm>Z+E@yPfA z-6k|b8`gW@lL?PNk2@}~8|nJSUAx}cKD(E(j+clN>7j4o3Ay6k4Y3nkTX~0__mZRx z_JZpy?E)65Eiz>VH)GXcORg81^7;j*zh}X-;v+AEWXjVX)fwdf0VW( zi~S=12>O+AK$`EfQU`44H}%r>0r1^uALeGs>Z;@RYWsLvo-hW)_Z#wo=il+UORw9} zKrioYKZHKhwVi;rGeIZlm?b*cAAk>G&)Nq*@Le%Y3Q@|yBYrFm{rYl^C1NG`u4DWPd@~U5 z-0qub<9oFB(8I;{&{wC~Lyyd`F`qMft(now__XJ!r>|T+{R`DIW3hUUxs=b$-m#W? z1~TxRq3ly|JoK|zr5&cPfGx`hi5x%f#zdxHDXNFc5i(~aDOnv z+Fzehg{QqghH~!tu)YqFk3P*izzv%D480hI*t*><$Z?xsuh`#zq(O1w)eH~AE>HdzOpM(znY(yWC zdtQ;T*1cd#et`a$)|;*A_|tVpr@F|WE;DoHH%}$X$bW*a;pZ47Vs|X~aQ=TC;hZ6D z-CzK63&{KWeKve!Z+q`~LqFf0%~?L=D-ZUWv>)dO(7%IreHQibpcT#P{T}H280Iql zS;kWgY`hG9R!``-#owBR&uD4?($w3)%W}@o7QCBm%CS2TeTu=xddu!YKa%gSrk<$x z@#i z{eZrAllVc|ji=ye5PRrT@)Ps$vr6+5P4IKWX#6Zb1wX)@mLK#pj31Pp|CiwB6%Rj6 znx9yLpJ}7@`-uA1aSDEb zJ1sxxXBa;yd*%%J@qYiqfvw?hQJtKuYzOgcpSR|2%oE&3?<>;t#Rr=)I5FCn6azyn zEQoL1@Vs%r9~@d@S#QNLzX!N30w=$T%K64T?Zg1^iQE=1$9e)EUa#Zh_$^a>GY0){ zqCNJ)@SPk((`U@w)$QTW78qC?=OZRf-01H*(!esIeR6u*%^B~>307aBhu7C8MEeF) z+gScxRXz2`X=j&!S3}n_@;E{B2t23ilQxp@z_IZz*tb)`TY%>~B(0FGg)y7yp>r6G zW=ynwC-2kn-T7f~;AIeeRP{K=Pp5zGGYRLX9;C_zebz${eC1Xj#-S+j8*w^@0zKe5 z!uHmjWwi77E;3>zv#q|f0Uw(k?X!VH>L05fLR@5*fsLb%_Sp|#oW3c2a<27vK8ZCI zI5}5}p*P&0tMg{;b%9sfYdwkM?3l8C9)cP?nuJ@1V zOWAC79$?P>S!UMg6I&Gyyx)5t=hb06IaVjOCZ8ejJ7z)~*E^iyn{_UVvBkOSy=Wuf zQ8qA$+g7;gOvJws`!Z(&ZaLy&CN2Jhr;X&%js~f+_=c|Z%`!v#_cZNa#M96X z_!q7ILWEmz#v!n3Oc@)B>GMzc<6@fz!2{!WF~q+h@3#g54}OgN$v0n7Rt)$O`ArNyImXxg1jbDFtK?LPm@4=IoeupS(xCa!bN>kUJ&gUw;q$R>6>#urbj#=p zZ3g+@0sal{!_c>qBF3||FEdctD`gL;vU7l&?I?S;jncO2ydQOf2koUze`T)&JW`MO zl?0Ex3lH1^kG=?>&|mkA>!1Z(czoNG@B^TwpEd=&$T;abMKj>= zKHG?Js3TlzdudA@_V7H2Z!M_#Z}diex9r$B>x7vDxX%K*+Rnqi=7jua+9IoudM@7+ zpbk^dpH%OgS^2jL9QDN2Z3EM5ci^*UNcvP?#IB3fz>pMoiV&( zTy{W?7HqFOUK)<)67fY?uMvB+y3VWR*)8rd)nYADzrhYTudIWNyJGBJy3)w`^WY;s zEqDU)m=iNGX2j1kQ=Svs7%SNL6C5u)SbrYJ^@D$eUCPqqN8RLjPlBxQw5^`=XrJtv z=o8Nnbk63te8JnXalsRbZ|x=9I?O}p0&sB7%tVZs{Z2r?7zew*{=EKd>!xz2{ydH? z&S6eOb^aLj4f&wXZ$w_^khU2ypSBsa-JnP2pN`Ae=m+wFeaT_GOPvD~2K-%Y>{+Vq z@!*N6@jdYt;3*p~y}>bx-bZOuKp%Oi*JWc+hJJTj136enf+x5y7nuQ%)&qfeG8B$y zm99t`{85p^c!R?lpM>L`e>iy`?1U~4Ki>sb;GSVdK);a2 z*lwzVF85QmX8bh_z6o%T*iw8`!Nih6z(IO)NsosQ)-xXT4%Z9QC+G{3hH2WKp&oW+ zXe#F0Uhq%?9>8D4Yo-n7E6UyWPurX7p}WO+zJPxDo;G+&a3%1d=qzEZe8q1Ze(b>ZJrcjBJ(v7RmA`NTEq-lizZD{;_F8XC&)0l}oX|&dy zU2C7u`<+OiZxuSY_h|)#xPu_SAB68bL+8lLhxVpBz^B8t6=mZoGbt~Y@}Mr~oK*Zi zDEu~|O}(y*Es6HQ{$l;N@H;lp8R|0LJMX6s;CUDI1@~<J0rcE+I{=mqy+Hfxx>?yg|l-M$K8u%m)-eQk~AHo|O>A@v>N#4~SKVc&Y zlVcUQHZsk=B1$^2hR0|>H4n6tV#85Zm7#1B^t#BcpmkCo`^aa*Dit?HH%}A|B}kL2hZX03SQQK zPkB|YDlbgIvqP8j?z5{${bHMy9|Ih}ejK(LPuPN9j+@L6BYWt<;rB2HynX30^p?r| zz_=%VDpuQ1<7^X9pReYak$Ysh7V`#5DEWfvlxm&qM0Fn~&lwmES}MY+@g% z=a$~v^A0ZeGd(=70#E(ozZLcZ_po(+24x0+=ifn}_*md|3GY$s`9gX)N6GIkz-Pf1 z;28t-st zhV$$D9+`T-OEi`ChwBDlI>1X}pPLvLjYnWMi~wVNH_{gZeWdwQ;5{gQ>GJ1e($uczG?bi2d4T`~6oYy*8EdCfi*PdwYSm9(yVoGXsx(ko?|)$z$L6sHgpGjO*Fn z_AR#T*$n<0AXm8~X4=1m6EyGy#<4GGP-<77{S!8W`i!k^O%>eSWOJ=Os{So?& ze$h^qVH|JPWtF%7^RbGjiw=P^o8SsHT*wFli8#67_c*fpU z^dd(4fV|B+F-TJ`qTAr%Yo7k{(BC5|{TcdX9LN{>JP3WqI`7Vp6uw8+O%qc}+{box zvkWxR_FRiOsO3YSll#6ym*79d8N^@FdoJ;j>0>h9M!#11TkqQVUHBM%T<9s|92ig6 z7paGwWuL~r$`WhFUZkmqb}(1n`@)?+#Ll;rAa0C1ne=Oio`t-UEtVWqVBZCAp`nQ-rq#< zjxYPRz%R%5y|1gg2}p|^>Y-x}WXtma3(pe9ZLU@K=B!NkdyqL}ri77rP8zvJfg^_4 z4dojB17xhzgDmGenr2UYZL}{{#*~SRTeovyV>qrLs3>-ck|lN2!9Im!N`8X0)5JZX zW1bprFW`b2PWpn3Ec&#-7e|`ozXWF>S22d>Z7=xcJ;5WZ*)PU5Wc)p(fkWLbnl1fT zkiG>Y(1&q4fc@LhR*q*H`g_$F2n_Ge$9QK6bYTu&$1x>+GG4%evfeoAci>LC%{_x2 zw|>gjQ*Rp|O4FCb+ZoDcBjUVC?X_&Y{l$%JJTzcjWImYp3P-f3ShEH|KX}0WOODZC z&nY(kF!W90cjJ`o@4&j6WKVyaY)@}RyMjLehVu<`NNm~&_B6sifH$J)-mqK3LgG+Pz~cHk6Jhtl7$6z*y2h5dDBmzm2rqZPV)n z``m$jHT%30ZT@pe&vVRMFFn6`f;PK)Scod%oH2t|e%DzI6)w!NN zcOZSv2z?e9x#)ExdK`L39L%STuU5GXep4j@ddsmw}5T60RhVR%S7IsLj6+;8G zVeKf}h;;wU|g=$PO|rh(n(4nhToPW-t1PL&j`7gF26WBKKU< z4tq4pXMkgfGNz+CJsxz+IWAzbkp}!Y(7`d<6ooDkX9?C~>XA*mh_ja%cp&|Zf-s+x5DfqMHuq3-Rf8{fK37?$C$#$_sRiye@0GLN>|kvXQrp z_i3~TT+q9&d-OVvbPRJ6^4fS6?v)8|#xFp>;s8HFrbHdC!mSG$#D3ccA(eMM%=|dYvnUfpzoCHi9Y3eCyhrhihom^$TKwlfE-$ri2 zmy+B6`kG!-03-fHiXEv6B-@cxeo9Kb@{`jD^?Er1rPN_%f#{ z-=y&zNuRvqYhX@SXBdz2wjV`j%otmkyBzobX}hcLX*?(QcFmnNiCbaq8py-F1?=Cs z_ZgU|bZP+k0r)=_)-BdE4IP!e4`IxmB!g=(0QdmlH9o-=5M0+GewG$j6!QUX`ha)S zV~m@j4}*7@&qrFg&SFi@;2fcS=9=o+7Y%TJu^jf6agGZ=P;s9)=L5>k8gK59Kqn=x zH|WP&iP**fo`c{4Iw!HlL<}zx=eQF%y?q+rZUShM_s~Hn`})cO!a-)*$7AfnwkFMI znfRluqo2h*?{D$R7$Ba8&e3E*|AynyPuovi92>5I=%2h}PdSu7f}EhEN=}d;+wnJ# z*oJueuqWjDz*y@rI_M8!zsTP(XFqHkW&a!-&)txuIiTyrcEbPs;P=|bpq&1198dQ9 z!?gV-VuEq)+kP2vVoT8OX`~gM=G}8WPAPQm1{~LY`nl}u1-G4w6^yFGq~FYe6nz%{ z)95hEjb2QHEUDL)zC+Ycc%2`_6K4cU_jEsO>%yQ;V9=I2$@yi={E|4Zx*LjiHtCZ( zz#tDC@|1Gcvn`&9x#f{7<~e+RiHGpM+EI*8TA5T%?YBiphv+L{Ujgj5hSBVa zxzB+APJP9=3(fGsgl70iLMMGPtec?!I`Qwce-$OoC?}n?O^lgqg`PC#BKWGQV~29W1Zj6TzM#X* zP0sDT;2{qDLc(ZDA;RtO?Mrku8rAUFVdhz-9f@L z^$t=RoI}S_a5@_24ucasJpdRP57MW9lRbe;$?|35@!E4Om$(N{s{DUELYu>B+a%7G z8HeThz#-_@0Q7;eN9yDx>id#tpM`h&sPB&Q&--}K?i+;T7(kDpYjTD`T{CeR`T|T- zN3$7Mmb8Kwn*{uXr=G^Zo7PA1lQ%NHjJm{GR(e{WIyJ4|wfd)?xAP2W{RQ`R{{yt% z>7jL^kt^5*BMbA!| zcc$*slr`YR&+D03=-LF7*|?`Cd7k|#7~FFutflS?n)|n$!>mXC>%Sd7cUew)%z7~d z7z^=@C8lrVgBd)?@A2X>zNm&Xc;3`_c-{lLWS)^P(kN#Kq)FB*i*vK61oNEh&=YzL z&HOU>Uefr^AwKUKfpk)=5qX zD74@mq9EQW8WHYv@!-2H!HmBE9*kL#-piSm4-;vK_$jDsfQ1%sxZg0P#!lKJ>3lJ=(;P=lk)Y z3wn=S`Y8N4e9LGD;2Ha)Zp^?F^ZZ4tKDYNFPrGiUSr7V($XDzhYfEfF5OX8JQ+yh} zx#5e}{Qj$o9{h%l;wxzN-Ud4P?Xq=v#&M5mz&~czOpV`#!?)WE+-E&-=c&H&{*U>t zm7ase=o{m6ja#3x7eqbh;NHoYBeMZJS=l%4l{0{!??G{_NDuL308btHn+$&h>*j~# z!?Tw$^XGaGj5}wb>p5u8J<`WfA1@nW&S0-Ca{{`|v5sP_F$VIDQnA5kCugw0Hx<6n zDe*wY)=X7WILLSj=Fm9K zA4F*nTlcVWUVjKGKJ0O*8#MF!00gN7$m|F-Vm=jlI-eWvjL z5X(ILBYrIQo%=!3lb|E9#?Vg4dc--NiT4kA&Wy6m=Yfm&(VCXIWkoE59V~9d+DLmC zvxVO_&2M77(%{$dKNXjI=};(muVLF8~Pp4Wme z_(c4MQtJ1X_-zS%7iH+s?XVw@B z8u^Zpw!N@7qAxMvjNJ|!fVp47I2zmV+kZ~5q6G1j65N%t9q7YOtO-r(eimU$Fs?Sn zW01dpMLLk??~@1Y zAW!(+dRfn6U*p*mY~|z8KF>Uzwb;uiZ0$JkDc>)G+yQ?TamjC%tNgea#+TopqFuIm zw*!3c&~o@(iX6t$uS}JLlh^w&+CKz*$?_O`zz^QKygcFl`yjv70=dii8)#wQ_=cb2 z54huyZOK7=+s5cxx$=K)tuJZi8p|6t7Ds=bkZUbz(6S@_HgJw4zhe)3^yCcXH^{x9 z@SybdBF%exx#f>2x2HU`6CdZ@RIeOyH}LRlC)Whi=tk^ou(7yrPM=5J4wJ)_M;CogT7M{?*S$xJ$ z!jB46ZNa_9t59DU^H*)5ZlbObdT||}1Ab>#?2p!#_#cB?Vkd)JxV~25yFPK~&feRD z75jDtD;~N#Sn=>Z!3xv=BYF6)JZ&Y`mb38PS0g)F=kU#QS-)^c0=DmqoICJshyIQ+ zltr*>i=Y!fMgLrSHV{I#T$Zn=j3jA7XD7;I1#T zA_!eZU;?EV1w4;KkOYP z=D!c?Aks3&P$xXW7np>(L%6dz4l}epUIH7oR@qn1IgUphdnSB~YgW%g(62JIho8uO zM@Z`j&%NVl!*Yz{xEOFs9=NDSvuTULJ86hfR+_%k?e|k7^n1-|_KWzyap_x+$C>tD zIYR%uFLg@3>4SJ=e$jo-(4_;$7H zLv}ug_AJ|-@GEa+8GN%;zw#CIrSO}3ylL>G9ch{8(qdqf=O6ds;^U>vLHf{QPr%>b z@?H+%>XP+wI^;wD-}v9+kCTUE)k8D1JY;P~o@;ZQ`v>kjww+zed4)Bn(8swXW%+KI z-!03m&CuyF>N$k(k_>rmHtv+%OSyBsOO|<``aYTVV-K}!J{MqaEP!liYsxTh5&t@L zGGjmawc&F%lWyuSz6)iapIs|yez)S%{94%2S(48|9_tk5;H)@cORy(_&7UQ454MFZ zvT@I&*uj2v_YV0UMeKdpklUB;j|I>dU~JBn_qFU^vwAJ;Wq!UFeUmnf+c@eZ%4H17 za36v6-J7iBJf3FSuiGA2tJOueXOg|svX5+VV z`3+F_dz&fW+@6|Kjc;%J@eS@}cxLP`$y~nQ&K$EJazNV&z5I6fRID-BR}JCLcAt&d zk<&wgl$zd~%&lIjZgei!=3yMo7w3o(!**MSf5Ga0KP9DIJ8x&T{g z<33Ona*hFysWWN*#<9G+4?NcSR__lWTWN>k;Xn;%6YE6+Bz<2-qXOhQ8^b9 zXW4pxjWs2XSi)Y6`@Ul668M8`-Prvi+PmUtAMW9E?dl6|vnI>9;QR1cU*1}$)}bR3 ze?eP!PhA9Dj4klpA3Wn|3p!OAxIicR1x}<(fRixP4L(aiC*lqj(%wNCWxfo*NkABV zcFXvpbt&vc&{rV7A8pKy^1YHRgri@>r@-m86muE-EB}E_7#r3N+v9`(_++ckDvTak zMHud{X=}ASn8u`*SUcXUk+TWm59L^=6@N@4z9Rgg4E-qnP%ix8>GFp(?1A7hbe5uD zncsvbuXw_C2n~lhzmbmvM)v+l%Ur=z_$4gmlEUvr!V7JPvS(MDe7%ZEJf-u+j<16F z6Z`(e8bZHJ`h-4H9#MW96FSPYqtm2QWX8FG?}@YC%7If%jSpuJ(7TQQOj!^XMd~rM*7kHy0~Xxi0ri(65wvWHN|8U=Md07{j}Q zw*;QNOFIwmlGnToEO=LKl3__N%c-wP^&Z|?Zg>|M@TQ(4;L`QveE{?un_}(*2|f?s zR)_M#>p=@_(2;V;OYlPu0t;GVyX^C*c`oq&)}sn1;=7uHUeUujW~OuZ@FVXuHU}E(7cjcKFqC(1Sd+ zW)hFF6YhMewtj{?oV#SmJ19X-0#M{SK7vkfp)86upQ4O zvgf`MK0;xP?pnGQ0%TcO)T4u@7}NDub-x3ILprT&N1#>itft8Iyfkt>N0$x2eoz;Te0f$gDE3J7p>GiVga2_t zi-%^)$=>FhKt8Awb135x=r(J^@7DVEKZSYqeyzR#si{T1Pa=Kq(xTpbeP=!YL4$w) z?-2{b$1P`lfb;Ep|5SZX>4PWlTVq>KPQZG-@2?`qU-h4TV9-AiXG@c2MaEja^>|0< zLEnV8O7Kqa`?Xd3f46q&{tp_e_Zy$O-=FxNqxpuTg+JSZ)xlqB(qC;?sI$wdZg1^w zXzvV{B-KdqKks^)c_p|0k(4Ng~6*kOI7p}iwq>8x%EhazDo+!pEX45JeC5#p9` zQ*%QLS!@k8w?)`#S95z?s1q}tf2EE*tSbyA$L*uN&FN}x4Yzl9IqO5sE#byFPKWBG zp()(3(FwJIklDC=69n;At~t)UN~w_?$Cwax9Q?4ezO%j6(P%5DH#%!a zYB$H3f6+yi0Oe@6-xBVmI^3-0q3*~6O3d`Gb|(_#!>B#tR2FuxO z=Oqs82+?kbbF}uAfD6D2TBm)zw-LlcF=*C_QH$6ahF{a|=rJnspn)v1Ef)_v!(S4A zZsi=Zt2vxEDu*M{>kd>BwWG;nB#ITCO<{~f-MX+gA6B@tv%M2l>$;m;8aZwX%<5?0 z9PVsik1d4ylYAWtT#2NXC))rsf3^P9wYE13>NT)6dNw*NbEY?nTvlCMeO2An*DhO5 zm8@P?SFZj6zOcl4omsmyG{h=$DjJ&(xHhUV71bcl}-8-nkho($%4!>%%yEvT6Yaavfdn zG&W;#yPQw1qQ5RuZ&xSEW<6P1Yz<$91n^qn8jvhbcc@LcDaG zvTYhdFlyZ`q0S_E=rXLOE$t1>FuO(+Zb8E0D{d_7a#=BrVKf+&>`Zf&(?sZoSnXi= zUFA`FnaIlcVDx24P_S47M0s5x&)B5WajKRHTDrPB+hAqan>9!)sT0}U+|__7sOsS% zaNfH*>{chysp}iMI$JO;;e)ty68fqYH!D)s;D~eQu*9j1G_`M*WOnv=RSC_Of=Xw2 zT?A^&b}4m&-I+VrsWsS2fiBz=YK13L>6DSAx}KgMC!+fnw=%1&Y(`{8O}L{o9D$4@ zPB$DYG8zeYHiufAj`q&3v{(!WE|!LLSgNb8Q7Ezz%pe7@44hKUZ5?p6FtNK^*()hE z_1$gZo({~zk)W_{C`8vZw}sci%yhQPzu{2JT#l*J(B9hG-PR1Rl~Wmu8dh{Vq2W%| zjkRV=N7$KKDiU!nHAH-TDmA#XyR9@kQ3hn)Esf5)aHUYF6nDC|U&+Jh9ggu*m2MDK zO}Zf*Z+Y}Wq*|GkW%NOuXyd0>Iw|E4A^h%2$8oOf4#P_|s;?b#?TEvvi9jMrDB*&$ z8UIvM6hKg0FhHwUh2~&pDI8Uz%2W&8&1xD~^v@NYk}){l#P& z4SQ|vbLmZqb57%|a<22}X!{sRB1JnRf)M~_QV;Vxxx}U*Oh)87NI*3@B0`Gq<#BA2 zXi7LVm3kP$p@t?Wf<+M98MTcP82UU(EyeYLKA2|ogrKwVNwB8_2aVxmqFomWM5_T8 zqt@Qq(cGfui%cQ7oWm&~+N92ne??h}1U9$Ng*zW^!2-5^eVDr$nh-Nwk*4mh#`ew0 z3aBf^djOs*%!rt+iZ=grvy%Ge3P9h)7&%=|$4d4U z6rJmTB~b^i^diC*hAD1Ix+C=G)yhK0LoF!W<6eDjt;2077a297)yU6rK~fwdnoRji zEE&3CrDLd}2@>~+MH*b&nFvI!y%*&HIBT(3U(cP)&6OO_h|ppdaCiNOL`h@9Spq*S zXn{Enb-Ip&p@7{O=j6}n$Fx184wF2aRKAkf!m@yc4&oOF#Y?o&FlQ}TFk*qfONNX} zyMD+e+>kbe+8Utz!z#U46Pl5VcT_J!@Q?1NB*qtX;F!v?7MIUoungBHfmNkZNA;PY%EuW}eYFW)~oRQ*$mN?h6JE2>U4y}Xf^f)ol_3pODlBBRs zNr~Y6gmHP`b~LYVrpKRfe%7+LvgwhV$GiIo7k&gNH#|l6mQy3t*a{jWSfsI0aXP}C zt<6|(Fxeq-Os5XGxSJ7_!#h{<7j9^3cV^6+;cSEZ*vK6a%%8Jp(IQ9FqT_=)X9-XQ z(s1Tp?t)Bjql}p4+C)5!C5i=)ytug+KhFbXis<@PPLIsN^zCj$z`zxN7q8i= z6SEhUDIX2lDaIeZWAfl@xo+r2cnHd({L~rH_I2HnIykVUk)|2WdPMKAr-;C31KVAp zjrbR;)h+`uqpYdDHCz^HY`{LSY<+WQEB0aG8QQkAcW#;EG_U78MhsC$SBZ+7SwYv( z-nPDZL%30?qR1UX(*X|@MmyA|$8T79U1w-B<-@^r;aj`9bQ39W?w|$T2zhlmTqTK5 zW}j~7t!I_fMK2a9XI(QDE9}fGm%lXd-5nlmx<1s=HFpF0LZGyZz5-;pWnFs@SrB@3 z-huYFhFhKTp7MqTNs~5&L zuy6jYs9NPfxt4yS7TkMGN46u?!|GjK)&P!*SA+90-tu}RenL5Zca7Dt@Q-oWrkA^tHEpm?~vHgCdG z+u980M%i0aE?a<>_V$jtWC&BQLltQtR8MW#=QDN1jdPb@zh>^DQoVlb{Kcho#uN1y zm(EYhUz7sBFeSgB^dbe1vtsFBUTL|2AQCVCH{-@};BKs^uBUQ(>HPI`5FwFBZ{1%> zUb~MnUTW7?r#FIi*zM^?dOUT#*@Yzmupfh&4HfomFW#QIP(yR7Zu&2V{ zNT!bCh9h43@pbE4LK|os6o<-*gV*&LgbB-*FRxo&bM2MOtJl;)FlE?uNHNlN^GfHH zt+=*!O&L~4ZrpeuCXOt+F&tqNp$Dva!5hvN!O9BMl7UN?lDwKD`% ztpPLUI4TRTWyZ~Ou>E$Uuj&jGVOcl=Ti}kZ4|TWDy5bxJ{FrGDCjp0F4()p7+Ue!< z8|S+JxI33L@LanUd?n%K9~a(iWVP8l?XE^|H*%M4;mtHRnBHrrH{PsHa5x@v0txp* zc|E0xgZNUV4++WEP_k&u^CyY8&4JRW(_zV~GbGr6I!$ApiD6Nm-g2)ks1s|ET#t@g z!jTTRXWASXpcFjGHp2sC;948&5L#jP(my9j(rh%9-uk53m;fOCW-f6)ni}B?{a`A( z{pg9sNnl|cP?rcn*3oRca7IpvV{1jHCn#3epiQk;er{w$(+xa2A|?}0@Xw?wti>#! zUcRsq|IAPO&&`&K&8+3&;A#G!r|lNn@eTmgVR$nEpl&g!xpsPwWB$(yXI*O~rImtj z46p0nuy%Sk5UT%lKR7E)fk%&^yS=f!b?x-^&anUAd?7WL?92K{LQ3XTt5|2sBM4Q`fU)gyy66EA5wew}d-K zMv$OtINhH1a7xpXf9n2MVe&xfN2Y*UF}nO#!g}L=&`2blR{N@khEdzsZi%ch9O@wz zyl&y#xx;mVfR2+?E@Lg_NyXlw9HG_>)Tq^1j?v|C)CnmM2hie^isYuOfnZdPvfJ1n z)R~ZUF^?OcK|K` zy>*<=dj6983*-9NNWG62L=-ki)Lxb2&TLjyC(3plk4}hYPta!+rtLfDJohhB2 zxbTK3>8R2~Jhw;ShSMj-3A%>Suf=a5AZ|tHNaLZa4g7FEN9WHQesIu->?@qM?pE#S zV~f$e&glRRh+*ghCar%sqQkx~O}*%&rdQRw_Ye`Bm5Y~X%ic`;M7?QCXR!|3GAu+1 zyPzgQOPx3xtm;f85uHqA81+x&WZf7UAFdqnGEAK|4UG=26(tp%qCJRTTYfXiVQQY6 zn$MJ)wXmNf_YW6Cw`WSVXDX>Z=BMn8_%vzCZS2@hUby9*oprS;1R@}d6$r&9_{;`Q)JeISmD4Y3bnzI!aHM)I zs5+cOY?Q-TI2*dT_4+f>*B{ySMlAmN?SK9HxBvFdJ@>D?`V(__OZd>2-?(dsD*EM@ z|4wmfSt*dOKlBgBo_zQ>&+JhDA6Eay9lKw@^FdEN`NlnjI>cGCvas!&uFoD!IcV*~ zxryuux&Jcdx3sqiyg8{b<$A6Yl~kGXE?g|tg>trG_BrAUBjC@w5i%S-@b0j6ko^-} z7b%_AW2S?N7txDLs%jBMs_T@;uv)~ATd~3Qv@r) zC7gWWf=;^rH+ME;P3j8w;BH2{<7t*cr-X&Q)x+v(IoSi;n9}Lx7q^&z5aSkzOUhBE z#6%G>x@CkoGk5N0pijS@@oH2{wyVO41a24JVgjzb#%2(+ekINd^#u$S>Gl8^S`~>A zn1N1_TuS+Jbs8b(s=^!DT8)sJi(4U(_zde(X<>ZC;B?P(Qv@XPj5rKEUJh4HY#waW z9EnA)samt#S&67E&dXLJrlJ|_RL94bffL2Loab~z(KrVIVp)>q?)8@TZgqxd^cjMP zbj?9APC(?=m?)>IMPSB=QTSRG7B2v7NZ48GDBr6QG--BfrF|U8$C_5b8e8S%WaGxH29qB5zSh^#nY3T_bVGKVP2C$)gm>7@HXH&BH{uI z5WEp7Gx9&*I3RAjG|-f_ma|d?Ogz<_Tdsy2<&YJoMyr7raeSg}9WK7AS79_BcV5v) z=bt&Jr~a&_)m_ux?yPEW+o0vk@@skMz8W%jmW6L|TxEC1iMUmeuUgKOWh!{uOVev` zWR{8?{S&`w#aWa}1M7+Z3dF-Dj!0wzl&nXD<5^sSmZe*~VCm|GB#kCrTgoT3oNZWM zBXcv+8_W177f^6S1-)^Wb!#(t872fSqjEf_Bbdqm3$Wx>%C+nIK4$AiTuQQJW+)8PTynMtk*qr-^KWik?@Aip)F8sGAO|)M(8>&!Iy_61B93jTvl_aI zdo9RFRLipD@C|t8<3Ii_P!DUNevTUVuSHxRR=>5qt&AGBtg{(LtW2$V@D&l>w=PE@ zU+x4~Ga6QwV@XK6KbvHnKrvNnm4_)T;3&_t}j4Mci$}OA9&~Z zht~9ka(zNmYgtoo%FM|gpJjE!qi2or%+`lmB1F;E*)5pXsxTtgM_doWMMm64r}^OJ z4)-JhF%cPd90I^SlEoq^KgVf76IFzmHvv-W8P^r>P_vm@&-QT5V6t?3S^6UwLP4aB z6Xz+J3;k!&+wG@;@GwY07P#NPQ}5`5vhHyHzK0bpHNDK}i`u{`~J$ zN&XyNpZPmnR>L3OSC+p_{lvT0@|Umcr|7(?&(QgqzM!PW=zQ=Tl^<*J0hKr7yGtj= z>H10fiTAjZ{`@-E^9MzrPv@V*hyD0hq#l;eS`&5t#j>EJO!>j-DsSjE=ZyHBEBQ11 z|LNpOdDC;XhCiwEhK_f1{)K4@pKks?_HeY^|HnG`2=PY}_(%dHO5mWjn;$)cBBPJw z@c#}uq$=#dPtcd?U47@5%U< zCQh*xLY z8Pm^4_4A;9KCPcuR99CzGjYrr>TGwAad2~M?)>t3xX`uuLS{> z__r4t_*lJye;X8~`&0P8c9ntO{TT&+up}L{k=Jvr20nO~g5NeO{r_jXfq&*c1)o1E z{G8ne{)N2?{vqRdTgiWl{kAD;@>9XL{Mf)h`<#NGV>Twq;Cg;M_p*V1=O+rjXjJ-Ndd0wJyr|%RYYbgl{9ky( zz#BXGC}vQ)KSh7p`vyMtN>IRVJ3k$?(T9i6vb8>+e?q~}9F^bKrW*KFK4q`^N7c{E z7aI7S90k8RFd9AMs}1~36BK+8W>C66#c%n|2L4|zSMbqM<-fDpz^_@U;6EHy{@>VS z;8(9!@JI90QDfx!U2LDVebDQ`rRmL$)}QO{Fz_AC3jd8|qv3D-vVni@{?p<2t+;_- zu}8tjMzud@;~T+>;A0PJdh~ufl`19w|NNeT4<1nPw~Z?QUp#N%pM6Zh_t>eJRbJu$ z^-m4_rQgu_(}Qbyp8c-|zF))NG^+d?|HHsf`If?emp^?6ik`Cu4E&?tR`A=>gCj`8 z_3&Q?4g5oTKVZn2qvI$hpNi&~v}b9il8{+{^|Q3JEV3oi819Iag+iSTO&2dLi|`Ds zwANA~#jb|U8|KOd+DHp7keBfgJko*J2g;ron!!0)=DhstX0vX;l z47VuIp2Zi}UA$1?DnlPQGBth9#nsO4p1B*^y2~PMp$A=))m)$!l|ltP|WM(cJ!~nWrjp#GVP;C=WMK36Y5jQ`0UJ| z@Zl4~;mZg-jS=!?2A<%<9{W?N8#4h9IGl(qS{YZcD09rOpoxI{cjoL&7;08tFFR>q-A#6z&r+a2Zx3n98(2i^-o8gFby3vPt!r zP5{LBl^gKSD~plzD-rvZ!2N0z{Av{ZO74E2$UQ^J-LFOd9y;;wY$mpUWAZj8fsJw= zlQ}l?Z<$pC5|DJ}nAbT}^8lRjgS86y8yMZpg(w~~)%Q;*8k>1H{>^#>#bYZZ`8lvL z_KI~Z-43|1t0cJ|%h%Y|OpeWb0RIM#;~!rW00QNgGg*#a0`sm$GCN}l{>@zVaUdGE z9f<95e}mS(aknAu&slnPE##(wYHuLWOrWvGEd>S}%9g?3Djt6efM3aa_urAuz50_N z=Dl?QvT}0)mGuEB&CLBJV6u)gou7LFy2u)0dQ$H1S^fv6om~8`iIw$7rf25<37utq z$aHybKH*O=y*PI=asG+vVBRX0TQ)N*^8UaITQaNj-eqf_WNys+IMHU<6VOwA-dhA4 zYoCKmQ{G<_L8eV=JM!*gn;gk><=x9nE)|Z*I zay#&E)>p`GW-fmeFl#Tl&4+5d3bBmM{50q+pbC=g!oNm>r5s8rU2aMzSQ9QMlAjaD zB{s`5zs#;LRp~h_zf96u*(lF`lznD>iOKzv+zPU@4@mMDIvw{h5>oId{PQp%i>$!k zv%#m(VBBPu6mVRBh=fpuH6#Z_<$TP33PqXO_$Ozw2qg0)%ct0!Vwt&2mnfJV!d$3e zY^G-k%voPV+Wwi{bZrnVEb9gN7exZej(qFNr4kdV40$VD=TA z?U;BcQN69RO%v}%@Af-7TW?J|7tGk-wFj;VN*{N)J^cV^&S{NoVC_1T`g&JQyn>Ct z=k~OaZGUJJ($~9MN#iACL>d{^$EFedEH*YqtVO$J_5+W@-c8<1+62JYd(-5NlA{>` zwkiF=AX1o5;F5n!(Al{g$lIqB&6@JU<*G%O?&Abo zoJA)8I~O!(`KO*-s;Z_Oyh4HAuR$+_bS8F?-to4AJ>S5dH|I(P`ynv#Z{lAQZlz6$ z`g)rtUdkS>)Y`Fi;`^+<%6=4(zTWjyZd(;(BYgE={oTc$+9}q}8m7lOum0+w)M8sE ze-l4RoOfveo{0G~Gr}P}e}MlotUrJqy=*-VCJ*30z2^J5T-eiR1I(AS4C$5MPn&O- zV}CrV2QkJ0z-Ih6mjBclhaqqldA@uD%Ekoo54NcaVjK>PSarqcQIdHp{_*>>{7+|8 zBZUIO`7^ToJ!4dXW@9aA(QH(p_1(mvm(c$SHuk%0e2zUmHJpvJtiUu@eKU!TJ2cfU z8#9e=JUxk{@l1k^`^PIMA~g)MEdZ>|fb*R%PK0*Q$fa-km6VPeEMHL;N-nqwCE9%$ z!?f`sIC#Et`i0u@kagQP?=HcBK2SY@7#4hmCE6*RfxW$N5fxB7FTO(TUi@RekCL(1 zV;LFnU$zGt75F)t`aixf6Xk(FffN6db|fBX6?UEP-dihBUFB5)Ei_pf02 z>cEu|Y}{o{P`e$u!&&6kKiGtzcGxkCS!^LOp zEP?U;GuRJYKmx|GpL#TrE|yqhUjuFVfd!vKQD6$V3tYsc75LYD{BtqWnc#~pd=Fw^ z0*ja&i?1O=+8_S_>A)1oClDlER^S?9sG@3Q1Xe-9fu$_Z3`B{on&mlx0-{;Q^8COG zj8|Ye(?x+bgui?jP)@RP%LA8|fPuWJY`Ee}D9pPFeFj!a=@cffB>RdX4xlhphUram zt|Ddm<$<+a(-nm`D+=$%CD%*AXN$P({k?na&S9O7tP7Ck3XleBJAiniF8i zDA2&RGXu*Zw?HG)bEx!mn?dv^sXmJ6Fs-&CdVPZE4MMc>3}>FrawjkyjAfof$;}KDOhx)*r2WRgGQv+L{2i9>pXVWS9?64&cpWnJ z{T0$#<$FNk*jtc%CHvh;lnOoY?DvS-3eW@3{(!oi8K4KAeVpn106p;RA*Lq6rm~;MpHCT^^tZo_&Jp#Q}QY*?(d>SU?Xv+p?KiQ9uto+m_7g0(#)t zKFQozKo2}S!(I*Y>I>+BXOFe7N2aNO9(Z=9Op}fRdf?ePlIbd-2cDg4BluzU6wm|D zF0}6gPtgK;;Mo&w+Sbn&{E#(8_D#UHvw$9W_9VLnnL7&ZCxR0D=XmTcpa-6Pq0KS8 zzknWi_AJT73h04n&z8)i1@yqP=Sb#YK|O0qZCcBx3+RDomkDkC1@yqP=h>a;=UJvdL&y^kEI++ zDgCS|)gJhGdf?fY*eoAU4?O!)m8J)teVL?-=z(WF%07$efoJWPBt7t~1Cmr8I0+f| z1o(RukY`zA{*4Wk2hNhScVaQg;Ka(AF&Vlz@tVnK`9f0Uu}vd`=l{v=x|rHPYoQ&J6r~GSc&?HTi*7xF5vQ7 z`16>y1It0|_+qAgnS85tyu-9VaA6+GOPJ0GyuB3ZspMo#pqcQ~9!B~2z~_N~{Q0FQ zKg;s{2~>?gI}e$$4KPia;}@`jET-cZ%3=y)i7zXY1Z8FJAhl1Ro7^ngsj8G-T@NEflMOw0FqROCA60zNB~)_Kx(fLVmZIRrR|Db(CW z5!7O-&z(w8-%_%Ael3z&nV-bJ(y9rGbNCMmD}mPcdoq53g8CMUeSVbY=iCX9vFpc! zz5J37kQO24PgO$vK7^Y;m4eF*tc6fidXfk$e=3DFGtdmY`BTYEc_1b*6vVey|Uu^lxAi4ZPA3(D*Gx4vGI}wR<_zw!V11>9*D@9QOO8mP??#FhbnPnH` z%5mBHMynu?!m%>fcUT4aY8vp~b3p+~$qyX88tFm;7s>P}m@tU>d~aY1m?h6 z+5#;WE%!i6DV0ma0tG8A0$PwuE1(4fRt{*ns1*f4QPG2n%27NjRP-n+A_6LKP;Ldj z_Z?%cy>}_+_?+MOJ>MU{&pc0e#~gFaF~_{Dxz>Ewm}509hhUy3=Rz&9Sr$yUww6sy4^csoES%r)qO7ovO{TbgDMT(y7`UOQ+bKtHVWf zc{+0z=%eLcn$Gf~84X{6j!Wlw-&=3^-pxe*Hrj83V`XMtMf-2WV)U1a8v z4xqzNLv|x&nq-N}#_s}M*Z?&~;pgZ9eAVGGj6pVaJ^0CDHsizW2%kV!j?aZg_-PDz zR_?)8_$o}wY=OF+@DETRTO^$f??j#15{qW>B5EcZ6tdZeSVg z_g#vWC?Cv&5yJi7*pshhFvil9{7~&$%n#MBMWyvx%n#MB#rzPPtJh+Fi00_EsI*>- z`60O$!(Tw%`2}oZC43v{g*0GJQFS-b2SA-u&$LANbDMyCCNB)v;z_eAe2g%DG zWOeu@$_zgT{&C?aVSj#vc8-Q`UIKdQ%ixcNzd-&n^0$WXAibRQ_V6tj#r)xJUkOQlSHDqCBai85y4 z>-hB*2nz)a-!Ukf@Bbun^KEF3O3!2;6iQHM6b^$Tvv4>Vs9_ql&iOtPQFdh*SB)$* zwh{UUX8&k$^8H|m;l=LSfET;9pwt4Wic?rs zMLMk5Lu(d?j{}%goJx90_|s^6v6u9r;g`^<#c8x*IQ$=^`#9HEYam=rI|?QdGzA7N{yYoNHEiBIy|Er0hXUaWUYrZyBabLk;9-qbYTXW4HGV8RoTU0H)o;PklR*6v-aZmV2;v7 zBlI%Lu5NJrkP`h3v0Aq`#A@BHw03(#tk&%fv0Aq`#A@BHw03(#OuKzDtZIm#1$!#t zr%_=;Lb}xO-HS=okfzbLwLpGpk8dkxOQSOhq-{;XuiPT%fGDkm4kNT1whuPOF9t^% z+nB61wlP_2tkT8sCR*-b@yM|xm@+q3-{0Gqd@SW(oa_K=7HNrnZ zGs+Fz+F0Qya5x zR?9Q|9bSIL2!0ZD?3<{*b*f2z>;clfLi<*rwQUVtVf@MPACT+20=W~LXhZ%FFhSOa z_F^BVXyHhhY8JkNBEG^a?4ZIoF|7lI>(Dd7!hG;Ug^%Dj()@1ZqCrN>eNc)2Lr;R8 zoOJzBP!qlhyh)#YoH^l1sAAGM**97&KhIMA$v>(s?XlJtPr)99hHmdLX6)ohh0i5iM)cgl# zX7LF=qw6V><&#mh*}}&)+h1`3#q!B$lUe3d8kojH>M&Y=jD9tz*#5m9<8d;2Z2vY> zCE6Y&19+>OF5iW2GW&TQ+WzM~=EZ2XIlvXd_CMjeE0#Y)<_sIv;??gP3#7vGJuu3g z!+X2!ANFY-*@Ms`a~|*MvIh<2+~)Ti6aPy25%ce87F4?h+I!Io^9|WJ?>o98ns;-m z@=r>bN_oZ7yd!=XO4duRcl@2BH`PyWn%C>DDXp*S-u@( zMwE}6A4fu_r(sNabUE^uiulG=s&LrvDO^}UTT+}b%T0DJ6`p_##5~MRUf6-4zlM2) zjHiFco-Gr9!#kvkgm zLh~A_YVE|0oE2MK@x33!Qp!clw)*iaqjDk?Nkf(zJySW4XPIN~(nbWTy)tzvt~j$@ zdUWrRn!6J<@Xs8ddJPTEO71Q?bu*t2G3?WR#lm-8EqSBUZd!uWLwr>6?N~jH+hp^}Pf6a2 zzEvwKqI9kN8pa7!{bgEq@)ty8*yw!Nl^JtortM+=CRK>yQErY|nLF^ZZm|L{9mg0EHq3#hMfwb!$K{9LwEh-RPGtl=Hke1+@!54Tpwux&7Upx$K zyqU*lJNWWvC}I=W48B4-X%p8BzDl}i6W0vBM!IYh*9^W+y2~c68Qe#@&nB)Je1r6$ zOzv8T3hFb%eNPFkqgJ|3)LkHG?7ZY$Vo4h-(Hd zaTyqk5Z4SklGqp_t{IG*S3&irNSQXK%_T@|jS$xiX3X=E_)vtnW-x1Rg0_nz#5IFO za~l%dBE&U=ttMZyZI2Mw3{Ez0L1JfwxMr|h61yVAHG@+mu{%OsGuR`EJ&{r7xSj<;+nyOP4W}OHG^}NCaxKrCv=jyW?(n# zOcK`&+$JP(&A{zK64wkh&=BVs{JaUtlo8@<+9Yw!P$N0=axUD?juwxb@T9FI`8qD# z!LqKi%zH_yvkXT_-nNAY&L+v%Y~fjhAgwJ}jHg%!UjZ}iVcZq1xr;#>HZeqN-U`qG zTizhdr--Ai9|tLY(roySg97W2W5My2NDkcvGHB7qEB&wd$?yjZmdRSyqF>{Gdn#5= zYcU^6QS3zA+^i+vN5Xx6bvScz#cLg=k>KkqyTN=OA_=~}vKwW{6MTJTH<`Tt5`29H zmlct5C^K1Q2*#E2s zl9s%#ip+low9VI5k&0f?d|ee8V&4XAzOITaAm6h2x+=1ee8=YNs>mYplQv&hMHZ9J z+I(FVSwaA=Xyp1LbF&!fJYQEuhA#s%&(~Fv5#jQ6Rb(lfqT|pGQ5gsKbyZ{;Ez9;r zj@^kIweWbgkguyEC#Z#dT@^WzB9_h9RgqEBNt>^$A}5h9+5|)+C*Oja$~IqDMb@xv zm%zZ0wWO=Bt6=oe-$x-e`jlxT#prc4qfZs1<#knL{ih(2-5!mf1ido3q6t=H*nB+| zO={Qi^;9%P+Ohe1Dw-ypwE21}njxLF`FbjvC0(=+X4xFC*e08=r=ofC%Qjz6MN90d zE}O5Xq7AflwawR4(MGw#_4QP=`De(G7tT)bJeX$53uk8@9iDBzaCYXu3=$4pG0=z5 z<;b%6!r7^iwr##}c7{ktY~uIM0@6{NFPxo)Z=h__<_l+M(H!v0HeWb9i^=b@39LCw zNDmhH!r3{L*Ws|u7tYQw`73O`aCS!i12vA?eBtbjuvzPEzHoL%*sPs4UpPA>!Wvp{6Dk#Ydl9Ie2Dai|xQr!!ZSkHSPW62AW zSnm^{ZN4ChO`}eDfuXl!ePmlUUy#K5KLd8s<_nV8bkaqeFGykotg3AD1xf56mTkv% zb|>=X1xakiN0A-0*l|JYDbND($0HWXS_1LMQ?o(ag!toWU91T4$1|h@HlJPMS-}A z7QG|v8(~p$Hu@Gc0p#Qy(gBqH3(7W9#=~`qYNmo5XG>7cRAnl3N-I-CwN|EvYOPdS zTbUZFwK6qSYh`Mv)=H(dm8l_VrA<^bwSfIyv59J?7QO(Rhi#&oDVgXiY@(W}#T?Tk zZK9f~B~O5}N+xZE|d-qBHMZjH?-k&$8SN~x6cQ=^DC&uuxEpx?&4@z_IA>fNjvsa zl<6j&w9g`c3hAu97gUbPcx_4W z+EN`}o6aAL+@QtPwDgOwoqM*AXJ(F{xB7g}?Wm06O zl3rpH-Ob1ZIn*Y)o0&!%hHav|nLe)4tF;k-@fzWxyP1AAD@k-Wa}hHwL3gu}qp{e? zyvRm%UJ%{QI-EzAJ&|;bbW#@lY@AIf+C+D=307B@ZpkLuEiSs7O$DIS5`;GA{E7N` zv&+S5U6+g1x=v~Bx?HT*b-7rr>vFML*D0-Cmy2oF5uwe+*+mtb2yHGQ-J%F>F3k_w z1T9)3*lgYjV!j8hD1K!UH-O0SYBVgtX7lki;MfGB^U0S`%#bxapH!;}L@QmiiOuFy zuR*5ECN`T-(+U@x&1b0Dp_A{0AY@YAW+aKt7VbWiSroqB%gPx^VzY&NE(0e?Y_`}( zLz2X1i_>|jB#F%y2RLX=FXO5)pPJi@Qwk#BkHqxVAl}cYL^MJ`E{paqlc~Q!gc5rgyNo>9IOV@09U`Gs%2x z-w74zkXx_=;-5KQ!W?P7ooX6Q(!L#)W{b%-lhen)RioD%ZLdtXKW0;55jUf5i^@7S#YDF_2!2ufSg zRk^|ynK-ubYyd3W?@*c1em}Kcwb#|uUez?gV4E*o>t<}MX6&O$8(8W>&J!`|K{jC> zmA-UbMI^_n@;#Vn6W5)6hGDMvYHc}!@<$v7nM)3kKaTQCbf32)Mt*^Vm< zv*phm-v-%M(LLMK-M)gRb$X~vtt*YMK}o<^$VEtxsN7Lfgy!vsU_Xp$_5aPg)I(ot zj-|m3F!g`SyEG)bU;n{RLs6K!U;o@|*nIJz@z1*zWI*2e`{z@{F|4=n-z)fM^QRe4 z(sC%qMUW!Ql?}1~kgt&BhS)#Uia8y%I`QjF$4`tuU_|ks?>j|EELaFKYK`F6S%sh2 zN(dNn%fASR9gQ$I%l^fAkSM^-vVRGskUxAG^B-jX$e`vgp~9sbk#INDvY`nC2_CBl zZD1Z>`^a0k!2Bc@DMLJH1Bb9X)q^%rA*~*?fg#fBK^s^=T0Lk33-96rCmytcMHhju z9<+hQVH5o8p6fxLaX( zLJyXB&PtW^>69uw&sl5WBuW#Cux5}{&sl3GX$!N1B?OAFW|36SS!@1JL5p9iRp&Wt z)p^cZb)K_Uo#(7o=Q(TDdCpo(PKC-Mo?orGZ-B}Wim-;yCdpmBH6mO>5!TW*uv0Gz z4xBW|g(9qFv@G6d9eWXS)WSN?S*y--);f_Q>N#tTl2*@I>m<_ZIcuGK4?4Llp0ie+ z=d88%CRk8~B4G5%K|%)P-$01{Ek=C19Vgr-SH7KK z#fEs!+I60@cAe*}UFSJ#*Llv`b)K_!j*EkO&f0aJvv!F+r=GKR18rB&S-X+)+Z39x zn`vIX=WL|!JXolnv(Xm_(1_=3w9a!j`ZDLTdd@~)A+4UX(N{^U=WO&f(&{-IeVw#= z&PMlH29Hu@&%N|p$7)G(PC&Jtmcnvz(NCBhu_Nn&+&KJudhvj_Ku(JT?> zXvmz7#QH1|=BVpAnp7eK4s){RAhcba zCBhsnn!`wJ%MxLZwwk-3V0)Gbb9A!FG2EFY!W`|E#I7t6=I9hj?9LKlj`m1mPj-|! zy(U-5d$UBCqps&{mI!mS-y}@+pphfO9CbZsqvLF(c+N&|Bx#7}Z1g5JS3PH=uIFsj zdL6?RwK#w>^=P(CJ#sme!ac#`X5a(_^HM~ZqX(Phr-(2|=PKPp{yd=zdUlO<7KkuM zZWEFSbL4g*i7-12$H6{pJKFaRNEVIAmso&P-f1MKRP~&Vb#fEXAiz+A07DG|3^nWr z4E+c)>Ny+heGi^n#B(-Q=Q$heBU?RZWBr^p>Ny*mPFg)@V*{*8J!fOC=WNtE9Y(pp zkPj-vb2grMKS=eQjW<03Izi9b_ypdZ3_0o%Zziptv+)+vz63pI<7Lw7IU8>!t)8>- zwg47h^_-1QycK-)oQ=0fz;``o|CW^76zNkfmqSo>F70=m( z-3m$doK4K)eNRdy2KClU&)LKvpE}g5F)>IH^_)!%{spvpH6{j25ni1FNDUqZT0LhI zgPhyyIhz=42VXsB6N5`ZtLJQDuoZJeJ!cd3p0mlw*J+!;YRMEU6VKUXo#$*aL)+AI zHkoBz@CBsjY@+-s;`ffy;|tY;U{b2iaNQSqEjv`<53)Z(j4DYb~D z_ycC1QuLfnbf^@a*9E;xIqM*zp0laepMsW7Otonz61_{cvE$TpR%!JjO0}`G)N?jf z=Q*2dn~F-+TTf~AB1*MUy^G$Z(!WL`Y7vkUbN>@Wj6Yx!NQhdzYzjp00^4bBlX}jk z;~Us;c+RHPb2b6b*>qAbgSC)WPgeDuO{XcWp0nx9*KxI~=WII5Yg;{M(>XTv6N%Uq@xHg-5YO36{!-d+qP13b)&|;t zBNl^fo#$-U^_-1bi;+EnGWEb`E=V^Xb?3}gF2R0VdLTDcn;^NN+5}NrCrECnHbHVj zobBq)nH#E25T$j3IdcoyI(6sFExHJL)SWZ8m_4BGoVg{_FuhmF z197g-oijIlJoxI)nH!;<>du*4x*mLW=gci5U)?!#%So#{XYO#)y9{yX%!jT<+tr;j zU);-nAc&YRh48EHocRXIt2<}D&Yd&g^g6`Voijgy{Z=+gRd>#Onz;=&9tMpDfd?Dv z;K6*JRYk4M7=%*QoijI;t!)s%uR#F6hC0A6*Y6;=B!C|u;&LPzU(s z=FCB^EU|nAA+z6e=PXQ~3fNr+ywF`6@ItpXl-H@!I^c!w+JG18+&K$%?wm^NfET)T zzzO&jrm!k?=PdMaVAY+oFqO2ra~66@t2<|58f{Q_&O#qAk=5FWc~B#bZ~?zUKbut` z;8(band;72jO=F9IEKZjjv)cRqQkkS?wrLKX?5o;*12;Q6RfT*-BL`lTU@}en0goW z3*c9B1~H-{Q;OBPt`w_vozmKMrC6=&N_8%or8<{PrM2ryG3`2HG^IGZr6MkwrG#{g z0)C}5Pnbk4S|Wg7gR=@GmR9`As!OOwH^u6V*$}@A9Q8a+E(Ga%o+j05@jMl}D9)G- zsS(JiGiF1YR=9v)Lx!5IL%{hr5HcRO83h7;jj1SxV|+D09YVGVEfm*vHhA~z)sdI5*7fS=rO+pfWYkH zY{0o@kGYGIla)E@F|Q(XiZaJM=5$~==G1dgz3t!bUx>~^?Hj1`YL(pPNnS?Dd)dLZ ze}^Y|Jed!jBg~I^%+p!X_jwDj{X1P|%P4iOFtz+cF1P$8ik@O_+)#lEKCbGYIo^5| z@jz<89}$-s8;W2jomVn&sXj^~`m1F^X=v_QzP?O7rQ{D#BT%82}95 z0E#~8rzji4GaGyy_YP^6AP&NN1&kz)8bYvR8LRI%ce!eYt76aWr>zD0w~vK@E_MqR_y!dN3!HK;jfk5sN#@v;MkW(x0DTI$Q?CW)$z_6TgBS}l zy)@@_wwCVMMKfL+cP;J_d%+o>x|)jr%Byahn~75Lhs+z;*55O;&&^z2%N%6M$JlF6 zuB!-pc{Q`=3D)un?tMlQi&QDOMbpLje97O5; z?OZ$%@r(@aS81>9&GcVb< zwj%X)Rcr0Kh~3#s>D4D`<}Fwx_-Bs43OjUu^ttmxnrQ>lwEcVbYo_qnOb5qu+00jH zMS0(71w8bv{8HyK6h^RmvrGcEi^h{g<2FxY)Z*$T*OcT?Z<`TW38~%`8`9um$~C?J z;_7W6;px3k^p4i_a;X%(l0&^^?2sXahY-wUqbY)Xg|9DYQTY1pF&Ts4|DS-b&q1a8 zBiA1x$BmH1xB9+;>&e+KF2Wt;xIvxv1D=ETAtw}&63d?f9hPWFVTpzmz64|Hw=^1( zFAU!d|H|*wP%-cIYG%7$$#(LnoQQ$ai7Ms6!{2z{t1J{`C%> zWCA0M60_5xlT2XbDVY3_Lnj%fA94C<|NfXV`#f$vfZt#XJ-zKHdZ!YHS(EZIC;`9qRbboU(XNT@@)uQJYZ+0W)s~Gdy$Z#>{Xc2+-l9A?_ zL72sP8Y$~M{T}#{)@3jkFwh0i8tof`O!Qokdz}})feX>0tFxm(v_n^C=VeZ4%b}~Y z^9t#t(?P|rk}f)bC;v6lWrwcL&g-PR9J)F?`$+dWbai&#AU)_bQsxAyIHRQ(TM>TkUMYUAi48m>^88+EE*KII`Jz$ zl*tI;>!=I%a?y9_LzztT9%?v`Av2jF9dPJFnapx}@-85qV)bFbTr73~WuxLrnQGld zJ-qLy+VsA!SnLzfW;sM&Qf;J*4uR`bTN@<19C}iw+E`bgLr+Q0+@CJtIKt(8h^D>Fm2R%V83t;{H(D6Ld_hO{y> zB&~GlNts!|UavUxq|7Yj&<;EFq|C_E&JY!mEZqeDm_tv>%rf$~I(Lv>PI|jTPs+^Uq<5iLdA?Bu)A>oUyQ?%FVCyV)H&nU&UI&UV*^Ion+u z=B&bqGR#WrFlW1Um^lpDDXgmE&}lTQFrwI*RT$Bs-(Xf@M2CKZ*=e+4*rDHGwvP|4 ztF`mK12xilE{vG%$0kf+#Oy`PjEdi2F4Bif%OQ-Ii?S;XhcIH!;S94J`VHn{q?7Ut zoKqOlq2FLG!RpG=Ex9DS#f1@bsb5mRz=(P00qW;EkdM{6E+4CPozmKM`B<&%^08Xi z6cFMlAKw5P=a((|OSej941rpd|?-HnjP6Ln3bRHYG4( z<7^=bBR1Ax#Kszo*eEdKgz;uv4_&-gY=6=Xaya2STtVh!J`~#ivd0X!f!WQcL)*W? zWBOXboWhF-c%sW}J|4RobLv&Xe8h$6J%PS&VD>0*5VqUGpN|xyL)9O*T z#P(_(pFoMWv(BVI7z66taaPMwl<$)ocxqTq0{2UCU`Xu*7C(zZwtwu`L#oDp0RNLG zeVQ?XRN8td4Q~-OdoHVp|bPHy3#~bXxtZUYV zV#hS_ZU5^1>>y9wKA76aJOZ_QbY|=D)cLq;_nBJd?>q(4 z^|wRJ_IG)9%M>6_x;}3Nsit)q8}macxBkNwsiHPle+vnn0zdM3vwPBZJn)*|_C0s0 zO0(nnXO1VZ>22XA)O^rKn%9CXS1m|Lr9orTUpeLO^KEoXZ_>gjy_2Qi=tAz-yjHY) ziEZ?fI8=?#Dpr#pZ21XC&dc50lBHc<@&hgZ&P&`&USM>cL+LMx>a}j=FjfA{@kvi| z2Hxr0cS%J!>oo&r5hv}~Hc@g3Z_&}Ua}Lut`?zfW%q;=K#mHo?4QehTmrk?+*+F^ zCs@-~-|mYmqHU}Ef;Ij<+HpM^gWL_^Vxo6^m*e6kFEm>3p;==xy}Axi;NY34<5!%b zW4>oZ!RER}C+W?&)~`_H6scp+hbj=n{#Sm%9v`KWP+256iF`ZUS$wKzl;|9TnC&+_ zoidBblL?hDf>hJ_6bJi6>4>c#sz4dG1M_Zjd*Se{7HCwt=>fCyf z<~}VlEPEm_-Huz?kxPA~8RejnW8x)8J1(ftUEOjgD_ibfmlwA5GI^M{ytMo~g%5X= z7qq0yNFL!Uo76m}7x7BB`R7aX&lTwT`TrPFliY|Z(hJOzUWgjOb)Z|nPQwls<&SLD zmh7pv``zYj zRQsp9_McZbCH8vux8BAYTcpJHEo$TLYK<#VqkGG#+4v}XFfB@7xll{gZ2VW+_<359 zuG)CgG9A9cbD7BROPGn-6SO6P`5m&m51JV8U0qEI#elxw>OL=ckukp%y(;wMa() zSvNV>av0~^b0+oRx~QA3+o~4P_-5pbMW)etK8yTT+O*9zXs~Kf=a0Ew{7Q0HySaU} z+=eo8AC(uISvPl4E%yy-)@UP-e4rxyy4*ioU&h% z2hCqypqj6()|-Lij-RpomrPv>Pj5Mc$-AWhZx^k3j=*h#AC9>SPOmCB8wy(F#p)gA zW^jEwE^Il01@3f{n_KQ<@^fzTf|f5dBl&qZxyk5`(7sPgdX=jl9QiZHZ>g&P7q`TP zM(6x8N?b4PZFfu5^~MzDUMsoJonH|>gYpaZcxPh^{<~UozkFcsA31`TOYS9ZZk^_Z z%)L}{R~?x93dd-xrROBNo$sn#mK*6OACtwVqan=74DKIY9HSs^-9cn)it2 z;(nUR6V1&=kmaV7@ngRA%KO#agT!cX#(S=8z<)1n24lIKSsRHrQD}mU-Amrk_56U1 zf0hqbNmqVuRar0cCfK}u{_J+DG36^|B>%AY?21U$rfg4|6+g;~yWGs$q&bg@q~c#x zD?X8WA7RDMy-$_ZD*i0xf6d|icdz1}m1QKq#pEJazIHcztg8RPs{SKb{4UC0JEr<; z_JmQl+H-eR{w~V@3+10XOXX|&x%*c6&v^1vU%^enylIy!yBy{CXO6FdZ13~Dgl?iT z%ok(Y<|ZVs=Tq;PE8j<9{F&p^26!o4%Z{7tX4ZytS}!lvtC^W}GkaJJe<=BG-U=_L z+P!C1$OBxgf981KAo|3-lqDZ?VWLCP! zt>tt>|IG1+kT>C6cI(;{1aSMF@E@FU>pUB$|GWvwW4JAO{`86zTP45Xj)zdNmspp1 z3=u%AdcB)cOc7OOaIWd6QT5^c_QQkk)zUqt7RQ4>@+M?3uI35~_;!r;pLy1KSVGm3 z6%%@xcjOw#L-T}l*cYobHD>h8qvm<+49nGgzbb}Zk0Y;_??+SspRMT~uZsJ2oY4CN z>YB$PhF{EtBRQsrxcxfN=c-%ps+({Ii!M|X!93{woLK{&AIGL@ts(Fyyvh}1Hc8p` z@|MqkG9U)fHo|5`45kH))iKzv&LJ~9)H&qsAK>ilgq{OGzqS8&x4e&W)d!aP-~9ZR z8*=JS*y@Fxn(V_=(~wgqv&nAAsjDgChMXepg`6Vog`6Vog`6Vog`6Vog`6Vog`6T? z@j^~9Q4Kl8L^b3T6V;GYC&9dG$f;A2sD_-PwbhVQOjJWo@nU=DkW-xE)sRzXKwCBB z)CZBMhMf8U#Ht~uu0*05a*By+$SEeOA*Yzw^Nt~>Xj?Vp)WxXhfRIycq#JUIq!)6E z&GkY~oeVZVX4MB?NP?g^*MUW|V;=@VE{9UM*Ld8wg`6Va3pph;-@_v06lwPpYW(br z8-0q^yV0kFQoG%RdU^Gvd9J5$~mpcrRtud&zZ2@(#l3nM$tr zmg~>*eUz4PPSy;P8qUd@Ng5$Nty}QF>(4?`!#P>=4@MtIuq3O(79b9hjm#k$q~V;b z1>|cuCu<@38qUdDM81Y|vKEupa8A||c^8jxPS)I0pj;v&S;KsBE|HO}5#g#o3wugO z_#BAJxL5sIXjuXNEPtw6c)VJu{w!*t`m<0(!#P=_q&1wAbrNX}=VYCHC2G=ePSzTh z)o@PMTGCa278reW18y&B^eJ0WUX5N?Gx}69+C4-0JZq36W7K1J9*)8pc~hT}H}x5L zQ=h4OQ*ZZ7f{exzvU@)dT4D*=b+Lr(KC(5IkloMKLt_cq(@ASAA$x#TX)GbzjU^Pa zK8<{NQ*X~W8rdQ1%lH+KwMg(0>J*Q)$h_M^sFrW6BJ;lqwuW_z95RO!L&7>mDx@{6 zQ)Gy=hINW8Agy7YA`7QkG>sl>kwuJvp<$gOi^jVM_CQ)q_l>0inw8&8aAF`3`Q@V4O8rUaF2?9 zMCVEi>20I~_K(^@Uq;%pufzQ+dO2yw{yk+rN;+x3)&=?s(pmdn%3MjhX#bM*RivBj zvnPSRnsnJdjPf7jjOeoOAbkzjn?A$gNR7Z6nbU39b zWJqi1Fegh|Lx(vzuDlvL%*m6lp~IXK2SY=LISm{P4ISn*Qr`8Qa+-IbO(Bc(LVPV^ zkvT9><5k5{@1?QywTPuT`i4zki&%!V#;b~D*$A#s-$4c9Wf6BaQ-gR}#9RMF4VcpKHbUKa86OGt#Q*YMle zj7@?~^R{y~L}EY!`DGcq$R(XE`+RRHD)qam`H()yz!{)y!2|%}or|%uNi{ z%uUnE%PO$>>-5_l@HfE`znz*C8ZlVO+!o=V82sDY;vi#aSBcq*}EB}`i-mtsOL zMGZWa7~TTD2A)cc&`u3Jl~{T?_!@XBv5b5TJe62ZS_4ld4kx_}-BU&vXt*OTgo&xF zD-Z2Dfzr=atq{A@_E%HPne`uaDH3w=`xH*(uqki4AwKa{?kb= zi5T!npi_LN8MJ+qL1!2dXSw|%){b`SS$ zNc!D&2k8>&)%FsWZ6JM&{d>wcl0MGVH7i}Ysu zc$V!ZeWCp$)-{FnR{KjVE78C%v42nbskC96ZIeHZGFR9iqkJFftL&Rd_mkdkf08oO zNq@|~g!%_aUu#b#J%f`UYdz_iq{rG`BTZ+Ee;Dtyq|V-JuXBK>9i7|JXleXo5g>4l{4w>OerMEU{y zQQEVZ^n>$nbq{8WM-@#Z0ugRO16EM{!=!>nbyw(@o>oW#*6$V7k(`VFG1b zuPcq+m7UxahbWi2YpG>i>+-Q$*X3iiuFKcO?owL2E+5mbQy(0*yCSi>@(Jk{&j;sb*b}m7 ziR*(y2au38f?v6vtOn7<>&1=TRfvBY9EsgkNKOZ-vAYUMwOV~}NNen_LTV5)8oR5I zrWNi{zCwnYC3Y8sPRn?>vAc?Q-^nZr^OHJ~<;LzR-t#?hBz9M+kA_I>uF`a_<2jr%^zU?9~ch}FMT`@ znisJom`~9n+kd_18*?MBGxLwfT~iSqqj>D#pE>?TR8#&w)jY%aV}L5kcTx0NO^uaz zGxZ#;@$cBR#b`-&A^qbfS5ZaOfHVGVRnbq_AS$Atsrm1GZuRXr*JwGFB|o?JV_N3k zYRMto;>$~E!WUHb!txTP_Aq7pcYBUJUuV0%sO`GlWg4xokvn_r3f1~jP}Q2_d#N=; z;}7Qiv;E_q9*4}i%Dly6{wvmgbDq|?%VoBmW|;F?A3(P94w@tn@IV|Vmao$K_92&l zZ4#bqjFl4Y!ldM#uf5DB_pWx0tKoy~f2Xz<59Fz37)PKR0|w`+cUlOGD8rH8|A~s! zlq76~zq5N$)jt8De*!|7fyLnX|Eqw|{{RL0pNAvoE^HkAE35i{6^=ag_Hg9D#kgiL z`kJ-iXCOoJY54RXKx$-3hAMvzsdoxhPATLMH(-gj8GX$f5wywhG5VUdGzfk!a2PDJ zmM;aJ7d$I}6&5~U{t^`S7ZlHelGPVe$x6K9u#V>A86FCzfIfz_&%T-Tv7`fbrU&$K zq(g?UnTg}696C%gza4DGrQ@bo7yR4l}gtFhjczGqjhy2=zsy)MwA#2IUPr17{Dv z0cHcwz}X|hC1z+ZJxzLpbDv-MliqMKLwgx5%l6sFI$=nPg>{&reZpZV6tIaI+9y&( zF++Qlv|@(#Nu(7sv`@Yg@`@SSb(o>OmU^m~A&fqH9tx?^r~C`;7o*qJjIP5B?e!T5 zH&!vjNay>I&I@Lk7tAm(m|?ySGmP{MLq;*fNbgTT3uYLp!we&RWGiMEslyB-b(mpf zfK@4G7&#C#jLeYlpYwccH27y~6SOco@4I*emFMs1{CjLPU4pw>^X>w>^X>w>^X z>w>^X7v7JuiWWxeg1|=?ldouDbP4IfBGJNVT@d)_F!_oWMn_%&t!QC%gi}D#!srMG zLD9nK$o-f)iWVxZXkpYv3k99y$IE2)xageIV6vft&N+4HoKuI+;Ygdv5S_z`Hty#H zox_2)(?Dmp$KpJwBj{YL4xNkDp>wf1bS_qh&c*7`xmX=K7pp_(Vs+?Tti;AEIu~nT z;}xBY)uVH<=4RLvvK~XW8%_RuV0h8w*_Hnwnmn%ot_5tDAYak#zk@QtUlMJ;9A--$ z{*tWWFUcDIlC0q`Nx@&5mgAApJc|$Uw*Lijs@VmRS>%m|Brg3GY&f5cWxl;s!f@jpe8+Q3GwF-h}Xxzf4|~@j7iV3#BVJ(qt-WZ z?EX6>Fvssn!U3T}0&_geucq>gV}`?*9ZbnO8ql{My|r}vV{G-~Kf6&IP%~!I%WT^9 z?Vr?)Jy63xbNu}%+}Uw7Gf8qLhAeK_+gDT7<t_5)vZ?ADRP|f7 z?R|V0q+?_IW>&jl-}R~l53KTMj<@filC_Vx8IW=_CjFHeN9=YpYEzS8s=D6C%$2;? zbe&%#FRGFqmsLr&Wb!qfIEP*d-B-8@o2oUP0fn7Cv`+*?KF1;Jr~H#UDtMVcM2b%6nT%lF2&=dd)lNDImf|x8m8Z&{~oCCBm(70MF z0@PM~2W>4?ZSD6^Tg-zAR#fc*$jYbh&*E{?g%l?DDx~o6%@vWl#ho2T3}6)h2`T&& zQoz;x{{*B^=UDO&aRlAY6EzH3@5XQXB>c$BE7`6yMuodwCy0m(Nw@2idI!&v{dbAq zWZ@=UruGby-Y$_epA2un|L!i4q_<1#=QG#;*I7a4?hB?IBD1; z!hQQL@x2h;f0szhxJ&#^)x!UBmq-zBmq^;%C6fLh?Gj=1(G29FMxSyn%B#`qYDVw3 zOMD6vg}PnhA`~vlF0m-P#G>pHi~H>o8zJNE5^n+h4!cCM|IsdyRsA=+#3PU$viPJc zo+Z)Xcd66eD}D-l5_hk7H`v}@k#}JAEQwY~t7l1ch_rf^L>G`&&ywiEtFguK_KLiR zsAoxZG5OwJk+gc2L=T+<8TBlQ4wLWg6&bD5+beP+czZ<-g|}C{8fCq`BI$S7D}Dj3 zdfQ%+4gE)ZMUnY$_KKIly8laiMK<2sE3)zLxL14`ZE|;sH^4M+m&i_ZcZuw0_2GzT zNPFKL<5L3H0=CHAC4LRHc)P@>!Tz7`5*zNplYp6&>iti++oz<2c}#IZYiwZt`Lx6K zKkPmMH++Q;K{v`I^MB6UMgE=4o4B!Bacc#(Vn)d?xZ~Gi*FQlX6h(j!ip{rB{;EM& zw)UXd!uJ~H<*c&H&BT+C{F&oT7c=t$_Qe&qRD?M$zpSN*^|Opms7N-Rms)qbBEznT zzN6VnIX=vxzgWw}pVE>wSyvc*`7_6tQlEUIWQ|v({U+AG^3H#$h|GEwMctDuX3VDC zTsL#9nt2VlZKCL4Pf^EHthDW9$UJ;=MI>wT*jyouVmmY0RmPp@zJT!yU~}&CTXC8` zzm2&awAp=rE6+lSe?Gtc^Z5m@4D)e^jvi%W`zWHtApMD_gr=Pq^O@ec@C8Oxf6MEB!X>?2$v63Rvqllm&)}I zRMs+DmW8YC7;ZA^OkDRsW!1s%)`=AHTy;r%uDYcEN3Od3+{vd=$o?u)9xetAGzwXDt(}`4`SJN z4DzQrH6)z(j3TTL#~A(k1OV z>9Wy#4e^PO)_mfl{Y%&h4EY%yI1HrV^2eh7w>@hu1M43>Yl+N%^Q_ee^ZzeBYq58{ zXD#;5J3ediJyFOy7~}0eaV>{|-V+!5+I`~UaClE#q~HF;#df(KsY^I{9>J}?l9=*3 zH9UrAlSB_m!{&Pcr7e5#NYGQsPuh>b3nnp*ck`nCAj&4>o z_u27xfu3|@P|ndB6o1!>A?zWpJ<9KQ`}N>5_ARlv7nxZz2PXL%*z z$)_QX=La)?8fw5vtA@WaugLn~xzZ41UISrAJVG^Y`%DFV`0vRt-n%_T;U3liw6fth zOik0GE7;o>GK^mXX$lwz<)I9 z@J(7ujxUI%Q4fIlI*tSRw$n`9wfp+ck;2x$QM8YjdjChr`L6=rzH^k@&$CD%@Cj;s z5lZ|Quc5xjNM0f&zwPChZ+l4`R=>ny4OwA}Mdi6Guy+?pe(@`~>@koQz2<|L^4lHa zH6Q#48)4Y=nh$Q128q{v@G{csH6Og3w0g}4KT2A?=7U#|RS>NOv{h9>kGVe4-2f=opI3hEvZ(a(Y~5kwU&4>p+mmYc&sutEJ8ne!I; z8VJ^5AlP85%5W(N>c_|&lXTt3$U+^vpfn~2XF>zLC?)VlXa-5W8;53+wqTNt|K)BR znnf}ufnY=PcY&6BU8urF>A{(h27;CEpojG1WAYvJkOqR4@1TbkQC<(ugcg(5gEOHe zbZIUkPGe~94?rdO5e?}$x57hoS@`tL?>uN@yx`sx}!I{wdqgdPaaJ+yCEX#5@!HV=SLpaH9(ZdX3{n(g%2R*DG z8gC5SYSM)GLSU)x<-$4(T*i*VJhZ|_CF3aIY%Daad!p)Z> zBPJ1Gt>!~%8zaD4WnL|Y%?Pko>+e8X8Ufbs<9D@U+>GvxyzpZzU~=*>q7h)_EMiJxMT(yyi})n5IyD~+j|9vx?jED5XDJpkV@Rw|eV7W|2(YOuSjLS2o8qU) zB60IuP`xR|TY1Ed0Gr~c$Rch8*c1`DNY>0i+r=qeb$j4(pM%iLyoQ;%|hmjje>dC{%O>C~7JdC&zV8hmXZH8cqS4Ef*5G z97?&oW_#QW;!UCo=W*J2Fiy^bW(3&CT%~)+pC@!S0=~VQb!IE`d>Z8SkVI&)t5|^Vnxl>6I9v~$Hs9T#!xjfQ%Oei4*+TM&LrkLIWw$^sCeiP* zJmL^r!K)`GM;zjbgK*!MBM$K-zq+YM9O5Zn2=BCSUp;uA>YiLwL7d74*()*}w_ z7SejeAzmh}M;zj9l-DB;@rk7Mh(o-cv>tJYPa>^H9O50M^@u~fle8XjhMvpke7@0DLwta=9&w1z zxC*o$afr_(tw$Wk)_e9MXEkA$~AvJ>n3bOInXO#OIOLBM$NTr1gkH zyz*7hdc+|Wb-43Nj@{UYiJW-}bcxTb= zP-=vC7Tpe|Mi|9gw?j(nb|~dW*>|A=JwAFpOiXv)hc=c3d$vO+ zCV`&Qy*x4{d(yN9dbSzp8E0?6);(#upNoYaA5Bjut;a{x1FTB-r0IjEg5Qoo;|)*t zr0E$CB0DU>l*3jF)X63#6Bz;-I}43YW>ROfavtr=Xc%QV+Ly_2HtQxOljVZXXQ*2_ zq<$33Iu}#Jx)^R>+1BT&LC(9h>5%ehU$%|i?4EZK+CA^m#tQXlUseMs+q+<8wvFZ= zWT&80Y4^NK8`Zl<`?BfRkqBERDrn&KoCMLxA21mfIBfArB%6Z5)OMO%9}qbgoDIns z?zP6ATxBLI6037VHLG(&HLI0Yt8+s&t8+u_8$FQdeql|lcE7M@e>Q>Jz>ruiC;V~? z{tS6N;g?(34J-A8Urr{jp73+Oux2wLa&F0qFl|+V?sGW}h-@<;a&Gua@b!dWZiIH~ z3BTOZo#5*UzuYqN^@Lw;IcYuNmph#FF7!_?xw{ zchfALBucv{d%A1go$s!7cU}V%OLr^np6uz??!I{mma8eON)JWlH88Qw0Lpm{Ol&hS zab5!x+YC&cpGF(>P*lE;*ZOL0#2HW{jc^Y|<@?#J>`qAMFJfj)0uvV^dqK;gs6v#J zN)JU99FDXeiYmlNCvAS5qo9F_Z3ZSTBv@Tpx}}h0x44I*3aN{!Uk*hTo%NVdB2$dj zx~>?jb)C}Mb;Ve%>xvqfSgx<41}2uSQ(C*O7}Kufp{Sw;CYD1{#e{T=9*Qcae-C@Y z7A=uOQ6=XRkYVd`{K|!RJqQg<9FxGrrTFi_kwa0X&R9rS(u$DRn+% z^iWi(J}_}9L(N%!sjQ)oDzp4jS;KTrvD;SWM;($K6wrg2Wg2XO1_2kt&XS=(dV5u7!U7A&@4l zXmKWiT-Cbz=#6WXyFk>^D?ecz8z~@cu3K_TvMYh$8;j~QB57!!h?$D z6`ESzvXQAPHMOdRhZW7MG_|6I#}&=1HMQI*x6tS%1T{9g_7SM&pE=G5&#m%`XP5#w zTV#}1P=1if@&WQESLNqa<)>4=`(w!2v%7*)SY+gv`pIpT*G)Yn`Kl{yv8S7(EY&>d zme^D+@gT(X1y!?GV&aSJGTHTcsLk@Kyzxwy&mawO9CZ;M-vCzi>3G0&hiMd-5dZcK z!2tR@`+~IHFHai2c`1xUfVU;zeBQH+0KezsJA_}Vw*vg0kFP@74)A+Ez9G_)0Kezs zTR=J*;P-rd3vY#FGH?|hk$j7e0lysJ_k4Vd$?ppAdp^D;qz8jsuziP~4w>P=TbN(I zVe(f57$@F0!h6zafL}E5jU@4Ou|B}>`S?ce=95N%-}CW}aI5f8fZy{``jG&a43vdV z0Ix)`{OwIhgcQXJ)j?POjv2@Z2ZE=axe*{)@EHgTRO|117cwliDWs8n1i$k4pF&O@ ze&rw7OhGmvRQJ^;|E#OX(XTeS2$akDCA!tN?qjLXQpU6%1;@Gzw7^@zi|3LgycN8J zWW=&1H~J_N&*7i53qK}45dmvM4G6-BWskT}sL^C|V#I|)O(x66hzo^URff1wXtK)i zQ8v^qGV+!t+(GmFf(wNQ)}mB^Z)w6aNE!itASgVOG(J>h5ttENC_Ia#UvQ!D{6|3t z_?9MIp&dqm0ae07n?VNx{6J860r^&7E43{o-wC9+NG>8j8Q=$k!iz~~1N=Zxc*zE+ zBrX)5YrtTESi-~SfGN08ctp6wg~ChOTqDYE12Q(2nwG>x)|UGg2E^N43(4v{6J864a;@~7GsKr*OKnx zsDB>9F#2fDQ#JaOMv?@x!s}{ApDIQRE)-t>QAi}WTk*p%@&U$Xwi2ue-H7YRN@~|J z$c2?6?F9Nx1f3?G4DbU%R)%yozz+mjS<=P8!7Q6&uQUZFqJdVP{BnRF2(n7-sjfh( z4Rix-T^-;Df~-c$ySR|m`~Wg=Z4lU!m{WG&23Y8Kk)J;XVIgBqMP8(4BfxL}L|*1x zwE}-a(a0;LlYtHhMqVXd4E&w^*GQKGIp~eNPP!|=TYF?5>AnD6H6m}29t<>6=bNOf z$PW`$lz=u!{UJQAK{3s3Jd1RFR+Skf8`58hzRpiI-B0p?o zfZzU!+(^<0jIn=jVsotkzx@-rnM#tlbpL{0wJi>yTq-nME){Y)l)_!IX994e*4Fn zPP!Q2XKtJUR#gu0+ds}hEZdImI1!yBTS8~X-;gce{)r{lL7QK`{S#~YDd-@-{S%wO zJB1;4!dNqDGr-t(u@=(4Aiw<+E0gvI`0bxqE9pSsxdouxUZ$D=&t%6YUJQOLz;FM= z+TQ@*{q|2R|7+GO-~NdWuz=j9V+YAy8pcweZP6gxT7h5r2z}hnqILd1&*F_$ zO2r5D-rkPYC_czrmlb#lEsPIRBpIk+NsbTx7IZmq7P=%p=wP+z3h-M#@xfuxeSx=x z=A<1A+=dp#2Mgd=0^G>O2j_tv4$!YVKFIs?iU8xp#0S~6t93)2i0q+lvY}3-SXqD@ z>O`9M7y-u0Nn}U|0{kvfBFnmfJzs{5c=_aDm7XCTmu#bYci)~&{{#tJ zzEdRTK80k7KVb6C>U$8+b;<0@BJ~D-MT(D1BIR`jZzr<3_ibmJ8VV3FBlwW5`yAhR zLmwFL^RXZIey0KvJY`_a_-Bsu+doYbKJsiI>-O*1y`@RQHoo5{^LfW-w@l#lHaEKI z&unSp6gSUt)3>*KWb@7TGeX(OIe&GX#+TedWB!Xz^{`#5O+9rtc&{^kJE zAM|l(ut{j$$#+M6)E*n)w&#} zRFiaANjgl%ORO#VLNb24wls@BU^KhQ)y*;&T4XNZ z3$@KM6^YrcWn_PNRR&D{N%KDWuIHh-I=8+DT>PJGy{Z==+T zdpBy+7Wwz@0WUdfv@ZH~MWnqlDj(aw2fQR^ZQ~6bz=usPfTIs+*)GuhGsnMx#i!|7 z+N=`rI?yZXM{aXBO_CA+vB~SL?c{UtrQSzOE+f45E@JC`Vsh&6+LO`$catjtu05T~ zKa-C2?Kn;+!_VD*J60#dqi*t;4u z6g=<^Rq#Yr!AGhJHnJy)rH7i#g1!l7o^uA1=ZSsCsrr@G8F)TN^If8yeyF$|K(6s7)_IU{H@kJtt+ruq z((8nSygHlT&2@E7)#%2p?8S+qpvP6PqN?DEs)C80f~FHPQb4bhQ`O4JHGQ9@nJLlt z{QcSqHG}@GsxRf~Q-cas1)V>qL2vT1-RYLcY?nWCydi}V^lh*u&%2v6`7FCt4t}6SBD%;deV8Z;1H$f)PpeawXbdy_}unGUn@sC$a zKk1h4l11T3?U?h7&M)*q?prLK{aQsz)n>!QwAYYtY3bEd2#}cHbJv?GGSwc^o8fx7 ziUv>w2Or(5sCAL6b4)ZNM7rDwf5_@EJ*LQw&`qty!#A%vYLII#ZCEs*v&{B=hD9E} zPc0k<%|CPer&S9-<677wDA{g4%LBzydq2OQyPhu53$JRdsW+ts=Z&twA88bA==AF3N`W4{Y?C@YvL3e&mHE+ zG!LD>7^!P?g1epAG9OIJ|mWi$(a$b#T-kDt!u{4@vECd&@E`vQZ zrW1I5YmeIwZ_f9ehA%V_n&Tm1tRU=*slTGSWwhnX_oywkX?iPdk?U=lPJ;DaXR(H5 z?vm9lOV%>3M2O`*MHa-Py#AI2>pgCV8NKgeljbn#!ICSgZPq&Gcy-7%J;z;PRBJ`G zZo*aqoe?l@E8*E&{n-wkp=jrW52^V**wOOuq(foVm$t8@xkyw8n66;^|cks)C#QN)ySbrT7>pzrjS0vV7hs63v{){#%66+ti6NrK$vHp>j z0S}4wkFZ^e#44>wtbc?}ago?S`@KlK0}>nP_z5!J0f`Ot{S_G&+fQ95EI!q~2`NEh!;N@m0!<_~++?z>AhF?Al_3%vo~$xNV)3bVsp<#Vgx(?uWJ?FQPaNUYsRc^8Sbn~y_AJrWz~ z3t@p%BsTiO#h5&T#71AFW<_G7FLSOc5*vMmv?8(5S4k@p8-0zmBC*leNh=Z?-A7uH z*ytOi6^V_$Nm`NEs9`dpNNm)Ugd(v~pClBCjRwrG!8}D`qal;9og%SOOD+RNVxx{E z6p4+-@gX=5iH)XBUhs;H zu?Q*6gd(xgDUwhmHrgWzMPj49W-PwE<7iB0vgkg^h++CWfOVpG?#xVjRXx}J5zmDtOW7Y3|A=_*uPx(ahym6H3K z&F#Aqo7&%HzO2NiCMi4u?I$%^U|ESxZlX+CiA`=6kSnptn+4nf71A|SBsCl5I|Q={ zti(>mf3gyr&N4?=V%d?3hkg<1f4vf0JmPrZ=t^wysJ{Z1mDu9Z9Q<`9wz!qqx)NJF zhOI_dVvENT)|J@eaTKL1vBl#_%azyh|Kti+ZyHL&Ee5?j)IE%MDuY{|ec zP_C@RmW(5TuBncfw=|R`zfevygu$!Sb|P>-b+wbPE4$iB*sgZ6d2)c~OfL*LQ3(SM zN3xO^Tgwbt3iWa!W)@+g9;S>eo}LQt73;9%&QW zPQ$_NZO1$+`_}>n)-2RjFEcv!G;kTB188Ba>eVSqnBp9OdC~!!oq%j|zoNR^S@^q* zoavFAZvvrF3cp>;-qZMF%st)hv^>g+zyT`p3sQIQM*aJU`j?jacD(-F2U&SSohP&J zlX}E%)PvyBs_Z-ZQQyh=DXH`8N!?58M}FNVI(J5z9~n_^u+&_$cdz3NRj5B^xvwO3 zm!Vz|QGYw4zS2_P1v>Xib_7s2p3P!ksSRMMlYgF?oJ(HMJ=`W-R!6)TmZs%6*Ydhk z(2Wfnzs+^ibJZqYjmJw$%h>7UAElsqTg3X#3c$^DYXDJ8XaZwlVok#G)_x>TvV znq)<(ln>x3Hi>sus=VemOUJDGyIP}Jyt8UD*43n!0XYeX^_?5C7>3lhI%6MvUdnXY zN<8G>tb;+r@y$!J>KZ+T= zgk%);3(5F89u#RbMp3^Ij4gbi(HBKJ(N6>bIKKxz!z;ju``5_i)_gD#WpVd83lDC1 ztPQ`InaD44d($X=C`)7e5M-22G8l%(K{KhENwwoY+XVk!`6bl}5mmFH3Xc=?H9)~P zKqXq#ZPwH|PVgQpa{zf+o9>Eu`Os7~7@)j5!q1V{02&a@FqHijlbW02R+*b6E9jc; zFsiLG?26&&*XqOb(+kYQ`Q~9NOTKj!h|Zf@$W**&x@V@a?wNV{dyubt zW?udSpzEHQmnR$DGgDai%)I)p_^Z2&?n%Pa&+% zyFZn%I`958T1dmF{OK{vlC6ciz&H%uQ3bAXNG zybTz}aVD6=`9nTUO~(%>^>SXV;5Z+IEbBP4qO9XgTI)Cqj&Ym?$2iU+N*!maXC3F? zfTeMq30lXQZ~*0R!~e!{CTJb!>9CHvrEQd99cR|Rb)1o{)* zdv%;Y59Y>kejb^|ah6z%<2(uv%qu`bn3ApAkz*a_ zBQbm#$C;e1kuno9Vh znTQ-`CL+g~iO6y05Ewbm)GczHd85#7jx!5s9A|>oab|I?<4h(Qblv&P3s`~DRj9Uf z73Q)kCHFp?`%jKD^R447uyLFT8^@V4jpHn!I?e*B<4i?TS(L8<&e;G2Y~w%UI5S5b zXLh9Gp&dy7JI8r6aIE9J6|ixfIq+J?nc3EHX4|liGhypEQ#5J~ist2i5d13)!@Krj-&5?6v%`@&F@Tr$}9R2zOV2FNe6dk+C}R`!!7x#Y~bWKB0IMhnFahGIlS!P8<&F}gs} zHUSiAp}6|VHo?uH82p3Z5K$BximvSaBq(wD2y_2ho%_4A5_ak9Wb$9_z9mn)>tyzy z74Dq=2f;s}X%KM!Q2!dHaqiz(xHV6-;TI1g!6#wX(;$W0p=Il8;87CyB~~rO=0xnv zMrxx-ecK3a6rukhW6I1QO*v06IoHT3Y!rVhlJkU-qr9G0UOi6!9!^_-PU>C1ZNo3d zPWeS{?<*1Y&#jiSrSx;vYk~6mRm5u}HMxVl?lrs$nhb-(swKXopC(%)>IX^vEmAMo zO_Q@D>W%$0`F1}|ZnC`UZ(t>UiM&?+rVYQi2~~bss-KdVY{q?wvt_g^)$2>jxx0ap zW$u@L2Lf*$-0*?aYdLw%F}%h{yxxp>EjPTJ{FjJ-I`IR8KRv>4#N@r>&2GM-?ue*wA+@x!X~t?fi7}e4 zWn0uJ!BsOUnk}jR4e}bv(Y32zMH$iIaR26KXItP~W z8Wu4$)@yi{sida58)RW4rChrl=Q>!=cjncz-(HMCFuim?_1t!uk!O?X&b@PCzkhig zECP-_4#IqU93+V$OZ^ycHus~{kMU;T z0@xl0;pUk=4np{U=r{=XwfpWr#>R9qr=OR2CUg270$IhJK3k9ec9Zi57&8dIhsWUt z;^-RHq^B4R}UxOdxLE#X{Z;<+Thd=~}9@M8F0-<{L5D5J=a|nc> zJp@9SFW9~Dzc~a#&>jML1n?dXfzUR4It0S}e|HF^6D;)*$UgvyGm>aOouHhjm@T>V zpzI+K8j9^hY!n>=p=LY;@&!EE!yypWP!E9+#U277Y!87Dwue9-h7k3j5~q;X9s(iU zXX`O>3|prvy)fD@O`KX#y5Av?izp3;K&GL$nnNHIq#o4&w?iPb%AO8^&{Fmg2z9lG zK!|TVsG$A_c+hw2F>LLGhV~H1vqjKw_d_6TtM(8GVS5OKussAq*d78QY!87Dwue9n z+e09PqeCD}M2A3_hz@};5gh^JMtYoS!U4^-XT<=u?BW0;ind}iXYcu*zDBqkZ^L6wy44_G{?l5)Of)q^UjAgmr# zNhKR02l&Il!MH+P(=AOOPCl}xTiVDaMUh^b*O>v=bW8JmTkD#x!n&qgnx|K%Yr3U* z%F;F6(mv-P6xKD}(mdH?O_z>ZY5BuQ1OX>Ca>C(H0IKNQrBEh?&DoAAg)(KP6v~vD zQik%GvmFAPvmH~UOg{I8GE-^eHh(kWX{^Y0zrGysbk2_E`cGp@o|(bgJlyB)2AP>W zJvmPf%VuU#R)^2q4KnRtK>mFH1^i}aQ_oJHK3L|UOOeyLj3*kA0*ZMbL zo}2j`;f*j1UD|>7pmF=`ahZ{nHArqZ7$mnF4C-^cL1xS_JRO+Fk7Dmb4F<{W27}~w zgF$_6H^}UFG@hndkgoxdF(!0kf5J?;y(}>VB@lC$1qE}L1yoC$kiu&2GFceVCR7#_ z%v}}~%&oARyDSiM%gL*lAF?_hc2>6`}cqV#ShUV2U znh2BGUAX#?yOIi(wHn;^2=^G^sxoEl22@5i^UI7fwerbOlUn99ew%y{wg#WuxDs$+ z%m>Zh(v)hzW^YMg zv$r&bUyPb4eb$@Gtpn||-n4g68tt>*^y87Qeb$?CFktPo-pr>^dD>^aS(K%H)@%1+ zYVEV$Z0f0f);p*a`Pyf_gPE^=)|*3E`>gjl!W-37ixsuO`ZipY1rR&L4p2L2xG43p z;i80XxF}&8E=t&ji;};3YB4F7dTOy5%vVn>Hj}V=YB4F74Hsp;dTO!RbR})LXbA>h z8!mb$VD;2uv&UlIV8cZT+i+19B?=d9Mq-cQqLcApkKv+62}R+~Nq8S;?C0F;l zSQIBkL$Q5`jiS9SYR0`TE?KCC$E$|A*QFZjUKdg9UKe4z*G1Uwb+O~xy)M$)y)MFi zJhk8$wobFxRZUQoKDD6qB2n7xb$yxAu-A1kCd_89OE(&MTtCdH>2$A)u-)q-Z1=hd z+r2KrcCU+8v3p(2w|iZ*l-=v1u6D1B_|ab1Pw=3xrqWlj>8Yi5lC$0G zVq3L)U4-pk7h${CMcD3j5w?3>gza7zVY}BwINIxCBHHU>BHHU>BHHV!gYBZdt|la+ zy)J4S?R7B`?RD`=+-R?heLdRiYDOa3>ly}b(O%cSNJM*G4+1UP>tY>7dtFRKdtFRK zdtFRKdtFx{5$$zRw`i~HK*-r`uZx8=dtC(WUKfjN_qxc0dtI-hx`KceC|!kWOIKko zt5R|gwYhygH3W$=-|lq@Z1%bco4qc|G<#hF>Ry+C^wiQdR3vo^e!d4xcxpG0fSy`9 z%N+I8*pZ5d@=F*0+EXhYaUXE(UROKbp=Pg(L%!YXVz%AuV%xBLU4-pk7e(2v$+-_PXdZnZ2$B;AZ!_9tUiKMETCMdtHR>UKe2-Bud!sbrH6EU3~Z3y{?OpZ}+-B zKz_8>^$g{jAW;&?ySZe%yqlpc`2_(L3WCq!*X(tb;}vT6x~2g(dtID8*u5^ocCU+# zkOTZN!e?((m^rb2Ecuud>kpC-qi-_#!VD>s=i6FmND3RTCSRB#W%7j?QYKF`+Y{@A zjaQQ=d*i8P%6~(q!FK#sjRnr%095k_nTO&(b7FlLz##Y-zk@yJo|TPa?d1H!;2@Tbz8?IWeI6<DiT}#tf1%EU&>CCHsz~fVQiAO26{2$no?Tgu*29a;&r*jf zm0Pn1sh-y@LT%^9P3G%zfY&0sHKcW#!~CD1@`;4C0q$ z+(GBCV>sSs8_7BD zr}>KBm^<-QeMQ0Ehcn+#^A)}Q{tWCCP2T`C8RbI9o7@aBM-E3$5VYb~$~+x_7*Sh{ zHyE|-9ZjTI68IVK_^$&l!YOX=1Tu7_9e5`aMo&k1yiUTN)VFsM;h5C1cQSH*O<7*cu6KGLmP`7uJcH_j<-PE1yw6{cM9sPQaZ5Pi z$6;vWE2g+zTZ4@vQ}miIOa@YI5;f3F5!5YT+}!})BJJlpy~n+Ul- z67_NZOKvwvdt1yYE$MrbY)`Zo%7+605J7M{(gehy7~lF;Q0 zU3WxxEE<&3om^z-8h8=GDMtKqy;oy_NuE>7R_87>$+K(a;)7F**xFF>PPUv?eV_>2 z^d8i~UyuAEyZ1o~dz{5+D5;G?pvKwFEZ-;*x!Q=#MIt|; zNNFRZOdIKO>K|isC>M$Dvwl~PW_D>AIS-SjUlQXsMZE}Xzy-iN9<9o%u->~Yb z6HR~WA1}T9oI0*Kx)1q$HNg&bgW2RC^Qi;-soc);xPOx*JL+UZ{b|t~BLuoF#|jyj z?*@hpPOejbKY45xtX=9rMf4ox`utBfHm-r)nF$U3iuJb z#$2HoZzu`{JT0P_8!03OoZG*EM_PrP?CC7v`!Tludv|I9djRv#?LD#5YVbjz`Znqr&da5 z|8jKpFUQIK%W+EoaxCayj)ncpacci^Ea_j4<^9WXLH}}GSSZK$IcN=*a%_7=%kgSd zAFJRpXgLP=FUR2i68)M`+5?q3tR(<(RAOD%HOnXwKsaafx4 za+?S(L^s|Z3IC(V9vU_3KYHw-QKNp&(?QGh&p&%QXf4%I{%@Z4z|J}uvv+vwG_H_2nQ zyFO?*&&{3xQk#@$ll6&|!U`*Zpm;hg?P z=;?2SbB*Rp)d*iONn?cbOwt(P{QgF`z&tfZxX>hx5mxm#!lnI~C7K zzDBsFj}e~Zi)ES^A@hQw)KHs8_8R;gP>6>hx#; z?5MRys5M3~14peff*CmK`x~LbXuecSoioYL*PX%Hd!tFN&^bijXud?7^eB@&&B-1^ z)t+}btaLr6sx64>=f*m#+Vd_44!M<3_9>rt^~Jx|y!c;~=bSZjxygOS<$4ol&AIi4 zX^Ua1FYnhxU^H~t zrO>;?9(Q$=!F+i--$}m~2HOk+v?uw)7l0!MzqSmV?4_*nJA@)*DDICaHb)e9*cz>6 z7z7CTh)W~iIY5%C!Th>I$?iU3r%NNO`TB>6v`KOo{IN~g7yO=2A|ab1A<}F%*=AEG zGH)~W4FC5?@>?bRoM)Baf~W`ObJk9)+-QC(6VO#IUvRN?cbjJVMJunl*>Kq?y5Y*j z22}A-tiiZnHc~qqxvFrPaKKefb>j}j!^=%_MQ);DVAl$?eXKEtFpbD2JFqbMgdwm~ z29>tnNSiCtt~Klr&Ani-ml^$({WlDI)BJ3bO(vUW<69;Ok37>RWQE2zFK11(tk4qf zoD7OXgktR!(mH{*%&{yl+206KKh*en+OdMs()2$xIaYo@KdVXS| zNg@LMYBtNcEl626Vy>iz~5ibJ@yQ(4?rqf3|ei&oPw z7SwKoBZ{Y7cSW0Z25({e*}+jRZG=4+3EK=|L-d4(&W^fg^;^rUjbeR~gcslQ<# zN^dtcI^;>{>V8ipKTLrn;CCz5eICe(zW4K?`{;Q!%JljFfs zLrvZSWI|0Ce_}#SB)4y<2@S%ViVZa(Y(q^5+fWns*8ftd z37ez|HDOeT2{kDw-7nPSLP|rZNgGBb6KX<1_E_~~z=8kY3pJrt_7rMDOW9Bp>S{wx zh#!TTFb1W6s0laWZK%o9acH=Es0rJu4K*QbLrnoGbCf^5x|3auqJ-9`oCZmvuLQU=kgDBL5br^-3 zFcF2CFcF2CFtJ6x35xs3RwJ?JP?PbHvscYC@SN)I>lHH4(5+sL4i%z5$pBHMy1q8fwCv zzM&@1BK_||P3{7Y4KkYC=)}9BOhnTDb`|VI+zT=a>d| zCgh%HU~R}f-~J}#p1y?*xhHHx?pehgKBEwh()3N_V1n&AACORh(tKgMQJUwgPp2CS z>vW?uUzl!`_6gxA?GwVGu!eAy=4HBJgY6q2D+u^`7};tc51^Vq$n2%OfP+w<=nNA< zAo1fG6R-@}pB@u%7@qcx3E;fs(_;eU>zSOk{TOJ{@DM*PpODKW<=Pc)d}UGx~ z>}5oFj$m|U+Mji1dURGcRsN!>qq4H6@;n;~mI!oF?XN5!9hSv)to}H50YSs(W@)cs|kfyy&hD(a87*?@$Vsii@~2B;q%KH zihoap|8okxkuCXE2c-CeBO`xq?>geoYO@GfPN@|u+!RrdptLh6ZNVqN!{2IG{)5#H z!IWO5ouT;cYKx_6i!Qy~y_?ORe*9nB!0Ifu;fmVj?MN+CJIzk+8GqOTvPLO zd$&hZJ+)Wz*}0lB_WgpU=IYk$c`D&7r{*>aoX3Zb(R~3x{<*yuM7qz5%6ceS?@jy< zjl1DTW&Kfvzqi5H>j3uFvUWQ)+)H)`lllQeJyB#)+A9(D;7HnalvYA~>)dRN@F&0z z%9aQMLDY*%D^Y2kT1yp{R}c_#PDJ1GooAZRJ=A-eG*!K)IUZQy?|ybi{9Se;crtp+ zcux|&|5VU6DMMiAEMEpOy< zz#6^fjXDBwPNJy1(fnwuMsIno+n~EfZ+T;Qm5oMkd1Ft4wi>gIRp5C&*&{LOC2(ZY>J|Yfr(R@CWA^3jLadF$ zg$zQmDa27PGB!nd@>?#!c1vKct)MaHI3mY!XRO=$$Ik$DR1upXN-6dcrxj7@zS zIO;{lrm>9bMaHHtM82L~h|Qqg^z1@x=0%`YFETcZvh?giteq!{)QgPGrk?6W#t!-+ z^3{us9n5_7B4cw1s}~vj9N~@XMfyeUD7(EaivuKgLzx3^^xRxi?*a@pImn6F->Kl>1rMZHLW_CSp5_O`4a0k*eg z?T4AKy)BEddXfHY7R8)hC~D>$Xb)!>iiXU zIepG96iv9AIepG9#J8Iqbtvz{9BzU~woDm&_sfI}{+XiXhJ}@M-E9{OrWP z^mp-N9Lk`^{R>j!PzG6-g^;rgL9I(#IlB-vDoz?1!7#<)*@a-Z;K-*2!y!~p9m;Ur zX%H?BWw1OJOd8BQRm4rO@2Gl0ci3)`rNo?Qs1&^CH@A)Lzmz~|Y8 za2oUV>_Rx5`FeICoIzO6E`&3?!IBPTIEi=iif zY4z+vxPWkjTE+oqd>)C~51z|nAkgO!EXBUzKXccuRlLMKrXBU#yw3IrO$r|da4rMY+ zeB)3i>wk#{eI3eFYd17hhcf-9oOq=}nchjxdUhfGF59X)l<8fB)uBwkM_3)o^!tR> zp-g{3SRKmrhlJIkOn*dJ9m@2_gw>%;J1!IIP^Mi;s6(0dB%uyv+II(I{-F+KI_~a; zggTVzK)QjRT}Y=Tp=TG;CGG=Ytqx_n++|0tqx_$7`7U9C`-l?R)?}= z97U-^Su&oqJiD+EMiPgzWN)4#2m-#>g5W5yGbaOj0NRrQoCuhc0em;xlL3V7$pE$l z4xgN2m@@%CBnNXQfKvl?fAWQyM<&m=pgj{n*q#X}%sevr!ptL+r~39x0AYJ3KxQ85 zP-e=iiTW1mtf5= zrr;%=h|#?5DZu!9Kz`{Hd<33Z*=-JDEDoHg7DcIvJngGs_*d!W`TFt|5jFezdn z)i=r0>Vvr_vjpYBU`aw5EQ!qhQN*C!FfgBd8)WQ@b%AF<83iu& z^@(fh->LaNDFz9}lDLZ88d3B{6jhcYD=ns42-sqz(rQdnn`hRfO!KUDZS&0Sq_D@R z-Tg%>>()rtKup0J#iEaC>*>hTjdP#m12mqzX#SKc-qrAiVX(w7$V+_Y@5mclqIn6= zG$}NoAmEUhtE7E55$9E3mptqMt0+CXhLp>@>=FJt)k|$#0s8Tq0mG4?O@e>mZg>&m}Q0!r>U3J z`;htuLtT)~Z_X+8K9*W)Y#*&Ld`IvsQp@YZu7z|&R#3`nODS?|j9jhxtnxv7`#Fl_ zJ1-1Iv(hD&ZD3qB7B8-}7Kz{Z<=-N-yw5Ifiw)s>d=D;lto5^t+djLvEpgHp(4W<% zPMrKOnu@yAiO()>!zA*vi`(4KE^bSrA%vSgySS~mp7%rPbpXW;g!MXr;v8YU4xqS^ zuwDmHoaa(Tk$f|%xaqTt+vL_QyO;d`&&6$5V#=OL%EfILVv(~YQ+G5b-ahA3nR;$@ zIzBf~GWB|s*n@B(6|Qn(?}D}?lYWK-awkG@;p(wWu@VTez-IlUxX(>*#fwn&y7Q7L zE?hmPuvz~o79;q)O*m7+rqbr`;C6H=`L{dXR{WPKr_$cxRC>TpfI+}(5#;K+G_
42OanbWfymm9>kLUClxULb0n<3yFmT`NMKXL=jjD4e$+&t#Gqio+5YgX0-N!yL>{LAm8GGi}kxi9q*3on` zQ&}>lF(snBR^@l&CJ!72^PM+_!dB|WHq25tcD@;wdYV*&8@fQh*uzgVOBB;DIK}#W z7t9-S7#{fgU9ec6?}B-)OYxuxp#~r;Y@K>zE@DofYu~(aS23s0)~Pq)M&|U{I*n~- zj%<$lm(X>W%~5|9LEv#i6+5lLGfe7ks=)G5nWEOWkR6@_S7Uqp&2AJX$<3RXivS*2d*UMrrspACy9>K0c7jDoA6&}>J_5J-P@7qN_~+G0+-r$ zr`C`rEs15RtC=Wq@5Ym!RE|29yB8s`GBuer6)x-S;?ytrq|&_$+%8Ggp?}7!+y{_Y zomx)@jqcBYwl;Mzg${F{Kw^FBa3+RJVq@wUCiarVrW7}(;v*!nCDq9%qug6Tvo$rB ztVfG(_os^ZWQ_YT7K6 zEJt13Rp9qq&qtr$?Om4v-5lkVRO!6R6FqLpB$>yvk)`hwZ(pz=e>Uq(JH>3qvw#~1lN(eV9PMSEw6vrhzTyP`+Avxqmpoh;xzf5x6 zPieba$WHD}&`Cat29w-}aDdA1#s3n3keom;ybBg-Nggl`#Y)yf`(zud%SrOHi^(Zh z0rZn|Fjgn0GCxQ%03kVz`RQaCte>3D{7kYP)=bVIT$!9l{Fx7eeU($$nw-Qa>H&EY zw*Lm11Li|!a<=5w5vij7PFLh@j0Hn25$+@B*2k5>&DfRH>vHDmxn@kj7xg@{vmpp~EEy)?MTXF&65gZfwK}9Hi3@cZaUf2VA zRr=I|(u+iC2|!48?EuEWwW*Su$(NfhsZt7p8PWJs88saP5K?7?)5%t}(^NU(OtKjT zNmUT8Ouj_8l5kaWf6@+M_pMDfp@6A@%+Dnm%$lmErCO3@dB8Q)wIj*kHxx9#$H0Toe3O3^RFy-ZTXhzmc~x9ZjyYZn43ZvkFL1&h)No6B z)C_P=E(U&jG~2V2-0Kj)t;`ORPiFy-VFS-3&o~(HSi)7wv1BujqH@XEWq`+%wi#`3 z2mUvgkiUV)<`VLgz%Be9RH!Si{ZGIZyuhKjjvd;O&Rtwj*iG^x-{Jln4&SuZf5*Md?EMj8jQj8{i~A<5W_<8rV+qcgQHIAnYeO4JxT*Yhd>~O86X! zHYVHHrRk%A8k)H12LOxo(!36PdI>p)q993cp)^mpD#=M$X?`Z)mgHhoQE7fP__roE zNI{(D{~1s&zmIzj<|xw zfl#n&SY$k5doL@4)L<>k6#fJVota@zva5+dI=oPj%y25N1yNWFk{MnoNM`tI@YRB3 zh8GH=uofgUTnduB9(rf?qNuhcw=FUwSXDEUyz?$IlJLyrx1nEV6yaG(&agA1sY846 zS;DOxvpbw(K7J8wWZdx`?^+D{nK3!!gfBwI>dd&`qJ+uelsBHBll)OT;JvA9kYq$| zW*@@oqFi8^G_y<4f^%r^j*t!MEsVs6Gnj(>nMC*-@cWjCRg%lD<>p{M zjNl54FXeLt)NOo%*_|knTSc|-@=s4g7Dh5T$5<1_T1`gwT4H5cjbW_ac>KjL2b`Lj zDgmpN(Adp&At#K@HAtByRml9vrGU)w)qp>CPlJfMr%)Dmb&OrEcJC?p#Uu+85&pTo ze+7?vajz5ueoKQ#?w7^*h)!W5;0LX9JILmg7}RrG$19sxg$dczV?0(ir$ltQ6K3Pl z2|`h8C@Le0xe>()5k=iiEc_8dv1OdfSQ1fO98nxmpx8zk?LskqH;TI=iuMA=I6aBCa+_4ThIKa91!uK4+RhVUUHszG+5-}k-&G_LbV zX*1YDGe`2P*p=wHMVZ!3e`1fbnR)_N%N$$RuNl8fa6TVYepBM1{(FdReepy)?K~AX`VA!iB=k-o``6;AzGqDnvAVm1)}C5 zO0>if-4+o|G(=rWq{-O2wIEt+h?W_mzeGd_7@`GAq{-O2H6RLxs-znX(I8A1v`jM$ zQKu4VGPZ6th$>r@=zc>qCn7q|5Y1O2O~%&sg6KIzw9*h=6cH^oL>)?`N#5zdP6iv zi8L8ow+lo&43Vv;BO{{k8lrY3(qwGi+aQ|9!!r1@^>kT8bgLnnu0)!Qt$PDRj~F6b zPxnPccNn5JCDLSU-K!vaVq|~oy%P~VBt)@w_pVSXo8AGcwo(1{+Y9|jE%B(K+G?n5 z`h^Rf{8mF{6;z5R48>iB!ls|Q5WRPwc66`TU5-9;Oz%BkEW_UW9Z1#D=XF;{pB@=~ z?nHhV%b3weM+fG~=uqJVq^n!T@%gW^_|RfFH%FY`Bj?%d+KRzfqAZi{u!5Z2CO*Dj zRNK|4=4f@5gWJ0rUY4qMzoF=8;Izg4nGkRkljY3^+N&NS(WkI$iq0y2}Xc)N$@!qfU=gH-qEmSA^dq4W_oE z;;q4}OpEsw!>?T#TpN`~W)R=7<&k>n1yvZ^^>^i#ACXhwR%7;t5j4jDK$LWQ6}|K{_JC$WFkE^d;GMCQAkIeP03)gpA6B6R1^uUCN+U6JPu z#)TU_vSfi4z*iI(jp|CM;dIgPjansGsrbyd`j-52meV^fqh*n><`+x$&H!%f4+ zwrUFIi761PO*VBOvW<*XL0J`qcc1(riWC^id4I#XJHN|dpGW2s{Z>WxI~((!p(5;g?ZoXZGGx4{LsNH))Y@N79kz(1ziGQ!luy?vJG;>^ zOs;C&sgGB*h#qfgi|oLaFDcsnQR?wwl@b;T{aB>OqpC-T>hYKvB2|xVszJ0ga_WU6^uQHr_0Q1l79frEq68^9s=X?8c{&7FfKZ!V>L(bQe^8BzfcmcA;wTI7DHc9pZJMVj1fW48PQ zM${@JsznCPgQx|%Y>SMUCNk8v~Yv1*+jp=s$ZuzsUfy{q%jXQ zC2x_~^A=5=<2bxx-FMC(j+Fu3BC0qD4)R!>o}Q^@S!sr2e8>3zfk?*}F?Q+UL2ouc ztohj|YMo-P-GBCpTBnq2_n&>D79G8U(YktgFsLM~hX;cJn*e|IiCULoc%OZu7C{f( z_WkS=wbDU!cj!5^3_U#f*(YkzKK@_%MD6ZhpVc5nH^e@i31S=z*aR`Y2JqhpG2Tsr z|I0y)RN4eFJ_;}hev4lTVr0aWe$~kYG5!NHqadKt-bySbm!7`L4V=8>AY^W!5)ZUbfhL%o%P(?!cL7xc6gOxznEA5l28~ba z)C+>YMKrpiuNnqidf;E(-h;vAdJUpl&XTiu4cAlRmnd;D6{^d zWj$bLLd$GC*-pH?Vuc{GSl=MBq97jJLJ|!kOAz*MfSUdw@r>pXtRhqI4k+$d6AZ2Z zILWV_0Skq_#HfE1*-rR6;ReEf_%)*E2nXSh2saW=hbI!w-wikuE+^bXHf7;agqwec z{PE$zGl*By=6fbA=gkZ8Af>*;tHNVHqx%^jHHhm3YhXtZ0% zXt%_>Hv&5d8SR$XMK}{O+AZ-O;i{0)Zi)8^=R!uiB|aeB5;EE?@gd>XkkM|5j|fi; z8SR$%m~dN~(QXOcH-$udn$d0vR}yp6jCMB*!q(Qau*yCo{+o`y@(jCM;@xs#B$ zI=!9@8r^lES(|3GTVj~|9VFJL8SRFTCNr@y&1kp8UXs|9X0%&kge114IqgY|a%ugo zX-2yxOtf2?(Qb(`?o?nu;1u6ReXa>4+AYybRYOL*B{mRrLPonKu48e7kkM`l6YUlc zUWZxY0V^pvoEq=3rjCKno+AVnzuzrkxWlrJ_5-{2=$TG)7c zgbdmVTbUh%4B83D+z7^*@Cr!dUaR}fyv4z z0N)kz<)0i-1Y7OWDkCTcT7inZ476S?x^!~j*8r9>I3bny^1z7))IP)Dg!H}wUJ7l~ zvkqe}gA>vcoRDE~LV7N92R;Et?w_f0Fn0=m(eLCJxxK4^HfUM{5eRZ|EFPo)4Ll#F za=DD;tUXkzSU3E0dmoLco-$Nb+#P-v*T84C{$38UEbf z*CWbMCGOEoK5($AvRcuB&zQJDBK&9--lfGqT7@sDk!qVC@!FfbMzC0O4pLq{ zQL(l~yhhvz1Z;>eAM~Q&lXYy}w&jCPrBy~~@}cEfv~71R+cwNz^FyMJBa_&==a$zz zokDUvC7~9wXDvI^arY)$w4Usl3(s=geKggnP5aNFtL3ZclbBPtnXCfR+E@B6!2Cm` z3Hp{kSLu*6&7Zi>)9F2{MmevX~%m;EJsx2*wOD_jXhP zzFZz|$N{{9AZHCfAd;Ci2&~bH-pe5H4_;4N&S;8$h6P;5 zI>Q^AF$Uy_?1T>@Ki>EqqS#SYUhs+5Mxg2oK6sPgFqap6u#?;zdBF$oZXubx;DcR+ z^#vciM_6C*!TW^u1s{AsSYPnLhlKS7AACeuU+}@lgxivQ!3U1ZM0=7i_`sFK+$3M{ zfhUQMBwz4>@A8G$ndA#TFfaHdU+_WTQrqq%U+_U%63dc&!3QPod3e&3BxO+UqS~F6 zNxtBN3YVt4ILQ}$U|#S^zTgA%f=}`VkDJcE2(-0HzTk1y+3iTIPx1wiyUv){nB)sS z*h>lMdg` zsTToL1a3DnP>_1YK$+B=AY!SjQolqVp;`@$56n~{C`=WCK2wFD&r~6}o^%-u<2qGf zQz&M0<5Zz!9RR*WsEp)tN+7v?1LFgoDo9{_pi_kmrwW0cD*PBsWUAo(1d1jOWgC+i z`Gm|GBt||VvxYLx8WJ*VDC4XlRYUcPIcsWrBB40=~=x(xaaM14rfo=~iazJRm)Wty1R!>9K@$9*`bK zQ92Juk0)(2j5HAXn&90uSuh$sD4y_jO4)!xt$1IS#R+eZ1Ky9Y52`cqcmQz*E;|Fa zl3h9$MGJp01P{NY=naHd3wrpU&49m5I0(Ns6!2w))8X^Pxtwq&e7^_<%_MfRbdG?W zo|MidIOvZhD2$sK$jI*SR+u$Y-Hm)Fd>qrRObz>b5I%>|Fw?-Uo(VrBPHraP@^Cw* z2bo5aR%m<91C;W8;#5taeK>@UL{90e87xt(pMtl{pqI%zw$TJ-)-3!yUOFaot;v+0 zai--I6Mmsn{U2!S?ziS6Ka6$Sg@-xJ-05ac0(1PKKIPBteE@j1r&Y>R!gxE@a?S~4 zHa1==6b}{w$_^uo*W9-|l|^mDVpqiCHP^6kvfGHg!+pYF=OXMOu!{=Z5ng%ec^#amRTLx#{zj&s$hZrRR`zd4g?tutjnDCExfB8n8y{h^!sR1`x-{e4k(HtxZZ4wa0Y-8=B@Z-` zI~%W|3yc?_!}%jf?D>MBD$H`0#ZWN)D>=ss_|_pqBO?b}SQIYLXb z#!~{f_c%eb;R{`aNSEhi6tx<)Ez2a`#)ZmRJSwyNK$q_cbMukFQS}~ zwv?Sp*`bsRm9lGSNWv~#AH&Bpc~raMQy33<-M4CRl-hRd3R>?twO-E}&Ks zhVR2#YTspCjk%FFzlgZB+j6`_fpe5i_fT=A4l%vi88L6^DULgV$}KazRz%V{^a7D1cJJjC~ z(v!CT(jC$@(#7DoyAMQf=WBRky&b~pj`(lZdw6|vz0vREj`;6hNfdEM{9T0A9r52I ztnP^aK4Eo7{0|7LJK}#xSlto-Bf{#A_#YEicf`l1;E_;w#CIj3?uhS6LfsMHcaMU4 z>W=tvm+^#M;*R)z-4Va9JK~qP-C(Wmh+i%dYwC{peccfsLoB#mBJPM^<(`SeYH>#} zyW$*2-4RT$u0TTF5zMccPvF6e&j?9MqWJlHjvV+MXFu=MF7lYRZ8w^o7;E2(cfP_c_QnL z{v?IzMEH{hjt872B=}txS#K=bMDeoTShQI{JzXmxJ%_k>4(Ypr^%nkNy^&6gtT)E9 z%rWbY*Z%fLAR^5cugzte`+=NsgHz5_d376q<1#!~k`Y-@d z&2>r{bd#=ee~7G7Dwx)3c_|Ofrgd6gT0*!{aX2l<6~ZTjO)014xItLDWe!CwuCK$8 zmFD5&kpM&ljsp(GHeJaC7P<0kz?$fm=1;@p@D3zOTgm}C;WCVBrNhW|OL!;-lhWa| z-&V)V6RGuV@|}pEOYzS%iOh?j$uyEx=4S-+B+o1+*mNa8?;y~Y1>XlkJh&Ub1H4=C z(5?QtC3%rI>uSqgw?8b|qL}3}_F?mfgD1G&s6!B`QCa?X;%TAsiiR?u_ z@`!x8&D^TZJf^MokN7yHh`jfmACJZ8qjR#a9jSA&ZqwB|Ml0dt@Qn8`C({LGvo>v3 zql`G_$Mti3&f;{L=~VY4&FCUD0XV8lahJ8^J_SB!|E49Bq_`o~3iNL-1Ia zjQw|S0chuFgzX%Su$`k3wsSPXc8*5a&d~_lIU3<;j>beZM`I$IqcIW9(N2YW(HxDP zESjTHTU|279E}NGGR7S3DkSziM}zInk}>9JoZm!qw2P65=4jUeEt;ckMk1P{F%iwt zn26?ROze4%M%{GD7;`jEpLUz0v5;ntM$pdDSX?_tBa;la7WPJ7QSg1F(rgPpF{2`BoB?-s0kh1BzeWNs>Bh6n ziTVE5`Cs5KJP8l7hoi-9B2Br^-^6_P5WEE|x{h$16_wZGsZ%-rD0IQf3cy}v4f12o zfF_cijH9>E_m9X*EE2M!fIQ6H&rINgZKKetg1!C<-0*i9SZoAAC#(-G9E20WFBr-E zOt`Ha@Mtos3LgM%Foq2-7d}OJEc08!_Xv+G1%7K-0{Ow-#F+>ipNl+?B7=Ph1}#uN z6HKhd*dDINP#)~N7eHKmg8X2=Nq_@qAlnAB2aN;(Cd97dvq5} z(KUTV+k}W#Rz|cf_63`~Ta>?JgPrBLj;O4Te-TpUp-hEN3&q?Z&pW;o$K$p0X*E02A{;EhPHA4LolgL(-A*IJAwvd>^5hul7K zANh)^!leTKVZS0}OZbWG3Zgxzi9V6dcQ{J=ey~rwoZN3%j~~0ehF78ePA4xZ*2fVq zi7d5A*yMax^G9y8A%>?Ve{S#ENRf{sV(H8u^;g6`g(9zz*N1NJ6e5o!WGBsI6FpA;O*Vq}1h?66D`=KYgPW8?F<@*smZw?*_MoOwROMaw?KP@O!6qFf z<~#*Y`L?Bfg_ljD2`*#zds`l_Hw@-ScKI$DNEcL$s0qGp>>_2c&u}s5Mym3baBDN% zIwEdwlbckLVvw7t^Onr7aYrmIW1oTBDXi?B^6>4;wQzGHZf(Vu+fGxsE|S|s4?Bm_ za(gs?4td?~-U9l}rON9Cy!-g)_Rc5)FHz-o;l*1$Y8%*WZx`vYbvLYNkS$7^-ngPJ zMUGos(t7LK>nd%f%w*iG2Dszo_+SB~PCB~e}!l~=zi}E`2yc+`Vq`Ib$1` zO#al6)6H`l@(NZ&UdlP?d=*&bDze+VAQG651WFsuo6;;$GukA+gTyx4Y|ZB6?;(5L zX}I+Z%6@Ic{>F%Xh1FQgqXZbNo$MqUBqI!08wSm$Fm5lMC+%bz%fQLT*+NT&V!>_{ zVVR{UEl?ayinOHLcB9yz6w+MNW`yc-2Jge3`5_0u&U3X?&qYdo8w5jy;6q?>)-~j- z91%ZMcc62~ffV2a@n4Pl>^Z=1ks;*Qs#-_2 zj5m)OMQg^g5RZ}=)l@CjZc?4qGSob3=8QGlK;k}nx?rB}3=3GOE6L`KZk1XIGx85_ z?+UBsm8xaC>LBRY*;E}kXXT4Wby(L=2a_^7tTQ@PpAEaNTP|etkr*4LI-FrYrhd!G zW#Up*sLDo<8UJvFD$Mkdu=b55UBSIt?H(t<6hS=uMn=?ve-S~+av=_>sNXu?0Y zH&u!1gbfZerKn-gagWdxn$BNHH=D^0L))&Tpxqy|H6w{|u*Ki&2#TGwq!LJEQ^Av@Zg92f{jzwE#?@i1rgOf)K2U=W*#!pW3&m48!4%tn$;v8Zz|du zHi-g;(gZ8bQspBNuXlvk7(7>2JuPRUwoRhj8SyrIxulP0ddIYf}p3-w?$m?13vExjZ1KCto{ecN-(%Kmg@rOBp6&9Ydi~JKxJ;nyU*_e zf!{g-d42_EX#TiXfN=>6ESj*3R16C&+81>Pm|=lM`w{jL&iY&Y9}*|&3sp(2i;&0D zz{W{EiLt=N#~|@mjhDrcpRS5mEW!VY6PPuCpp)2940s^<1&Oaz03Jj*op?9}xQcKl z!QG5_^_jr0gv?8k=jlF{&j5jV%}_GW#cO{|=KCWGAYT6vketLy)I+?1ah-mGw}{4b z>i`FdW>j9hk?2)UF&{q)u;e6?IQ~2`$g?vSF*}`(H-|7$DelXN4^h5v!65OWEUTY* z7fwjLh4}%363KYjvn0zUQpbQSaX#23idhgXc%p;_*TN=BwSX*aB15=R3Y#cnVXGYf zWD=KGf)DsrZXiFFFEOxCzQmwH`4Uxy@+GRZeEwx5s98WB=|t_55f5Xd4^Wmw17&Mj z5;d!kq#q`4rOPYwFu~Z039l`Bp&+%N%er^cHvHYW`^@o6Zy{Djc|qm2PV^D=ph88Fj}Vln^T10MhNF$=5kQ%9xY>cSb|4^^IthU z@UNm}KJCPS_f3>GcI#q@@LnQ#_m2R^gP&5SIY%I{IY+PoIQ|(o5`8fW>i>*mupS;L zDjXgt%3XnMJv>mZtZy6$s&b!YsaT>Gr|vfw|0Cg^Mi0DxlLn!I^^Bj@#)OZguGij zK7(*&$h)=UGiQKhm6L3ZPx=F(6z|rKx6dWWyS3x9C71Ve#1EpSob*re^9r8JHn6!{ zJAN=VD`|}%ccN!CJf2dVkaugxPf!hcw|4wQq68uD){b`)&V;;MJAM-3s*rbU$4~wa zNOR%a9Boe_ZA-|zwc`s2M|W#O>0{P{NR?jrk4WiL3ra5%rR8qzco#Q%%n6R~0<-Td6t0!9;thIl;li+|oBu z2AtqvqNDTx>gc=2LA}n>SMZAy9E^hOD(!oMqjU{vOvqFzM?;+8=mvwH(i}z^dxE31 z?+K1lbAp56(U+8(6CBHtSY5iF3{1#W>A@6gj%b!1&V)IlS!zyju%0%RniCvMY$@#| znhBXI?R$cw)STeB00<8_89Eb%a~CY6Y{vx~2i5q!Tv_xC3?yHDu~uh9DsX`1l*Ymv& zA=9-J*-pqgQ09NL_cicwR#o0J^Gqf)nMpFqBx%~F?MxaVK%1FK14PX;na~1lCxr-A zJ87j&+cXKJZAg>0Ad8h&L`Am+R=aCy3*sxffZY|96&LQ+F20NJ z;>WtExW51Y{dhiRk|r%JR<;9ua-Vz8J@?#u&pr2?bMJHS(BC8M4}G8U*D+iY`U>H% zXE+d=13fZ2%y4Olx>0m9(F8paMy*FsRHxKa5sW^(n*}_9=_dNHEZ~Tj5D9Si;RzXL0Hjq!iF9zlQTeT@GzqQ))ZULXuczw#0@ zh?;y=7PNpsf5ouhGfVXE?2G51@#}UX!CSW%PhZ`?0jp8B5Kn*IwRo1){VmW1Ji$-k zPkq(aQDg}H6bV%~w4-QG=z3(U8f7>bT8MV2+QycR&K?@Q!BaJMIl|SmH*W6pRE;wn z3vDC(c7|&_WznizZ)5l0OoV$Flq~QOghZQFddljn-pAd|;UgfR>iyS({P1lA|9}X7 zj=>L#V4T4_L~tbw`H%=MWAMYPfjL~q;2*NZ!cC-9Y+?#8X10B7h;S`~cM6KW$kOf- z!RHuz_Yq|C1b>F;=Bitkf}l{CINr+!@q}s^{v(nd_4sHJRHs-)Ukc-?IxTpO#zFNW za$rR~7Jir*sN2TMNsuQ*r9M`{VH^xmk&jg}J{qEK8;der6QUv?t72B%eWtdeQN@i_ z4hQ5R<1ys#!hne-W&&PrdaSu*JM+>As&Q<3tg$vd zz7@$0gb_EP)Rx@Atl}n=TC*RR#dp!Q8SV!6gm@E5Z6^s1hJKA_ZB`P`n^0=I7%mI- zEJFBFhQlG=gi^cszmPW?`Y=eSU2+ZLI2z*Z8#7`I z*MxZc#*7+<>qFv8%%YjXC~Qr z^2@!MDMrgL_hzQqn)1uNnXL@VFZX6HVo~zTy_s#y%P;pn20F!;dowS3KavB%7w{C< zSo765L`g~A~*d!fgryLo^ugF#E!=O2POU|E&R0@0usLfu<&nTf`xy?h5rT{ zKPAAN-?C7lf*(5|@gMbS`aeYcA146<0H1%)eU;U{j0v#v=D~thDT4`EuwurB{gn_F z>{2!gY7&2%d9J!kZe%qEoFR@AG zvwn&--!fL^m^3bpCc1P2(h(PMT=sSb-{&pt?2-?5fN&puf+Zhfuq+r1K7haB@8R(Z z{)uCzyw=&5)T7HOtpl^Y7cop}9cb_}Z#ktkZbuU^l-9T$O~6oE<8Cxj)YIsL(sSt~ z6X)TrMix;7PC^m3cIl#Bi1O3cF1?6Bed{;F(D8!IA#Cl^OBghStzDY=DZ+l*+ND{R z>G9LnF72W_%=UJHKB2gh_YnSFoSu|C;`Y=)?h3}LU($+4$R#He? zyL2r3XV&0svZI<=gL6qTq@NUP8JU}xX6k}VA@O~M8_Eyn<5I*0_j^1BI z|3UZy@p8C|{)6y^;^l!V`VYbj#LJN?`VYb_-VY+rqgC`Dgp-1{qgC`Dgwx(TQO*;d zYWfetA2I$8dF#UmSV=#RcnaUcpvTW6p27!N-JqXGJcaKQtc3C2$+#dpQ1Bnz^!_yxs2q6pLyfM10mSu1IVDFv3gyn?-yU1F^?{Az~`q z*|e*qt{g2Br(6nMIa#C}VBC2H5Mo(4c1thm*(}<@kDjAK(NL5vl@~EFDELBw#xJEEwRqWds zF?aiUxKve54lVPD=#i>g_Q)%8^x-%cIVRsN&*`eFI|3Sw6s+$3)zRmXD)LlU*}YgT z%9FiVU1j%TwP;w`i`7+jFIHFCy;xmk_hNOG-HX*#b}v>}*}Yg@C3?|ckH)Hwk?-UaaFIa~d+@)5r7#Ls{e3X&Tu_L=b*(IWW4jTCL9@vbrBk!Ylj?EK^=#FE)Oad6hZY!h#Taj}=;+eD4cZ1dJZyZ3(gMv=C3-h24=uktNB?`ppN z+uH=>`gu$E_C5J_%RF9z=l!94TQ~0^miHeL=bCwYFUQ+U@@=QQd*a9J2pDAZE+^#w zlWE;(9`a5wNd6KH^L`K_8U_bhTtm=>1byjnm#F(Xv@Cz#0}=GJY=ece4PLxO-pR30 zw!!na$TmpIHW-v`kdke%F1~(zlgGP=ZO$u);$kC8n_j2*m|HOJY}skpHQK=3_`cV+KG#{f zWzGnNrIoW%=k)v!7zrQ5z8RH}X6z-{F-kKw`{^!$Vvib62S0-RTt7US`@F9MDlAQY z9e;#B)R(@QF>2ce-J-rlA7+f&*1_+PeU}_&jN0!Z7fRs-(BG#q=ssFaB+`I0KExmo z8~7f9)RHK}V#(Hj>@b2s3bm3(UkMs5Ag=rlQK$vp^lc=DDAWSt@Wc>>T0k707@|-M zh{F@hgvwnycMageRJlvzPavNsOqIJd@pml1Qzj%|@RIish>|b(rnd?pO1|Km8Ro%I z#1SEk^5?q0St_p&#ePTx^bUt=8T5p?MJqhWfALo=x) z*PxIeA+D5}eS6W`p;`ALSRM~GT!h+%=`9Y;-3<^=n2Q}DakZ>JOmA^0ehEN>VVXXn z1i@hm!o=}hhG6BFh}PrdhL2F=t3*#vM_CCC(lX)cC^Os8tYLAmWo8A+hBW}{%j8wo zVR|~sFFq2as%SyVR|~sE@OOin4XTZ z%NcHu($i6P1*@|(OixGIQpWd$>FFq2wjTtp3)9n4wrmiCaWG5=ZrQQ`I(L7Vo{q9* zcYx$4!}N5>@UvlhI?9$U1kPig3bM!&fQagQv53h=oaJRjgLDamz1b7{rz!bVKA~hUt9#DEz0w-->WBOcy|8G2z15C53bWMArU^U^}`1BI_8AhUo%`^f6o?=5l*v{lB1) zc$mxWkqyk-9OiO+WFx~1NNt|IDyi+?M#2TPn`~+wcUVUTNmcpY@`{7VBpANDk|lV; zwDrq*athjvwtjgP!;vs;{qkzrX0-LoP9f?%1j-z$HT24t9@<5vEZMZx|B zvdaG^cLu|>-z#5XI2t||nJRzDaDABed*!bfj)!T#SN@ve<}mH|%2ydqg=xQ6{)XZ9 zFzxrs|6w>Aqy1j#@$zM9jP`q_SG@GZe!|>7@v*%hPxUa5{~j?sRvtnrQm+wK_c_sV+j zd+~C6jP`qF!u#jQvo}Wjz4Cl7J8yrC_B(Waz8sFxey_YxygU%2{a(31yc~(GV@iwn z{{igL8145;bwqQF_IqX8`$3fRgr|n~d*w&Ug#BK5fRzl>ey_ZTK~I?Wd*wk^HyEb< zUU?t;hUYG}BQ6kR2a3T#vc=$FEW1*~(hw1`F|0=+dyw{fVzuVDv<(qF2l7(Zz&OEw4up^Lnak zc|CfR*P~a<>(RqJY^*xLNyQ(2=~4;?ikA{G&sER=BgB`7c|Ce{(-nwU_Iq_*GhWJs z{a(F@8N_5(-6ke8^d0d9f+Q#q{1Z}3`#l!Ambre60lzMG3FjY?E7mTjK-%xI_T9)C z4AXv(wG$*7ru`mkr_mJ;(|(V&^XlB@FzxqP`<-~E!nEIG?PTZnFzxqPdmm!5VcPGp z_V*#YG)((F*3N0HCrtZ2*3PL*+3z)FzankIey^!wVPV?uHPxiY6Q=!M6JyvPru|-1 z!?Kk99*bWL_&~4&PjMl74+66YFpD9ie1c6t`#si3P+`BvnuZa?8JKvAT<<|(79WVb z2E+*aJ$9~y>Vf4$s6m!G@@%;g=XRL zdCKv!=u;ql_Pamnw?Vm_xS2W|zHgc<&QRMz z#g5hv8k?;e2vUkS{2}vYiSrp{0=$SYf8GN$J0(e3Nz$W=q^u+fUqAgVt9hx5q{S|h zmMD_u23gSMiX>0N7nre$84s&+7l=|>?%!DDHj!yy$H>Z_D>3i%#DB)zb3$&nMpk7MB*#pMoymJ0a^Ils&Rj^+@x_5MR9K^Xv&}V5+kxqa(}RYG&K7Pu>#yhk5qv(OYU?VzJ?G2+aH6T|4hmyheT| zUT=SQ?I)SHJcx12E4S;gpP-@&X}*1wWDG@kdffLB5Ibzb@(3tqSMQ}v6X!w^iHHn( zN?$>w=N!yBe$QWbSkj;el7Rk@j)$c**rUYCyn9gMDe#BrUE(g!#|Kb|_Iyy{7{?eR z&X@Pw_s{tEIGiAKcYKA}ig$qPe&q^aN$Q6Hk~@e4KiPnG5<7?k(t;3Yzz6>OF@lIg z7Xz;_EO!tGe#x-hK^*uM!*U04;MWYx9mIiG8J0VU1HWNd?jR2Q55w|6pMXc~6P5@1 z1ia!!9_SNLJBY;@@BzQ~V<1l+=o1Kd@5PHe&?lfQ2yq5{Kv@vt4ER6=z9oVMA{;5pf25phesgBhP>jC<{WI0Ut3aECV!J&%_@kgBPQ#zY5_O&g+^KQWV z@vm(OE?5c}x#=s|!ZmNP=_@FW32|I|FvV!O=_}~i^c8e$`U);$QF7B)&@v{zh4vA~ zMDU`Ukt~dfQ00$_O&AlQhF(;zhQ>rl8WUpsU`QGhAsQ3XA?B;0F%go+M2N;jNE#C% z8WW+$Ti8Zoi)Cp3yHRL)h{i;yX%FI+F%hck$4gKc6QM=SAhtG!+CG3FyOH{2AV`7& z!RJ6??S9A~uR+D8Py%@m@Zy&`p%VHTgd=%|ShXl27T>-db@ZZn#X(@cecS8At-Yl( zZF~mn;uYoLoBBG|#v77p+v@1-^Oli3s9JTbg*VJvU@I5s`X1==EQiJD_q=SPHd1Z+ z1PDE4x(!Dg(<4H=O?>2BjO$e=);!!~FnJ{zI?_{Fg8&-EjWQ%_0}9IDeLf!;J*f zz~41QXyJzQU&?sthVw6GymZ6)moQ$s;ry2|EZuPa%V`~8w{FVc@qZ91ryI_{bT)%@ zZ26aoSi0f-%UMTHDI4kYNEZ#0^!U9bCr8REQvTH!pb3Pd(EmDBPYbAwr!}-?| zBp9Y?<6p+&-eeO! zAc*!q3HI?1rU6`e1B)bnH1j5eEB2OD_|ZYamSgxg=Ogl)pYOucZCH7Ca@R zr04|=U-K`-{jFC&S4jP0j8+NzEd^UEzDWPpEkFk=G`4^ReTxNQQ)nzF(8#wzPaSW@ z^M2!Yg>}rL;8PaXZ%C|zv0tzWzd>$*44To$jQ>b5lu>`bLeQ-c%!EexPqL7k$v2lF zzV62?`l)PD4ZdZS^^~q{-TMgpxjP<_wSB~*>v{-TS=-M^*j19Q&q=y^W~?GzUr=;O zDj$_^>t@jR>;0l?i5ZoId`uBpe^eEvn}9X=l1$tQPWS@pdGHp{u~Y#rv1t0FMbm?- zt#D0-_hDJ;PEU0&^M0Ip{Y81dZ{_{CBkw1yyjz*~cIK`5tZa*yt#aoDbX(l+$ol~+ zZzJ<=X5NNBmw8{Y@~*b>Zg%9|s`J*hF>lWcM`XTsugvH@aIclGN9Bu&nW~4yfG=3{ zt2LHcFOX#x5b&ALNKEw>rvD%&I&ZuSRFA|cIP}{fF}27taK6|DgOQpxp!?gW#k07Q@9w%MWSdE4g$4QqozYp>9IO&q}*$MJE z>5>bG;ZfXdiOeObIe-s5kC=rB2)vN}JWe{0Agb_J8EjE-^)mQ!c zgZ}k^;pQ|&T*-Qb%eS*j0*nqB&;Ps&Aedr~GVc@Nw~8U*HLE*h4(XvirVs_#|^w9H_sZ?{UVXj+Go+TH=|cRwo0V~6qQ zJ@A56Qk$!!Hdjd(GqZ2sE!8h71kRGW?2>k~PVvhC{G#G)yG~bv$7P-3u9D)ek{X#A zc7An-Dk+P1{#Yk9lF^biBP^+cWa%;Vi~wVuD(9|aqAI2GV-~1y-=?a^_!d?5AyP4w zvnP)+rCOH%E|2FiF9+-cSq|8{fG{$E#{v(&Dph@qnMeGB_k&`228AJ=hin}`{Ouf4 zpGCE;At(->@J0RW`oQ_u1AzYmp3)%ASfTEQZbK;aA^m{wvSet>7$ELKRB7;!@l;$N zelw7Go7W*GJj~z)BG`eacYz4*Vr&b8CC}l(e=O@e_!|kYT!+LI8!db*gJ}lKM;Tlj zf2<2HtiJqt4^;FJ*J53D^nmzz4}8{(UcC=>^e!gl{8e5rURj53zFxJCseIj!e^GHu z%G)~;d;$NeUQn$GPm}n40tlr;6%3M;MUFk z$*~PP1{SU#9~$1cZMbiHe{#px(d)O3^leZnoBOWsUpU%7+~2pYKPkZaN7oWhvTyT7 z;2Q2*-#;vo>}*eyuy8{K+KYfI~*TQ>J?8|xoUZrC>Nx#G&V#k;PFBl?n-l*hXZT7EQ8g{ysx z;OyWz!B`2Z@2&ElQxOXr6|*a%Gr%WJ*jbUmD+Im@QtLj~vkcZlNt?&0cystI;bpPT znZA0F8yMdfm>3^QDit{EtZX(`6yUcDD5*rT;57bWNu{#DpenG01$N8?lRGJ3M48{q z93;w%eBovk)c{Np1cD5d$Gk>GIIICG$}L*jky@!ZW7=)>w#7Cy&r9;VEdDb8Ll>|b6d4;d?#-eHgheRtqK$>LfJivq5N z3*E`!=OU+r-_O&m+AJCwG@P#oSOK03T2zs)5a8RpVsjS|`8P*+fC!;l(kQ>I)fnre@q(Hsfj* zb<)Aco#X5WtLI45T)PegoaY2|bR|LKZef{FT&QGcqh>oYvZ9+9n=Ix43s^;;eD7W) z+HeXnr28zS`>agzLRj-gME6O#?2`&-pHS>LT0SZnsLF0B*}2uuu8TRlu13A6xvi++t~t6id1z1wzr4PI?&;w|c@k(?TLS;~jmD zBQ%{UvhO~6DW>iD&Ul?eq`1VE)!XErb4bpzSewvx&b8RgA_dtAcAjD~HF-B%fW-pj zd^bN{;O4sv?dr4gkX%Yex!KT`U5)}oRa~;mRh2@?zb8xwvnJe@NsFYl-MHbpyi7Y2qSKGKavpOc=Q^?{rXG0yM zfNYQ)U8sVo4xNa>1$)~aE>-G;#XH4QC{}ZvbEcMAitCz)O7rSDPBbn)z^+f{lzpDX zVvh0zD>d6GuF-;t*`7G9@x@_qfiuOChiMmD*eq5Sr7W=WI9OTf(hHqwu1d7HM^Vy= z+)*$l=!sH*-s4H5xf~L|RjCifR4meSM4L^HiZ;4t5{8I>4c>a!lDn$YM3cP|#eReLi3J?5Upa z&$yn|io=A;oV(lWbhp#S5W>6O-F-8ivUZkJ*3K?e1R9idv!ve~YdBg{s2GfMo$-1A zixgY8bI2#vom#h30?_VvCvplO-R}yp$ZDB*mbGPQAs^9rQH~HYoSyzsO};kUskRwY zELSej+{a1ZA&K5F;^eqY=VT(c1yRUE^_n4Py7_RH-OO_8oNY(28yakJU1So@anBz% z`&m6LCZ~B8TROT=q>%L-eU{LDsX0xt!h9zUE}1o%$Z;^8V;qo)ZS~VZj2I(t7>;o= zh1)i9&M&ov9Ab+sH;35XHg}7$HR*423}FW|k#}b6{yf>HReG_U2!t_D9g*g|W9BQI z+qIG$)=F|jakQo97J4(C4R$*GPEw~mDWhI##rBw#gVde@+(T{dq$6dXje=bhcLEj+ z5xA+Gqf+b3)?jqVc}LFanDuU@%x}+nv{p*oY!|S7=%u!cJ1AM=_uaebbOg?}x}tb) zZcyV(O}P}fl$YvN+x_ZwUfBD#861^y2B5*|;itu^f>R0`Aze1R?o5bgrU|QE76!3N z_R(h1c^1XR5~0~G5o|NZ0jdhPK-ESumbTi}>jF0y!itfS#-4=~8W`(^DbtkaXW3DT z7kin+!GWrE^)iX#9j%M1*EyQSY{BC|p%hFZdNl7$D0oy^bSpY$lg8t)*?c$e2&bxQMDwfa3iWDpZLxHk=kCoyRn^_6$7NOB-?p%I zl=k|Gsy9a0+wHE*6^j=fjjDJ-&z?#uxRfTxWQUcIiI6y@mn~Xc^2=q5*oL!%lC#}= zV#}_RcduiptDe!_JJr~B!ke}4yiw(f+V=6Ks|b`(}Q~=&@&r0kT|vLH-?NjPTy#CM)i$WXVmN2HpV8O z>FtlO+SoC=)VS1bti~mWsbjF&>(P#!YFri@G;&R4nPA%s&b?o1vqGWoO8GC`s=VHU0@~;a2`k44YRlJ%y@#M&JGUyd zbE{JCDkxsfb#@JR++hzMR&w3*K#kM)g#*iVi($8v(^)v9&{=4^lkFwkS<;$xIFO}^ z1|e(jahq`XtD!ts^_c4A!cMpPx|l!cva;M0_I4CEgE^;f)%&WX$(+Juqsf;g$nNL6 z*~nhIb?~DSHy0{u6a!+(b^^BrOLQ&RYMC`nUUc)-NqN}b7&?HH`Q38K(KCwgv|Lg> zQ@Hs+YlrqCngfOE+{tFB>3BsamLF1ZoZz~)77w=X+bv4UZBcTB(2>k7NA4;6Q>sb5UzA&+lCqEa+TPq``A|R9CLy~sAqVU2Q&O6@>Xx6 zRl~o~UUT#4WcC^bw@doFShiU9WAl${K^LIhlO|HE_}5v66mY05F;2mDSf@^bkM-z@ z#FkiWVY8)2t>-+9g*scUfRG?uy;P`*dC^{7cFmQu?RZ{?nTs=qj!Ot_>CzAIQ*vyc2|2~K82l45lipQ9c5<{_;nZTyLB-;wP_QW(sickO z7xh}`aB||c#<^e;XNu-$)&FoZ3kg?p8l9Pq*s$w~*%IDIa zqpctbClRQ}k%LY;T%@`-={hRzbD( z4MuIKLLxzZ(aNXeYYE4$VZE^eBZ6w7^CK~B!dBa3NV+4~Aj*W75%Qz4Le<9Jxgv%? zzQK{^DU?9RZYO-yV@VD1ncHl4zv->VlQgrK1>F6mN3{~jg&Qc{y*ag(>E_k{#kQMU zBbe5QEspUpQAgQ)#F4~~atN|Snc^~D;9xrsCgFoqKHL;-7#EVqi@(lvGlpZ(3Ga}U zUD(rPZw9W=L$Ol3iK1>^uX2uJ_fCJe`d6ccD&&tIrgiiqy*7`~ByG#CE8JA*?mGH} z99?&YnBDF+JGEbsIh)F*Dqt6~7LH`<8u!#v>u$F?ce_n3j85TQQbD`?BMYa_4~McRgxa#Az1JfnTZh zTAVV@IazrE&%!OG?g`1UpGQjUh}I+ZC(TxKS4>nh)!dct z@rxdFvYn&n*mTvp=?ZnkNeXZ_k3%W6N422^JK02^OrTo@->a(~PfQJJrosj%zL(iL zcX3ll^Syi$6Wi4uE}n9>2A10OY6iz7UaM?dmr9}@o=Azk|5h)YM38?UxYg_N)$h9$ ztyPOioIQ{Rv2~=RW9F6$IbuY+6rQ$#TRCu=G>#j?5pKW6*#=(x2#EiS&#mxyw&7HX zF`QgM7*ELOF|!PKjHEX)e|}=VQ65hu&YSNG0?&NJ`#f{-EW+#=+A=iOvVl20JMquw zN#R)pHW2|hIb+B!f2l6t^d=ICMxPhuf~@_QWPuN4ea+*wW1G~89>y`m3Q%#RlZS_` z7L_fJ<`@~>dR_m9vE*f!t?jw`s^yn0Ub*(_6+Ouw6^-!PbW1w9^r~xCCc8#P@xFBH zwy`9SXOaj8Hf-R@8#r5I;l(X&E$M}=sWgt#XkRFg>R77|1aX|sfg?GR$Th*a9Rfje zXv>D-@s0f_jeo)tHzdcmjcU}%^+RLZPA7hxhH@Iwdpw)_hPHsaz@yv7Hg4?S)Ph^b zaCg#;BmLVD#4#~Ch?8c42W^qoc#Xj5L-vw7FkGanST+6nEBob2y~O8|c8(*Ad7h z)0so&p-i$hky?HDP{Pb4%|tSFC_$hMAGq$s@156t$mHKfK17;$EI5bnhpotk^MQeH zfp{R-Wag5=nzVRb6<7nrIxHzz6)B~>V`dw$Xk)}%yq0M#;6 z{6CkT5`f6=94FoI7FU;cPOMJai~|D0K*-LuNj4PWPcaK~ar-0!0}&wXDlcGfGe$SRTkFyAzpY zBAGYS#*HmT*(x?|qC1(%tGHE&yE55|GSi1TliAOhi@!Ub>omKJnvU#ZqjJo+A#PMI zH^$<*M)6;h&wyO}HwZMJIACZJVRhoNW@=fW#_1$-@S4#LNy$i>p?$Q<4EZ)qqhS69QyMeKuABjqSAJ5;{N-pl-GB(;bJV8YrDYCMk z2(d>u^LV7fx%YQA{k&F|m}+XooNoP3_5ssu-nxZ<_-}mi*3te&EjyDN@b{$Wh%;*n zon-8sWJ7fg4{RMB8XMev{E>N**r~lN86Dc*KYCiw7xwZ-QB+bKO?J|~JvGPj__f!i zKIB?gZBA|97dD?=9LChCt>8pb{bV)TX>?HEw#^F%`nU9t4xPN>JdI*bJELvsAH!^i z({`^O-$JGDn*Ooz5la=7QzE80E$O6oXep^sN3~`OZB!|Z03R6}9PRJh=t#SIXv+ZZ zP~Fr&3Ka19Q(L9-31F>~A_%s3=%GN#;k|McCkp};TfRv~Pv3^?B^jEiWm|Ci-zEtJ z-Bm|-TiUFS=^7d7?z^#n6tZS)>xQkv5)I3^1|8YQcNAj3I}u~fQ}x3fNRXwNGW)1i zt1NgafL{y+d_~`gyEGMf*>=pjq>wxWB)H3mNSC?55vjnJ^o{jhbK{l`67rgn{tX}( zGqwXamT8EgyMLf>!;J#H1h(}S$8W8Ib{S<4 z8WC#PzC^a|QZu{AywvPWWrQ6N*c6Zk$EHA+(4jX4Iy;m19y)a2y@#`AB4OT}6E;g= zZy<9hB_LoO?4i(FNOUGm)2NM`)-RLE z7;oH>fxnWf~s{Alb z2J}>ppnEFEv~2mOkhoz||CE|z0aKtu0E0`1fN0axI%W)rJ2F^-szBRJX#oJx;1g&8 zNL2-6nlGNVnOV-|h10gu1>Dm%B8#VOL{2zutBKz|Z3B3cX&bY=OH&imHYdpYSE~u~ zJa2M5f2UF2VfNfw z#;Army)#+S1aoTVFVw*`QJ(b#oRAh%*nF?EC%~R@tf>sP3nmVj7aJy>j6k&T?*UFu zU~*{&las@;{oiBt7Eg?{wkMt#&un{^6XxM{YQmi5HS>>k;-3-jNG6){kEI(^na5fi z8#7;O+-E+PNPWri{L9|%?hGUUGM7rUCL0sx;%=k9#Wcqco4sZ(mo;<28J#in+@v`U z({H>ph8Z{AIG=x3<4+DtO=f34(U^G4b!PW?Hl0lE?ws@SJ54;&pn{V!OhR)}64V%# ztLCieO6DE|!uc^XolK;X2{HZ7g`VQ`{Pv8p@6JxYQ?Hdz-A2x}>{B~~z0T9`S^EzA zDkjl{&Y0P7?dHCbwS#?IHV*gyPA5h+iPCL&3LV4K^#C8w_QMoM&GL6_;Z5e4MnMh+U2|gCgKbJ`7^6)`+rp#ax6IXKImod%kOEqr) zlg*e_lIhq}^J9nR#~zy>duYD-RHsP#{ALC74>}-XlKW&%#>O5aF8TfhFvT89o4bG1 zss9Ny59r(guyZENMl)yq*O^INEDI+g4>|tFD`U=0Bm~`N-rS9CCtvGMkCyCYYe}gU|gav4V5$LrvzsA0^Ue_Ql=v z)8=ED&tL{_BL2tD0iMoSZzjT3@CNHskvk_D`ydzU_5KfS$v?DoTRA0J=lL$#>YRS5We*nDw?FwlQ| zMrjCVJ-{dB0e+n=TbgF4#ZgkIfSlD3&Rh+lYjm{l#+70f*HR27+L)-PYuLoob^aDR zcAc(U2rP%$Z98UBfXn|2@uuOX>*6i8UxD75Sy6zsjow;5M2H`2@JXA)PgNnSa)yVo>A%NufL2A=0+ zqA``s8_|wTVt#L%-uaoy8RZ8jdnt3KoXkt;VDBf4XmB|QF`ImTOr`$}cJO)L1x@hG z@pYe_O3zNEVpE;xik)2}Lo55SbNh8$q&tlgd@^xN!S?t^m0&CPCgGwpjT_@|l9@tJ zHn<(bpvG*B^UG#Z<1R=#IAL*FM8p*Mwn{1cY8BkcF9DSnarWk zisi<(IR2I`H+JA}&+LrZ-G!~wMx>+Lc+0KEWpU#z%Z;V+ft!q*Iv_ARAS64CP~6zj zVT7NYKVXD{o96F!C6;}$IO0m6%qI8$hlw2|DgrV{(4w{ZhV!KYqll(%u}wYJkaXkXJOsV8RLo!(`_ z-w%;C!C*ZtIu^!`Ya7sMbCx=U%PEy=N_I_DkKfscKn`b{R`smiIa(OPK!J3#H{i$* zl(BuMSVX$y9Ym6ngc8G)U!4HVGD3mg@(Ch5u}=`9Z<5WL4j(0iDqMp$!8-I?=pSqlWJzD;V#oO)~LiL(@wpyG@Wc*lkdfv6gHan zCR(xBxcg!A>7V`VXTby>;u(znELbDM!9=j;2fUePepONteE* zEMa6@q6Ms_B@Q$vB{_rwCB`oBE;+s|=bz=Z9pDXr-_@VkVFi zNTm+9@$+h=zS)~I)0xy&>71!QSu$HQ^M!wG6P`Xk{K4u#t9e;sQB%T*w2bF+t8*(5 zZSWf=<2`tApCVFK6%J|C}r$?5PQxc zF5rfeMawL?R4(~2i)4ac@$Lw~QJGPbzs@33+M>9xcsmiJ}GRd@aCk6haSsg!kdg(`>$*UynxO7{3EzJj$bV5Hy6? z%Oo=iNE0a$5QAM?iHosKD%Z`mT!$osfP~bPC;%qprTq#dlv$0rhvpMZe(kE{k{soo zm?w^VILjoH^6yZUvKUSDjEl$YzH-j$?6;S{uKKOks~VM(t|O37iM15DWVD;@e~6E_ zsTREo8^Tl&qCdGOhm&u_^p#BJFuMtDv;xz)&okq!pgb!mC*R03kv3YSwYhk?C{=7g zaq_j6tdwGS;`*J|x5?3akNcxx>ydL)9Ma zS|&{_y^1|oP(O+*Z+*@D%0Ef5F%w@@VJ1FgG%LPr=Ex=9))LE84vBuw)mv(a|L46Mk}RTPQaQA0W7ChjAHreO@ljV3sA zp!+~Q%BAw@!F}o8edE{f({c0~<*{oE@!k8zS7gKnH{qG1i6ZyA1?PyGbOheDM;M+! zbz<3s*+~itvu$S?la+Rp$_C$;!xfm%^%^&Af_qBW0LdR!6{MRCHEBgt4y4WQ{Gt55 z{GCXJddI?LYTBJ@)0WA%vKb~x&g2(a3MEZCY4I)0EW@!(#?DRjKpHW4H&giFNi`Nae0-fyPz`Q1Cd3cFhw@F_E={D7>0YGjn3x>kgx5*qjc6Tu-8HjUkZ zPTSlKS60t;}8Y=?iAt!!mKmbNf4fChkqIT!$QP( zav-_G+?~7XlFf<6>r7+Qa$|N}h&^r-#zz*AJeY(afG|};wqfqBf?zUp`9ZPMP<|J& zA7q}`PQz&pcr_$X&I>8U&RLl;zH{NgmT|Pk`bl>;Ptw3WXX0UXE??S2=Z-i9N1=X7 zRlG<)cZ}BGW07(^>Cx@$q8RZQ4ch-5zz0?s(qjF9%bJu6w!)xSJ%vO;GQL*;u+V56 z+E1}sF@Uo#Q|U&dx@G$S)=VAxg+gE{-@6yICXKIpTDF_%w29L&^SRVOqwzH_i=lpR zt4>_iG|h$c*5vl&8}p61)>M9B@8KeX3+Sgl1i2`Rg>1~`a4cs!H!zUPr*SxFM^08_ zRUn_n;z~MgJn!iMDbzj9d@hYIyM=TAO+q0$|5OXNlh!n*UP?S^)Mu5LQ=!C6aJt_c z)0a0vMJ>NwB%-9vOz%J*das@!XpP^mdA? z36^1T_-;PANJ0zp;)*C#9njjk_Q2%;)WPP9<05k`3n>+dA;Y|2Yyb_rjT1wCzUAs)bm_ zENBzuGq|+PMvxoKCB?VEaZ_YywUZR?PGh8HV&rX_kg-5w_kweic20U0$-n4F>{T=y+8V+3sm>&} zXxHX)UuHjRr+;$^NGh1@95EA2c1WF2 zds;1Dbr~-CK9RcZm3w&!b_x`78cfg6M1-_vA#8cMX1K>a^^tp%DFg4h;!pc zqmuh!y@@Or)65iB$dZk%IKtvhO;{t<+E*r>Tf6(3huR)W4`d!nCt6+jk@yh*&-Xs` zP-^!>DNK0?K>q?)tNkKZWAOVte~7xAwBPy^aPM?k;51%h<@mto#94UiA#yrLA2`^_ zwR&t!^wqWch-Wg1uSW>d^$0-_v3;Wh(kI-petc+nY~j$B3@wSN#*QiuGlw;5fX^B= z2wS%)Vc=O|#M4UY>5-$!XvJZkoylC#>=ypcE;uo6+yvDujk8=H`-gLIG$lTQxoPY? z27-TZE);Sz(`)uZG2}S0$v{ z|776l0kd(>KJy2n_*H>S?z!D&?%xNDfevH#@)XaZK?b{Au^%(h8a&h~-8~(F)M{KM zn&Ym65?*#x@-;qw!3T|=lDqjh#D_@eHF}n(7p0B!;+@j3i_esh$eO2C3oOQJycUbJgybEYNu_+uDkjUeEC*N6$?`y^Ym&Gj8XGL!N>b$XIxe<=z zd#BE15>*nbVHcqXeV(74l`6mIQsub2!%k8k?(W+%fc=i*I7M89cifY@+(JmKLW8r4 zqzUwsS-Oh`L4^&P}^2 zmde@IrzF>#y_~~CfiL3e=d|vlkGF)bf&dS*70%wWTLWex827-OAz(aL45n}@`Izts z_!>YOWy%&apWL3mH~AReeG63Nmmf+6lR*fA#_lBLp6|^nVaNPLTN2j*;0P|WHI=}P zZxE*!$IRS{bSwv7LsHn!aeS}s^L!a<)>(B#-+Fpl)Dh1Hp3-tE2H)nsu|W(N3=Dm8 z3VM&z_sEbM1WjJ=3Z<`-Bgp&)`Q0Dj{NoL9QWmE=8=C_Ac3+y6lh@t=zV^hllF!TO zR6vPr97le2TcIO1V74Ze`Wwh4S~HE(h7)H-FIV8|MS?944CHyocc>$q-ytapNIEq* zvHSTjUQkC{i}HxY;6q&gUJ`84iR$kdl6)eYcqpX*Bw_$3$SS8H$GLBLpj#7u z_ki@4iuhFlu^&`O3Ii`gi61FXB=H6U>P|$2WqUHVWO-mv?DylWpO+gkmj~`LgN-}^ zZ}4$|$QC!22ee~W+_E0PDlmsKQUkg7ihyV>(d2xT@KMS#LhON1pgX{dhHyhYjwpCK zm)LIf5`+kh^Ovi>4M2}#B)o5u7fdtj8fxGg- z?W_=f#tjb|vE};`DQIG=NLe5d$5TjNACZY3EL|SR;tF?d*Qa!YD-DUL#{#-Y6Uc@- z20E_OdX%iptpS2@MmAU*zl_l-{M(&xRqoY}Kr+~k1J-jmG$_$3 z+a8@}%CgWang^5YeM(xXZ>|a?cWVN%JrgIxs>02DE6!)7&ghdh-xSDXbp3XxH5Qy( z)Hp5)W~&$+hhk0=nS7f9$x8%6sD2>=uw=<$9RcyNcpxBVFm}3M%undbe5;vHDaBE+ z3+Fe#2#L{cZD#Jt@0(s_)fmR$)Rir+eld)(y~QYZG{`^_Rx?O(w1}vZaMFt|B9CYZ zgf3C7#7HrG(Z~DjrqgXWJ}@NEu=?IWuJO=wA|Tq6j}j&b)(#5%Y*f27b)SgV3>CH} zi!EjTAlmg%D+1mCUxlPGuvt~auoR_91ahk3L96Zp#hHR2_5$+pY3vmA_|T)zp2K8`KEFFPPRx=b3P5dB&LI4R_EgOV&EkiS(IM~7IVLJ|3R^1tl zsYv!10#5-e1R|ckgL>YSFH#f&M1L?KrwYoUeR&)pyF{+B%z#`W4=Qa%!t_3Kk`%mcVLj{f53Rg%a+#KKL6)`nfsP4!c=+NrK=DHloud>6eBTyCA~3WG ze{r6kCESs10ugS@d%cK@Y&gqL#Uqnz!5F?BS=w68BmhOdiB+Ehi2Iy19<}ocxJLVS z05T#WttkbdoIjR+OwJ!hrMI(j`(XE#*wXXX5Al$!WUBYjVNMV5Gr@J=+nCvr%cKTV z|NO&&#vjtE@foAk&^dh=)ywY$OfJ!gotbM^n1`;ukSR@!$(iGW8L`n(&M?iWl+VL2 z#7=sKDI8%F+@5=C$3kI&j&nNCDCvD>tpc9fK6oQYJ8PX$E{8AMf|d47eH+wmiF)W_ zv=*p^kRtY3rAqi=7)>ht3grf*lr2%TScL4*Vi7^NSOfy6T!BC%acX}hh|{FnH4rrG zX#49mA@iUr^bMm{Kx4leLEg4DQ!kuNC3~_O2}}v|2c%?_1X1&ZKg~q`d#aUC2d+F$Q z+WJMEGwo>z&B)e1s#`mTqY|OOLeVsF+jX*g4?Zc%Ww;qzyl=-r4C%XaIh?+qQ@hs! zotYo@4)hMB`Omnn!7Gh&>j+2YrKKF+zadl^JX4`xahX0c$_POxeA#Pwu4=C^S+Xbh5 z>VG|_oDS_#?keL!B5#Miw&_M|^0DQE-onLc#j#<`+S-NQac%8VQ%=Jd)WEOsiv6UH z^PjksW&Ee=|Em%gTUhWobnCwFWey?)yWZ1Z}Y~B+mge5>-&c#=+5?w*IwKvaV5vFFSvg!Su7&f3M3NMw&X_K z$cfFpNtJhe%k^8f?%1+W_{jC497zbh2@qY}($-=h<>%=i-h{o!L%iP;KTG5*sqw%U zRagC$$7@t~7+d1l)@p27jz1l9cvin`+hq(`{5=mOcopa zN49C|;3pj&+tP9kuR^A*y8n_a10JIp+9t6fZoy-Uk_9>r9!$?~@$-88JLg8`c@~H~ z9#2muD?-Cj8PQddy(f6Ew5xoMQSblmcK|7WP3rISS7t@%cJ(Q{AP!4Tlr3TO>C zc$I{E#)8v$M+DqN^y~#}TaV0_#c<%St72W3C?GPY$9KnfzN-mhIfNg(I*X^rs!vx% z^d8?qFX&ln(L=by3a(v16R(ELx!{f|xcx~ z820>iRXppv=YoUhgTSu4ntgx!-S2!uR7t}>{*J7GYqRji@9`fr0Pb5Z5Q|igN7w)5 zRT92K#oP7jcG0^aFX5iG;8OPl4weA#4KBD>72E@={7Wm2#Jldf&42K{e!zO@33u@k z=~#-sx_`CAKWO3C?fVW3Kj9*4B-~C5PS3vQ2s8!3XzyWoC4O}LHkl;w^U;p=tb zJEq_?AKUGDxeM-91!wb#Zcm#}Sl_#^mF3#)qU$T$h5b&rR~6j-R==;iCvq^%e%~Yt zR&-C){!fCp4zH8ttWj`X6}p_27Ttt7JLfTx4{o5nD&O(s%9DT#UN7l>+`_NMqf~xf{>#G>uib8%UuC;#xFwq<+^|)?mK&0*Dg!A;h#qW=JQOu@A)d^$e5RhF}$AihJzw-v;XsQ8qM*Y!HA;=5J6EmwM6 z^uDCv9w>qvaKYU@k`)j~ir|J^a7%8Ga8u!XNx|82L${|rpR(PXM~`2wZnt9!PPeCS zhv+t$f2wl272JbG^&1rR)8)LP;B-Ieau$rqa>k1C+w&glb9kC?HRIF6ce{eSzo=X} zomup4m-r^DpN2c8;3n&5A>UAs+jmHO&syb1M=9TG@Q?LewNs|IsdOEGhl)=X#6Pa$ zb^mGjpHBkcbfd&yh-c*_@p~qTe?-L>miy8q@l7|m%hm0%QpNL~Kgiw7EP0Ri7*XlN zGTAZDyXDch72MqxoR(YbU3@t5uB?D4tpDLj;-6LVOB7z+zBM;XJcaSARD2=++f{tK z!lU`-sEU6<#oPAHc9(p3^bcftdo4I!zdjdS&n*&eDmn6sf}0B8-gi$AU;D1<(f6!^ zJ7U#C%P+S)-1Q!b??nqv&u=^2{duc|iz+zXKf6?XO2zB;KBD4xs`#!7-Hx_?FXZR$ ztbo{M!D%|*DazOU`#=#~^jhb5Zr&sD6w=qO;x&Dm?m-pbrpncHA5ig{f9!cl+J`#- zHx*oSLH<`&{9sXiq@J(yZ+x$tUS0l}inrTMw}-pkUQ%#37nQTd#ixU}$#SOR)9Cvo z+@lsg-Cx(c@I9&ENH2eO``C67`}L)1!bNY-3Opm?>BJ}PJKbKp6kK6H9+@Qm`GR=e zzR~x~@(vf3=hl;sD7Yg&Ufjt(0DiA znH7LG|7gCo`G@5<+$G`U)7jrE1fS{h*C@Dket{Nzw%6NrPsPFVuE?AbqXwl*570#I z@ocrn^Y}+)2|Y49=R0M;yw&1o!bSE=xM2%U_n$rQ5pL%+;a*U1ll33li}>#NV_7cc z8-MmVlJ6Ss0R`7AqbG%XR>86T__OP4`@dN3s|xOTd_uUIKgkL_-xg0NePgcnds)G0 zIck?H-BhH9_?kW@@g4C=gqRPyghMMbC+>Sd_olQz3IEM|B>ZG}b^8PlO1M1|E$XfP zCD*#>yhFiFh41Jz;eM{*c3S0X{<7sX>oI&t(l=GV?4Ksw6Vrryd75wyho?v1QU$lM zsJ?G^wey1t&h8K0F7EzF-7Cwr`$NkM$v3)xH!8SYMdeEUK*PPD;Oudt%eDPZ?2pKO zvfQ|ZPnUa{s~!uc3D-SMxM2l1)wtU;O}GQognMKPxQM5CK8b?JXH>osr1NLXC)@8z zxQ>r!Mfy~54=T7p0qvAewqKa|YVMc#c3N<{f9!EZxH}Zw0Sivc?Tw-zYYt+f_V3#E*PL_#PD>m(h-TOa3TqFOKW%OxRB<-_4eM)9WF=1A-uhuP{H$-G%)6 z7WZzeT+P3>KZJ1Y4`cD!1=N; z6xhy8fBXwsk#JNzNuRcNHVf)l55nF2XjVY1v(Ko*zhe{HTPJPk~3l*?K48)+xAVt6!{fEGH6Gj;8PSuSkqs`sNS)?ppx@ zHD5gO)hweuKey6HgcghSoSU3{q2V8WLc+%_c&mIVfCM%h|FOT8@Gn_%XP5V$=)p=Z z7(MDJAcA~OyMgq-G6(+cCuRP^_Gdpb{h6m^`bxa>XU_w+d>~x>>8wa^6Hh0cJ)aY9 zrGmS|g45$~oyCuYdtSlaZoz53wbz#kH~6)zfY?|BXX_<|dq%;nv*5Jce48j&x5t8K zvI1g>1s4_LNvDrYk^aae>AF2%QR(X}{JLIlI##JWlK0zi8!Hel>__4~I?vd+~3x0^)HCPPcjc|*803T~tb zztk_--h_Kb!R@u-*0UW*r@-^~S&=eTd5>39F5 z#1pmTRmyiMDyY-%|0kKgz$1UK50|n2I{jId-fX8YW%@+?^*|%)r{LQyc-;>6{td#V zp34e|r52p#b2%N8e+aiz!F{_3PTILO3U1}GtbkxX{z$*bui~eopY-^z*zSgz+g5^kf#Cq2G*C_Z8O#_!7X2LZ|- z>N!NZbUQ@X+yX628I0Z}rO_2YL&B!4D;T zuozw{m<9OTUOX}Qj{hs+?Qw6>)8(W`w|Dn{NccUfT)Y3IUqH9ZvkLAdt6eO-JDqqn z{Nq2Cc#jpsZ<`4I?*BY7_~D;O`03aIEB6TnH(9xQe7~aL9<<7p<5&07{r@e?Ybx$1 zxp1KJY5JagMZ))3_;kD2_8!}%{+AMN#Da_WI_1XgDm`weE4|#Rtbs{W5ExT7|nElxZ;UzK?5 ze$jG9?i+|8pVKa2`$sQ;-2IKrcNp*d*?iP5*jU3oq2Ssjm_y#$^D*(gs^I)q|Lb;< z`y@3!&u_B=)5aovQlBS35#L4yce{npk`vNEQ2909mpok}ro+Ok`&UM2xMr_}TVla! zI&J-rk!6G<^KMQc*RB$^jINkn|uO@2$y%$2i^hr8aS@|@*(rzao5$=8kXSaXU z@((cm+bZ3zk8RH|J#NTy3iGo)n7&G-PsWED?g0finVew133?QqJ#XlG`HJQZ!oTE~ z^nKH62i<<779SGsXo-Y-un11_xu$bCAmJXh;B@)+Iu-FXl}b2UE^9uJa#`1BSiuc@ zB|>|g_~ZhTDo6L%v7p2|S${Nyj-S3xr5E;>rf0uOuea#2#)Vu6ETHE|nJjO=)gDn{ zXX^G^8kXr#Sn0aGwuttRAihw3^t3=9Rkx1W`Ej zMB|g{jK&wOkZ{jh^y>QGVDSs_J+I)_Sa7<3?R~O@>!_6YCgW>e?ude0S%lB_lMvq% z)5Q16H1Tyuk53=@j^*xBaL-%xrGy`ie8cp0RT9rpuLN-Lu~e{CK3(6qy1J>u!l&C$ znhAw`!Ey#uu=`a$dtbZm@8W&!gx^~u>3YH{NB5`XBi4^_D{Cd(m<1PIU4gJJ_equh zs#QPDKfapH$Gd!Pli{w&rtyu4L_(v@|;zGaD z>945tl!Y(lTaE_N^=+On^YfiQdpyW@4cD#UZkEvw{YUP@(eyv5;JPCcu&d&z_n!KL zGvKE+qK<_T4PTRz zA>o!3!O89y^#*e0rVjT_PXbop9aDCEQN01jP4K!LEBg;63<$ ze&glq)jLQ?588ew6x$E`N`LTV<86>*tdSxuRdge|v?*`$#eT zb%lIRI`&>A;dd%Lw%^L0M+g^Gmyt}Smrm5q&tHN$Ugcx^@MrJSvG?r}ZcM@Lkzfva zX7Ar1+$##s<`>-_(mrQ7gj@PnS+D&TKHa|?L^Ei(=M|i-KWTYq>rcejcD2NJw}nra zEB7C>{R#J^f_uV(JL0?N+=J(US)}5i;x+so*GRl~So4wfeV*^Iqr)`4^>3H(cKtQq zxa&Wt;Fym;dmeGO`yC4Im;`gcNjH|JbK^T?xj(n)JmS5l?qDtI)pb{m?=PI+5waat z^-B1-S0e7Ju-d^VJrXir|65bvccDp$T zhQ?pBR>C)1^z8Nh|L)!fJg%!c7d}p$V89`Q1Z+wO0!-^$Vq5-+<6J_Yu_f6O$hMH= z#DT!^Xl5i$Jb%oLY$*+?fwVOcz=RY`n}SJ0YrufNHU$G|>+;897-<7v~;(D_FaWQDKe!S;Z zutUVb;}M}d^%Ut26`mTuM)Aq%q}-Bku4HtTsJ^?;`w$c- zdXVQwChhs*Ir7Kv-w55biRMZ)+s!{TS=Gge?7m0eBM2Wk6EkJ9V1=rFWfH7 zUkHDZYjN4+T1S44=ZMR_{5jt-;t4z9zEN90$l8OX&%GM^f0(XIxmo)Vd>`?-c7k2B zb#JYfzt9ieXz~`xC-xUM|0Qw>-BHrT_0lyZ_Acd+=R0>BpZWR;r#nQthvwwBC+dHN z->ntncTZ#|9)EAVU|`XCAOFtZUN|5-a<5?i8|p?Mk7L|Vr^hi)f3{)tmqz=Io&Wip z79{+y(=Xg(^zpt2?=Mo@9wL35oiY0EsGM#uW>>D)u34jt{d$+iL9VY|e10b4(KZh@q>JV9b`Y;83%`@3+b}0zi;KOS3*T$` zo{i|bZ%XRxQ9c*@k-xYd#QV}EzwQIZ=UnAHOuBRNyPtFm7kIwjPUH0k$@ld8EZ;*$ z2Kk)M=4HITW^Ok+??>Wt#QU3s-;t+CcZPK5s)w%kTfVU$cYBN12PNN~q#KLM;dF8Q ztn!gAwtuIK_n8XaW28G*d9S$Rsp(}G>5fG5xt`4?9L}Ir}I5cx>)aC&a~d0@4*in-xJI)t|tUjd>={j-^Fj-?w>4okQ((Q`+v1nX({%<4# zAg3StJ8sBWWrN4R@ z>HYh8w;CDb><*>B%F;`IO9!#8_-V^;ag?9?t@M1Q)1Ul|(La@VO87r?)aW-v{N3Kp zvyPT>iu^)<+3y?uW5gl<%^ttV^GpB0o@e`GPrvXUd)^nPkM_4p`hj_#i`~of+xYyR zD81{$rnQ_d_lK4bRIYzn~CVXUN`>6!VjF^ z`~C~>xS;QY=N(*tNu6(<{>C@|>VA9w@=~Vn{-UK{$n>qLdb8a<@PQ36kNVpzh%wJHEVCF z=3Dr%{Hj808lP2XF$z=pCcfHtQ%Sz;8Eo0Mqq}$Y>TdlwT=$xu)mQc4f88sp^2xea z=bP0%8&>3TTPe5OmC}k*tys?2z zd|VEqlyF-u;nQ|2@|DVpLcP{%=WFd2&}Mxa%xaV1)tLe%n3>k#jS#Gpf74$2GVAcpK_1a{&{-gF? zYH!WYSbkwBpBlZXUPGb7Vt%$#o}6k2jlE5%Uj+;c)6K9@uS{1_S~Q0>;c96T5IPJ{ zkNH`n!jsK|L;Yc+GTjQoM!h8^3B?R2OJTL%3ZX3g-V=na@#zWWB=q_n*fc!myDqu9IYHA-E+^%uw;FN2UL#4@lVYYt{BoE++ z;p581uu^V8tzm6%9(Do0m2WgcG-764edORLMpeTFF%Wj za4zjx`8+I`vq>#4O8$rOt;rYN`+E+kGQtPK}x|CBt&}^b!hh}AFq~g z@NaB1hC~$+L-b@5D4N)2pkMGGDuG!A|DXg+Bwy$U|M6x$Uo4;}Mj!F!lqA8VXv~g) z=}9GnJ%`ilL($3V_0f|-KPCpk@7Z1}$!E1UPuB`Tb4I;U73x4+7FD3CN4NLBHXP~O z8r42zMzMn0bQP^Kl*SKQo@IbEsPr0&uV#P@lzC+`7@4k#QH|mQwQcRH)~*2)By5)8 zvO~+W34y}49z-944{8RD1yA?lYq)SCQt%LF3RddYGpF7Jy&JcMgMH!H^~3$)=vZIS zo*`e+&rp3*H5^qA92boZryiIN@uLSWq!zk0w=|!@e8X!jq0tQi97&-Bn}OKyEgAq6 zs?be)Hf)IWtyUSG5)D1(FzGcL)GFe_onmvjfBW%; zq3Kt0Q$>&Gr;9-jH}KK*Og>s^U~9 z>5F4d-UO}s_T(!_QGi(|e6C~}TJ!7c?Hxv)w@`;-1Ji4z^M@xCM~F6Ib(LuiFl0D- zgpUo;M9UZrZ|r?-|Cn1>KjKrUa{_K!-08ITO_D%j6K(f>TShi+HNB%})mYOchDlE3 ztL4gUfX_%bBF{UwX2LlZ7c{&dfOVjW*P9`t=&0+U2I9sb1vVdsVyB)C!P~pXjMPW`6Si9j*1oQlYIO?`nMSTEbp-_To%dN!;%)P1>l$|9Wm;I8ltuAzzyf zMoIR zv0gP8Q*YN>ktfIzUbzHo$+OzTfy4Qr24deWo&>mfY!n~Dv{Y(oOXz>q&qOBWc}ew4 z_usJY)%-uqd9ES!!4H+&+RsEiUFEubvnIXrl!VPt3i_S-Dl(B?O>=Z?q#w2!sV>xU zReY=JwZ0_LS&09h(Ed%TF<}-MYKVMzh=%SmME=FQM(O+D@Dce&-3a^m5TR4PTwx&! zGL}>K+cdU`wjG5e+iSg3h}5Nn)7Zy#D(%(lSv-aWUz=uOCN#MInKHZO-l6UNJNtXZ z;Ixy^rn;`)lnR!i2O=@>FHRR^Ams50eN;O@z)@>k%a*c>35b5eEJGY?G~rB3Gwno= zuo;3@q$K5Ls}09kW#F*!x+rkaJ{|^!-eI~mE+cW!YXsVY`^K0LO+oyX1o7fULks<7 zn5V?~TCrJ&y49t66@@~bAjkLzyrSmfo|nxAcC8_(2{+pRIy%I-Et&vRC1kH40~>3F z64B<{=+r&l(b$u6ADuONPGn)Vl*B%u>NKf^&Q`%Ly5xLK?&U=kD!et(ID9MY}>wV(-1;H z^ydvVQ%1CjP^*9E7%CFtuU@kun&(R7<4Q+WWts(&q34^F4iuUd2gvs0)uwG_ZgU)T zPl7&C2LiO&NXelXSpzdd2{EL&8tp{Av<6jC$Ad7lzPnUol<5Jj8Ep$)xP>}n<-+dP z5UUUe*jQaY{mw)TR2sW?Pv}sbIdvi<2{D1!)XIpWtBq1|a}!fZo3sNLjllFP6J{X@ zN+wZwTD^;FaZk(^UPcUExhb#s{IM|&!Y!|A19@DB;asGI?ZtX^81diE>z#Ert1zf$ zghXB%E2^t$1zTqDyj}A2UhF7~!Rj;y^8OgHt@jUuEoBUm`fX?!<{M4zm!xg9Of&E@ znX=ExK+4cRT`4tRA7w%bE38!Um?d+~s`F}NbF+$khwF_jchPLrLUbxd1<^oClxmfv zI+PfDqFkyJgQm%U6mv)- zr|#tz;nf#pR3`W)F{@5;MuMTDHWmubE325uTB$nBN=7N88b}lfuC-R$YfASf2ai=M zMj4FP^Ub36^*HEc6mvl%C5(8Az34L$%%il;w)^bSQhQr|PkB;ZHlDOGbEus>y76`s z6A@xII$;Kvi^Lf16fot9s1)X3L={9vWBp@+Jq_H}<{jI5#|F1=3*k}n4V_-xB!X$( zqZ34c;AW|5J!yDjt&EOkQcSEF?2*VDli6~lAo3rRh#o#{vWeIWqYdc^0B;9bq7qCN zG)7GH8G$XEo{F801;F|gn@B(LP@c$diLmb z(%QF)UbMW}UX)gZ;`ql@~qgR=?4`JUSE184dNE@Y^ z%vvIr!gL-w=D?F+J~PEij#tva5$zpQ&eXn}r5}(OY$>(3%nYF1nBdUK8!467fz$}f z98QcU3ZuD9jPDNjx^5H^Ot2Qp z76wlmLoh*@hiGWFh1$e8PnKfP6qAX@tF5Fa^%15>(sFAhrz)Q%7BR;$YZGE{hgBr; zoLlpa>ttnXqs$nI?~p!6)hj+`Q>4^nLr7SyluAa5+EAmSbu>zm)lF%yo4c?3s1r{X z6w0ZTS`7q966uBIHzU%nO7vnHOs3PJmf%u@+Qy<<6sc`S&AN&99$BJ|YZTFBgLa^E zyutw(N(Itj+oL9??-Ren-E~9EKW=g0sCVY)E;PFA?$Y4cA$Zq)adWC2!OhFCR<)1teOiV^)=v!tV(+f9k6oq7cE zj*^r0H#TsGhTKtfuoRN^$co8o?Gh5*0sV|~u*X_B)3{7=ii$BGrvO&IF(-({EA5yR zQjeRq8KD4D(2yOSGOXMtpR`2YpfW~2SDPK3rOb)L1F)+{|5|Dez;J>*W)y5AfEthV zLg~%`aqkfN?NMw=5aoLAhy=2opw=V`Egf(*e86@X^qriqLNgowT!74NIRJc}Gf^@}-IB#)Y5947Ey3)MQZ$&=%HaQ{Cen zCm;!;4$7+4%-@^DO#xhWO5>EsY$lzw9O4gZBme3KRGyr$8q@6njb-K0OTQ3mQq@|kE=btvu+<9;bnBhr;?S&TG+M8Q&Z~}fSDAy9AC{f=-m-*dE<@%VM0}TRbhb4njzg!|>KKok z0~C^(Abmd@jA8jpXIErEZma&Qdj@XO@-&lrgRqE(1IZ+zv!~y8ZEQBNbw;Og&}9jG zbywmuR2vrj>uYZNz4((d)PMcCwT;qALw!Of{3Hnn}2}YB*VKOV8a~Et+C= z-Y1kLlqgt3xK)t7FilKpa@?bLCEY_;DbK_pjGm;jyLE z9>S=7)F#k;3>0Z9HW`&1)SL3{!P*3Nz{t681{fu#0vX$xyk!8OVv^-qmm5QXIL&4gbM0!Hb-q1MQ~*_;?rq}prD(etxj(> zuWNW+%j-I;CCoqcqJNZKIodR|pBE)>wiym88C8a9=t!y%4hEj;sc2WmYjNySI+r7lk$fG&Za==p=^s_IjsgLf)ti7TF^;(KjkyYLu#pls_vq zM)S}q8&;U=2$OkHQN^hsYzgblGA3ydYe^B}9I>{yTc&+0=x;HUi{>K1oq9=fR|7DO zXzfdGTG89#pCG@g4N2p+3CDs-Pq&yvlNaNWui z@u62D^v~5BTh>5@=qzGXK1_Z=OpL=A3CKo43F8qi49i3+c8`@dH%le6T$$8X%S%jZ z54IGEmL;~#WUbs2ZJYK*gjPDoC*AM&RAwJl0=Ozsd8RB_=CQVd5{>JM5lzvh(q6=t zDRivB^4S7Ypp!mW*VXXpHKW_N83Gdtuve@dOoTVK5CBNV^26MnCc-XDiKqmXDQW#- zi*`@DxXu$Le%idEFa^vc8n>=heBoGKw1P#8RDWyp{1U-r9)LL0H7Ass;Gs4kt09A} z2nFS4Oy4HcyQ#$TWD?jS7zB|CGU;^CwKt;`Q`_(tSBRRpMWsgaOGedZH z>=1MgqgZ8V76ywPnZR44w?PjgnKzmkuF8#USMmhT9Sd5vR3AO*m9W3GMK;n6>T*)_ zWKJ5k4d*EhBBMipWK5$%%0!)>XwC=aUvH9fTytpewwuB;*Up0p8| zCCwnVJ{CJ^9^3>P)mzLIwk4YtywBeeZE+m*9ga+kNkWz<(x*|g_Y$-R}mzR}JhpbY|Yy!HQW*o05_>O{X0x5`8 zdD+zz##_OY9wL&KihfEZ5<$4F^FPOkA}L@^a}*QXZ(NvY%jz6z7!k`58&SkwtJjl= zMULo8IkL*W2~7+8+;kGBh_MrWl(x|+1fF-QS2z50Ea}dnz%KkhI=ydHnCa_t+Ua~6b7`OmaC}C1MCYLvxqE}_G z6U9aK486^@V#fYRtMh3!!#TO3{n>6qnNQ(lv}B{bysZIyMQlSidtDP7h9VXEtGUl&y@&-YCpiVHXYewqpiXACr?8)J#E#C@z#sF;eUx0U%^v z((Pns^Cr6U^BxonCC<;2M7yP6!Hzji#M4bPtq_*CgFJD*7+Lyi~61<%Ij$vSEdrh zwRcch+Jt1?m1`+nqT?b=Vtb=$Uo29dVMzt=AZqAS&Eyz29X_BJa?=oHCpF=kLKr)z zlC%*>!VZPFF5V5{CG;$k)`yCT6iYh4cS$u$Nb=BZCBjZ?&ct(60zrM32lK=*Fo&gc zQ;9hual>i(yIks$oZ1VInJc`aX3pC(^(WwGO;FU1X|QM&H6xt1gAO{OTS#~WscpUm zU|G37q*mC-R7e}X8jZ@JaVvsQL{^xg!a5aY5LJMQ-@53cMw49=lGq%y)4E52_-UIQ zhnLEWB5hD%Qdp~TdD&z`kj5`nIb#>XtWU*ATAk->{xtHI>V}_Qe2013>6uk5tW3^H z_lIUEYWMh_rQyT0WAh}cGtq2vkN^XKAJ>0VdWkscu+n-H9gL-OLU$~~{xle6r0*Cr zR7;a28N}N~ zeWc5zvOldl8I9h)a4&$mh(Q@3GEa}F5h3bqSDMIl>NM$Rw89uPV&Sa?DC0+BydoKx z)5X3rS(wmGc>w2;i^CyhRgE+8^0*n{jl-y{S_dt=)kWQgS3pcdsZ}@`S;bGXoD+|v zOrBu|#;DJqjO&OmW~ixjHqa@wFbM)ixCsOqX(?ie^(4$RxeP3@@FVx;7oGVac8%$5 z3!jdZ)EklB9G~tuz_LUf`8&H>VWc$S$!!_|p$=L34sxx|KqlDTk$ZATgY~2G#H_rS ztJ{5B;{0SAOOz)pAbQbxuJ}x@%w^xb<(1%%4$|e5)OhtnUa-URej3OAX2c>)7rVu$ z)tt=5k*C`US`-oXPYGE?^V@XALUg5Le?FDHSDsFak^G&m&n)HKTr7})Jlx4IVNHgm zReM4*wJxy$p^U0S$#&H2Lk(y(#*oRpz=;ar^f7jEYBkGTukQGVy*Ra-C0-0*ZhU2+ zt&3y2j(}wZNh+eyHzXuYYeO_Tr!Z*}-HXQMSLHj0nT$L2HC{eJzv31?Aul;;Diq(o zAK_KgkA8j*D=(gzTU10V++1?Z49VLgC@eX_Z=~PDNaWDD<~>I(rpPoQFM{gcBBpiK zOC8HNh6L0I$<`W3IGZ##YmV5+HjILw8$G!6A#C#9EcVaIvrk@;W#jZV@mzuSj zU_tauLw{L}my-|tP zN_>|A-wwi4tsoIEe!OXRSl$_I>ocrKgSS#WX?^`4tk_6SeNB97p^4dD8D+;=2Z%fq zck&aKXi^X3I}R!s*6pp(`Y!~0Qo$0_y>Z5?;!I#O(4rO)I|7oQ)UYrM!zpY9$!cgD znj`0?V^(2scD+@A4rmydv>Povbi#8fLHXCERM-fZ))PR!MmOS(Z7*uERTx_m+_UOm|#aM^<3Om7~<1m1;jDdRsD=gQpupBBK9lD=fY&M zS4vos05&d}e(*wGvm8u3!o)Uhz67h?LQj&iA)`+4;*lJ@;tgS!JYXGxRK}$?mr4f6vShTN<7Eo>~8iqGk z@qs9;n`1+byw;3e#N>@x<|tH`dxK>pEQ+G8ycZXdrfsM-P^j7MC$ zw4gResm|(JeSam&6noVs@vdqCnaTbUjpX#92qeX?SYBM%Tayw?z9xWABOtDk?JL@S z4kOsA7tw#=zT7e_)rr^edgEjhi_j^)__&Ich`C_z67Iqjwl;OQF2%ksTh4+)zwWNw zDxb~LNf3ND2cK@hE0VM+bLep#bl`PvTPv;n3iw z@Y?>7QF)_OK3^2TN(xhDyd-SgW$g)zlFW-D^-VV_<$|_hFRn^FDzC&FeO-$m)MUb? zP;blgElZaDPdeuD2>&V`eHlR-9Jfo zR-T}>yDZ;)!zV3!>reCuZvFlJ zrqkB+xV#7F6-r6R>a4d3`9_6&QDZBe7ly>tn9AC`=I>qNh^1j5Xy2JFU`TQO$Mb_SE)98$pX=RkdT@SQsHfZ*JDBrf4G* zKVO(iKau{z*;tA6Lrk7PA`(wP=}Z$aT`Bioyv-$FV8d4uQUY(2O-rT}QW{6-RGa;< zSf718p%8Nvx!?fe;(Bwai{64RU4FQUp9k?>u?D4QsgqQ>P(IpkxHE`ly%2_PxU z_)r2xvqi!rC4Qsl<(HR)IxdIwRmms#E>nWe5~44WDFCD@Phb)pearL){A^;6EIyfM zzo1@eHbG4mBC&vt51))|ye@pr_Q7rPLDDgJZKRXWxZ%@ul1#b5YUT5D5I&Jlfev$-$ajBj=IkDAi(F-rNE60*Su z6-0c^5bwlj!Gw*93Y8^!#tK$){p6q~z?T70l(-^8Odg1u5IABQmNE}*-#)wv9~jeR zIOK%+{Di!;De#cjY%F=1or@TV4D&Sy)k7j-WDT05goey~YOl(sQrWl2WFboWa~X|9 zVp%0AYo&K_`$tAtfhHymHC1D3L?Na`T0K8&YZ#SAfT6fF2$TQ=t|q>BV?X3uVBo#l zv{7wO2fF&tVl|tyAznq1S2;w_c!3GKcw3kn#lC&a&-k59kO&qO#%8Lzj8HOz<-5#m*j46<)cVkhZbPEcyX|+tS(;oe7V3aJDj|q~JJXPm=&YDRU0@cE-l8SSI zp0YLcmByzh@uiJbJKE(+^rAnQ?(LXhuvXA9bBy$rN)7pzw=&gN<4Y2Y>4a!ZHC!s~-d-tUJ7Exkqv$p(^}YC7 zk*1CCCYI0eA<4;W@q$q?BROKotq3LM8+b9jFh>D}dDT%JWB84H{h?)__KTr0ykP

~?SONbeZF zBUjouj!s)Yb2VLEEkXZaO)u~kK_6Vy5ZZd?`8pw!=fWg`>&3SZwa9;3GNBsO?;d!0t7Y55a z;ui$DXLO>!Fvz{I6aI|g${P6aBLTx1S*KcRo%pI!b*e z;Nbk=q9CB%rSazkZg*+?;$TCEdN@CT5&p=|cS+MfH(2zeO-V?9pC3Fg=<0}H5-jbA zUmA3G#GfB@{aYvgF9>EH?}RT2mj9#^zBK6mX(#-Jb7U9b{NU&2!Cy2Fe%Uer~%ke6F2e0Y3BR`|QB|ljrMv+)p|FzIpiE z34B2?*Ur6MyE1zFILnpAUC#$I^v>r{2LB}aWO3(nIzw;xlAtHkUY!4#4E-OIe-^)A z%Nw^ZH5(|&_|NqNf3Ng&@n_+DSgGHxU&^_P_3H8ubj0WSpBI47f?zIgd}290lPf{r z$sUaU;vkpthpwODj6By+{;BOI|4C-huktJnUPk|e;_KfI;>$9)<$Fc*5j zhA#;=%wx~%hI1+UyO6KgTVvF4KPUEOFE_kBX7~W;ir_X1xKEDg?_ z*Q@v%{TJsHlK$*YqrZmuH;7+xz2T>b|0DT4?|kFq?dXDq#{ZHGZsol^IK=dRc?sy} zx96q7Qu1+n*XNU@5|MF|ZPZMVtPXBg!a2oZN z{5uHxPWu0h@>v>mEwuXe_T+Lto4E7(66w2%_wd2ji4SM+zazenxZ97{=GCIhS4N`>KXlNN@6A9Gs&)j=2LEs5b9NrRO}(u%pGF4%7Wo9f1UUt;_h}oNc`>${ilc@&d~ok z@lOzEa}OQ_F6Fw6@>?l9u3H)$B)!Y&`aIN8LL-|{TXn{?8Hm-pmdCJ)77|8j9~=zD4X82=@~$&5UGl*e)RdtR+QZ1Ia1mslJk+YoIhl~ONqaNsXX6BnW>2jFhBTY`JVl1 zr+hCDPI<>p{+FJE&%#rk`Rwc_17230gU@5%?8IkDa5~doyu8O=mge6(4}YUy5}fJC zXGw52gL}OkI^9X0%YzvYRGIybdGd8W%YM?CPxmjT<)1tUpP}>8_TYLr^vX1!Tjt^8 zddU69rc?r#bMfNN{CBNPkq7TT2mgT#f6sR~gMSQsr2QVa)bhQL*%&?IgpB>WoHtyO zmh%|+Nc%nW&xU(9_GRLa5qEd_0P(JWG5SlH?>`e?P8`!>`saF{@j#wnOi-dkOf6eg@7Oz5BP-#CK)zUg9&vU7s%J z{`Jn;t~<^l=kRc6IS-J(b924z%IGZ*{$eLn*BYN?Owc5L8}ZY`UCy&tIcK}Rbsjm5 z{^DTgzozAMJ+I5BahG#{M$UJGzv#L9heq$?QGnMa=AQ$9ywSckVWP zfcU=3m+J}AZ>Ssntqbgl(PN&iVYt&feqtW{)I9j3gww0e)<-}PjVjRR^na1YWPEl z`{nO_#2>xQaCf60A-?S0hR+yzG(R)^Y683*1^tu7GbaujA5UfWfH=0_5xf4;Jbc^^ z4`%Gp>v7<>I`i+@oaX=4dH6e@hdn!K4*QWWuavuK9=kOOg^XVE&^O*0{`G17ydU)9KTi{1 zBx2yt=^Z!J@ww~lp9Y`jfzPfF82`ge@MplEi+P&^&$Rho=l>1TANu8-Qo0}e2jYzk z{;%XS#d+-IF3@7j_pz4oSx5Zk#7{R3-#~nm;=D;*c96cC>s&r>P$E9`b>rjw-vM08 z6)d)Lx%_vKe&BVchl9-H6Qtjj(Ze5+{^;9`zx(a45+DAU;oX7#JxF~2Uc*ljKdb!X zaT(l^{;kKrHZujI_W5cG0Ve)?y z@jH$g?)mN^eu)0|3evxuxc3(g=KI^kmtLFZ|8e3cUt)Nh^nXg+{n%pS-zNURU*|N( z9_D*L1d#F`W&OIneV_EF7a9LP(qH%-v%_^GhTlQ_MZ_QZ^_(IeZ?7ia^?sutApIuA zd6T&8ApQLdjNa|!1DDbcpJR5IW12GQef{VL;_r0)PmFRO@s9zQ@;-c_@o{0gK?6Y(bp8RxkCD~KQX z8{>b?0!uImybJPY_qSX}`b8IQR6?J>DiiNnXZRz`_wB@sjQ700-b?(kzp{LHlKzhs z=S|}Bm!!XR+UQ*m|4O`ZvE@6)G|%a>@*ZlZ>DLh7b)(^zlD-eP)K||l(tdRZ>3y8& z@?TGU`P+@pKJuv&f8^VS-%Wf!@u{yEUL<}u@q11h-beftaFORU+spaHA0+*wGe+M- z{0GE+p5#8_V4{4cGJf&}z&rV+Ur_v_;MNeKDNO?-gs+6T#Jzw+lz;_{pG;Gdoc|B~Vt1rMBOa=Jdh4P5k@3#@)U-ye|v z=sR+n>rv+Y3@E3QeqN~fMZx}?jeY~^dx)Q6KkNCvn)u1@8hzgaOK=@_BhUM5NZ z*h@|R9@77c(lfKf<#y6v`kThz;-?_^UE+5P5v_3x$9-qW=lR5!J;UhT9v;SokNBBk`dg9*uO$7Y zJx1?(TkrVYCdmvF3=%)_al<8UkiRz(zxh~B?}r!YC1?VIByb{ko5O`DW~Y8)aTxL=-&-o z+a2q75qbSC`J7~Y@-Xqw6Tj?AEAKJ#|BCWi68Jo=^Z6g7zjey!ajSoi62Inu=JdXc zd@g~#i9Gukm>=jd@?aTo(dX$qjn8q?|5xI{-x{AH@nPZ*9X0w5#3vOe)5PU1q~E~! zb19!4Al`Vf@wtKX7$NNUdBNO$hIf+w;D?R=1o<2#Ui_<^B0GtHlemuuPZECs_;X?B zKA*Xq_&);g)E<9GK3$Bvj*m&WZ zv#ng-f4zbD!H?vW?g}FhTEvgB-p7c)lX%ZZjeZ^RyAUMgBwd!wdQBzIo`s zN&Z8xF*#=zSb|50AAgbIUf#!v`@XpS~|L zi-P+y`spX`>sA}c@eRaJK9Ezy^)svZoNR;J=E3hGpM9&XyvvyM-g)T%g7nwiX!&-L z{z2kHFE>6n6My-Yo%QfT^6$FZ_>erf5DFK49?j@;DR8mFonJNjgG{iR_%X^4ccFjV ziJ$y@PVWb(=%V6All=FWNuRqZt%qMHUi^;nIl@FAA-;?K<_6;T5I=mt__&>ajrc>f zXK$zfKz!;}_xJTMRa-N2>1jg0+&mVAmoH9q^v=W9y8 zB=B`2x2x}vzN>EZZihc1e$DR~-Y{{3i(ka{HDkEf%PWZc`qW9%uO)su<0m&cAKH)C zOP+Z5Yi{|o7JjL(meegOmA54M!}PU252-KfYR;$`Ap&oTTI@mm$= zP2%!F(jVve#pBH1AztBp$Q09jmiX9*jDHXD|4#hTcNsoJ{M*FunawG(f%x|o=S||W z@WrOLp&N6GUdm@BoyWjDC&#~C#4jQJ@cl-A4e?&!V*h6u*X<;J1L=<*Hu?tfI`K36 z4fk@rmH6U;ba{Voy~sKD?_;FDA`{PlnfS@~7$4We_nf|M`L@YY_Q#0*bkqO4KYTgy zvmY^fZ;$_#c;!Ole~f%+bRUBoAdpW!^}81Y{w?)&0~iNAyRos&65Jl{Ks_kGs# zT}t}T5I@QJja|gQ?ED#*dVT#saS|mi=V5=3=wa;3IYn>dvlkJ+m3HOzwSu_sTX4N? zB);po@mapW80CrIbC=;Rf1CK-nRwuK=THCNZES)M6W^IPK6jsQ4?gL9zGnC?gM&XM zUdhzsw}>DAu+gt0{r8C9$^PB#=Rb(wNBcZL`WJVb-X49g)r;5HRm7ioV@@d#>c2s7 z9r0T;?Yc~S=&oEKf8F|T5Zr_xQZLIHr+K`$pZJN#a!Tp;^9{rs(jHG_;?;wszxRzM z=T6qkCy94oVz}GMapIMUTp)jrpXxSw+9NrE126C2b{qakkmmCQ@w+)MK zg0}+iB&+_eFU>Q`&=TOFfewy^{LmQQFhVp!oc=wl$kK5scijydDd6e|0 z_Za6}fmlA(3Dz1~g zeVO!^-fZ-Jr2iY>V&~7|z96bU_;=FZ!1n9;Uc3zS=goaj@G{`yXRe`t8z%p&6z5Ii zGEDmYneo>o@uA-{{Xcr1C3*|-qd&?iaFV>XG+@t**f`9^Lao!{@pC$bhe`x&O{{Nh~zyIa!_wR{6 zG?7y-L*(@X;+GvV{0idd{k)ZHCNti-1i08wgX0&NvHq=e{I;ClKYD@TImPXF^555y z{`7y#DeU{5CWznhFNU9{LiZEDZ;6%nxTXq%-z0wTzZ(4v_4&KRhlY&a`=iehzl`?a z_zB|OnfdAmh%dj@_OuGnMrM=0lN;zu&}u!;Bs9GCgH`1Oi2 zapF=X{S((4|HIVJJBXkBbHm4&<_PhwcNl(%_?L+LzA3l!uPIKV#N|P!|Mi@rZl6CS zewgyR9xhpKdbsTOO+Sy3*DDlHFy_w zOFR9$i2Ht<8S?op;tLtqohAN<#CN{m_`5z&5Wo44a!Tp_+TRl|UT5^~5B~+Y%me$r z>qX?h_`jHbmfd80ydAxS_`MwOZy^0@$N$ObySxf%q}% z)8mTAfs5Y!eXD1Y&qcpzdRz2$lgIi0JaExN596_2q`!*v_k7ai^!D`{;*Vs;(QhQ5 zhiQkW$frvBb&Th`iQi1z-{WxkKSVyqGxmI#^oQw(-F`kxeAhd3%J~5Kf0_6LTTT9Z zSYJ0hyYo82gQTDOHRE%be11&)7}sCAi7$Gk>GRZwjNbkK=C!oXlHn&w|3cE=S~mPL z;wu!#&8rM29Q+dLA7eXm|4@0U@ef{|rXMDKk@nU_Mh)U!4;lSs^z-i~{s`%BCjG~W z-%r2o_WZ}hZ)5!9?dxxVYdd0mb)0;@NBSqoXNvd}#0S`K7KwL3fzm&AbN=lR@s}yi zo5W>3=^wozr)Y!Ewg4A-_FrJ_dW`k{`g!=wkk5g~jZZiEyodPBjK^I69|PWL9qLo0 z@5-CKEhC>V5`ThrvXuBq;3{Xv&L40-59XBeIO%^xd?(}E9^&V%FugteIm`D5@t-4p z!(ZkU*-3m0@soEM?s~h9_#K=-v8O>$Ccf^BA+Cpa5Z}Q1b$Nc9_^pf|d>sAz#2;a~ z1_Jy0OXA%%<9~?wKM_Cq87tRP*5gl!pMIa=PXEG{qR%D4DZZCP^5Er)W4xcy^J?H? zZ@00(aQU|o?`oMm?q~AE7wtCuUds7q;GOm(y#=_`@BNv1hIf}Hhk?&bX+@x^>E#_@kwoQV^ci&l$%=Kggnj&by-P0y}} z6~uROpZ|U)-2`0Z_wQP;x`J)<@XwRaG1lW@@|h+6$U@8ae&X*YKEUyBAMv|@OTMS5 zw+o4XO6hr%xO{CM{JZnu!5ZNozo+STav5;(OHaHhr`+#mfmaYe^Bj}^2Ijq)_}KFe zZxg@P@j=5MBR)xdKgYjLe>3sBznN3YD@gxa#B-z{ApR-heVKW)uPIKV#O3cuU;JoJ z(S3aOuf%7bFx=bSg^Z&v z#eTL(c_t9gKaVuY%Qr}WV7t|?xA%V_zUYI7A75apeoXv^&*l_xdt0#1>}`zg`Z8wn zT;fM>G(N89mjc&zLHQSwex=g$CUNN_p9=TaRVYuM_zkCWO6_{yNBq(+8t&tQ_Y=SK zF2k2xdDFAoe~b8H#%j32(9_@$xAznlWqi0`_?aM#=06=z`*mk$7!avf*C?B)I4dFVe+{>z(I zuA}7jP2%@6P97lskHn8(ke25s#IN8ueVFu1t}?y(`|=+D{5)`x^EBl=L;4=lUvXDX zk#7AL?=w1|EtYSEc!~H<&c`k%zK?jWM0)y}1B#OyB&^Y@5vIGj@sZqGkaoJ3(cE@qHP4yPEiI^#5qK`nQ$%(Z_Ro zf6U-u7jWr+{rhQ4iQfoZ?77YL5${K8#Mk}E_;|g)UHD+VAiFR3y@EqOM>6f@F!@yO zGCoV0?;jKQ?<^f4{w>9Mlem1J^rya=Q`GBs@zs`ZZjr^GF6YaDOS!IKdvX0-N&L3=9Kzjrn!aqSQncj{*%k*}T|6bxZ&`)~3e_e4hO8H1g-`p=QirGH@fS>j&$!>?ZV#46?#~R9*4AQZ@sy@)xc4E ztMo}Vzq_=eiNjKH0M;rc!{HbCW?^bozFJ(rZdD~eUaA=B%!c*h`gO)@6^ifN{6yKD8mwFKGRgp+cp!pg~V`xY?EH|w{oS-EEIEjXVKz(E`ks;;7~|Mg!8V+aJYH{)Y#rXTbrk15qkJ*cD|~Ta zo5Ca0H8~|oPYDH;9IqkA1?hpV(H+hc(nDk0Z5)n>Gju{d`?qN)y6I^hQ}uSEGCdi} zAzngKHIi|VOor1n96nPM4Q<$P)f@(LG>kmi5XgD0a#D()6%BcmRROrx(B>W6ddK9z z%y8xUtFK-M&83kIY2>ON43ttdSM{vPq`Io-s-8F(95LDmr}DL8rGyN(;_&e%PFlA! zVoNm~ZG*#uLLQkWC*CLSaT;|o0P%G=E2xBPAX4L;8^4zmb1IchV4!Cup~_(NIG#!l zPLdxuCu)wYYcj~{o}M{KwmhqQHUzCu&v&vTqYG6#**&d@HLJ7C*Q~xe!+ed}b3(;e ztyz~<=$iFcW>a0YK8tL~=CyWhR_wLwvX!@X{pt*#wO6eR^ejg^92PZ%1A%Y|^>``Y z_G8oRT%S@6=P*fgfD5ZO^lULXD0vcQvu;f=Q9)w~i{;jCxnIYVY_%35s} zQwigIkmAY>f#a2WtEKh}^y*-25Qp)NZQME>j$Xg5H`p?>u~8m_2oMy9(&L2f8V+_d z*%g?|<19iR7%V{iNRL0&1AK9!l!`BnWPQ(7Yf!hAtsck;m2wm`@))X5 z;)pLCZI9o*Xr;aNrojHwj-lLIuGO13-DBMZ|H8 z&ejUT(rEfcN0N)QT)?AtWIg;|BDFZX!4$s?B2776hz(hjzfzo6n&#@&8DzcqB4M34 z*B&wnV&~}LCe5N}b*8ajiOx1lvu3rjP1FPYa=j3+fdRR4& zJ1zO4qjOFnO&vt5M;zM;q#%q>3C6);b}DM>eAv{nvgzY^jSf5@SnAYcJ>ts}@~Ivo zZ1i@Jq&?+tJyqDw<1?DN9foW~e1Ke_4||X~dKf4D;asu!6j!O8=x9@|s>I2Tan&X5 zUC_+&d)X87q?zzQIyvkNr;g(UIaEmMkg!tnY%e|LGwk2ihtMPpB~J0*iKDXg;H$pt zw{6@y*bAz}6FWsL+%mL%)5f82`{vD~{bS+S#!W*wJGr!B-P(1lug>-KtS*H;^0)fR zwc+XlrsR`{%Z?_F*sV&pI9A5Nlp?X6{09eIz|m-vQiEc1;{Xr~1d|Llv@He&#Pm1{ z&ir181GsUDv>d017*GzyoUY)YU?ssZYvLNiLBty9Ht~4G9^<&rLSr_U+k)e>d&4y= zwM9rQ86SP-UZ@YAw^^Uf`W1D1Rq4FZA)syJU`(9gE3W4Ht$ky4D`+5R%okN?4@Pjp zWE&@q=Ep1O7T{pu-a{o20W0IuuWu=}x6BOWn?)S;*22N)8UkoYfj+pUddb%&rz_Aw zH9r&XDOJLWaXIcA=PRd*G#T4gk37fWl&R;j%mZ6TBbhTt+C?YIWlfR?aZ0Er-a!uB zl|$9+cw-CvBniCYh=!Ipr4PR~_Dmmom^eC+F4tHif%{;0zlbj*HO10zZAHS1cHJ;0 zF+pHKBWxLn*Lu7)C}^Crqq!hR;wWZPLID4r{{T8A9X^5D7l=A z8J{``lQrYpUaVL9rz@rA&g;DtIBlw|~KaV5u&~^=%5O-`+9ML}OPx$PR;|5FM zGKm)EISq>wjFgaVBBpOqi%Y1D#s(TG-6v~}&AC#qH^TCpaUNk6MNWtYS&T6{VC9!g zjCN5ewHl35F`Zt$7(#2bWSmtk&915uL8-V|#!NVU6H$WodvT1$Gm1f-h!jRRpaT>Y zJaXJ4IEAv*676+(#)La?ymGTL3lBF~gXU|6l6naozAH6_inHE#90P<9=hp9qA4nEo zcw@vk*DwQ&k&7v<4z{$6D4ZP@>J2-49OV?uDMZ{DntP$$!e?%oZAK<5zC^|z@v*i& z!9=@Msid-OX%{(>!s-n)rEBbpYE}0X7dsHLdsxhpZ46Ab3`$S{9T}Wl6 zVG4b|%myi4CF)74d+L!#abq1RigD_Asvfn}S?!T%{b){O^>)4z*?y~y8cdf*!t<;f zZ(*cu11OBq)Q@9aTa|%E0iN3q8jj4wJYL3yu<3do47N};waN4e_SfM^+3k%sPAWA! zb>hS^$?&@UaAvQml~v!Hn^l;E4D^Er{z0CI^#^Mc^|3neiHu0%29R;JXmp_147VDD zCAfop`m9vz=;64;UyRjth?VNCY#?bZ+Pl}d?XZ0$Pck-+)}sVt`4&#xwI;LHi|dwy zQPD(s5@NP648ysnZ0nl6+PBvMCn`iCg$cNhx(b!DA{R|+Ljo-1At&+%?E>s8-)^U? zUb#!}CkjE&kUh#-xcC{-v?$e&hS28AQ9)5TV2lz3w1UlGSLv5-Y6z~-%j;%~j$!-6 zb&0tE21sJKGJHv%pDqrPXQ1q?< zfF5{VZB0fN<=IAs)j-+(xShUR9V#K9*(OK2hoSUNa31KJBv1DM(xpqM)h^jcs6J`Y z25Lvzv3Sg6U^I#8D{2Q$+xoGh>l1yfw-|NX(vZ>MJ=|QfEllbA2pd4Ny`wg+ zQ6I7lQDYcE7fXrJeK3K!zE)aqk#~8$I+uwSYAK~y(IT=o=QoUV=!f$-5Zg_rRv0Nw z1f%dN1EoqM(BQd+Zn0EUcKLR_oZ>bKqjK4;OhcH=(*#4>rADJ-F_*{((m=e15H2U< z1r)bYPIof-N&^lT(x!5Esl^efp-XPV2*!g6=?+q~U^<%LQ!@VoWAGxU6m28MR60@U zwWW#_Yo|GEZ@7_9!GYP*BRj{q-9-V3n5-u=Nu|?lqK_@L#gyxfbivFc4a*48O~`cx z$EW_)aks0{QhU%tP;+G>$7V#m7NwbsbR*J*3Tbo-mudxARx`x>u?&=w1<}^V>he~P zxEjGkwEi3Vr_bv@kXSwh^IClG(MfC zj9Z(+FuFonCyJ%u98Yr0@0DN;W?Mr=9EWzj0PXxhuJBCvc?d(j|-hiA8>b-=xr(~US?#|+TfmnlmGO=yZK6-8Bv zh(U~P0!w$I%R)X)M`t2|1;>xl8%#;ms>8U*CL|*pYl@+5njJ)_J)=j`i;6(YUPDx) z>X*8(4qn_$FiYDRqG=sk;Ma|RLF=94ntxLh{o#l zjH*$_^J?AcQJsf}?R;S><5Ss>ZEuaOIQ1%_}hx=`H9}q9)on0<oNi2a zv^Eqmk1GoS+BwFPrYyBL(7m$shIO<_$sZOZGi_V*Gl(@@3rs+3Lg%7Ah(3+`vjGh0 zlOuQS`^qwYFJl$QR)nmWzIdvE2bsF(h`Nb%p59q+m4UE$lR?7k~ocvNg6w6%Oi&Ey<*2HqWN5j)jgZ3c!{+6!uZM)vr&(4GrCessnU6;>$630 zRH=s4AsT^Aw$y+TOqDQ^ogSFzlY&l3d#Moqgp;$)x|)&opnc_L!h)zODTDcNs3hX6 z?vb-)*63ot7L4D7Mw}{;Pau_KaSL+jpff$U*@SaQrHP^<9k!(&h2dlsL6rpup?aYy z>7Pw1=@hYglp2}aES%J;%<*G5sgwAo7C1%BB{L%6Oi7RQovX!|w&nMfC)Hb_la{d= z47F9~a=R)o=^YXi#xDPj^-S<$rlUdV4m6Es6@z@Z@>qe%ISIB;L?hPdF^N!0PrK*G zv%?|yk-0-0bQw`AP-F5YR)V)_V5`HV_8?IoF- zFh8Vo)cJx;nWS=yi`R>tPa2kKBKYHY8rBj9P z(mjkejnjakTh+$=;NqB$L$Ywt_>&s=)Mv zQhEvER12|j4b}?U^U6RXQ?K3o0j z6p~sGl&k}c-Ns?ou09rMOS3-RpxR*MVZBn6%_bNhMn;ewhS+ML%@WYrjzr_Zc>N&L zcDKQJuWKePc~ZJ(c#C+C1h$qTsz}ufxp-uv<&VJ?hOllIkAP$r(oMB!+tj?yB9n)Bw0BHB>vkINP9@IE1hZ%f*j$Q1J+}Km34sV2 zD`wNI&U+?(Sz@j;F|$fpG++h?mq}_K1x~M4$o7gLWkSt%hbG9ijp43P4>RXP#K5N;cXNY(a$YZ6R35Mv&~G z664xYJT@PkU5p>8JP^rlkL#qcDhJH#@MSYJ?QC2ubnKfyh#ir(*k#!Sk zKHfxjkDsKE?)q|~Tj!brUKV2$$yC2M~un@kQ5*Jn5}EOt176;%sI zeN|QanN$ewQE0)+t%hF4{IRV>w0vTiA*l_Mq`Y36q7)h5O5Zb;UMBMG0I=7Mg@O?3 zM$lwq9JQTGbcA!fBBTk#T2M!&rVSjEbA0OpnUr(;F%3sH8TFIN6l)?EJJ=eMwH{1U zC;MJHD->IzY~O;Dsmh3lzK9C$XFDTNUZ1+ zNnTdxZrz&LxJG9gM-IErCK!>~+lW5x_pKSIpz0pypM{#x`GQW40;U^z2{m>fK1NDY z{?w?GistA;lB-Vj#zsWp6BtLO=c27!NN3LwR=Fp-jd)_CP_JUu7oG$4FroWcQw);z z&{v;EH)|aQCDpP>T9GJjoWmFhp~#rU2{4w0l}iU7xl|ij7x5IksZzN~YsqZJ@*#`* z;WBbcCD3hFXdiL3;*PDQyWhM@wRmyxL<{xdb0XkS!nhyq)y3pQ$v7U9;?8H%8w>67 zo>C&sShGBdhMMf0Iz*KH=&U9%tC?{YXc91ETUNwCATnI(V_fkG`O}Ood=jheIQ1Z# z#W>Z50+}Q6QqgT>CXux*qYKgcOnL}J?lwCZg@NwjRih$8YM~ebQK)v{1yW1W&MX+w z_$sahpU9hTRLWQpfNG0#*!dQmB7VEuO^@f>o;@Ui?u&l(6H(n#>{EGh~W>yqcVD#tFI1Q5_e}-DlC+;`FM>-5J^~Ps(XLE z0ZLsm%YNDP(km0&i7q+Xv!uIr${NX~)F1nK3klJ)sd=#D)*WMXdp=IlH3s!QRGqZ~ z-GwH*uX}^JU~kHcr&143V~#W=ui4;Xq$nv2CeMx}wykR4f(3g_fMZTS`j9 zO$6k#nHk??Ah9`L!KMjc>nOFSqfJd}vAWaM=wVY*htV=%DjMh%L9mKkywMWJOkQ>I zoMn32W6wl~{fbgQwnsIT{c+-3EG)(>Hl{TLaPKe$4VR>IRp_d)j+U}aYTiAxw@-m> z-4QJ-S`ls6E7GZ^7*xe|X-kjV&UW9c_6S+pt}} zY%SVZxUs?HWs_MlNREY$B7OF1)OFm~!3Wmyo}Vrj$UK(5QKBw3;dz+YYdGFepAuDa zjY16RNmGW$Q5zNr5-$M6VX00qL~$F(u#xnluEZLP*xi=6w;9)gvbQl&y6-rOH*+Vw zj1OMn!hFAms99H0w__DGUC!y6Y$8jQRK1Z#MN)uq9gDMaV3+hJbmG315z`4Nec-i# z?52@OdFJ7IIZ?+tbIY{K(A*<^p)I;OI9X8Lot;~u4w7?Q+HR0!5*w`1WYF59DjCI` z8mxS{-q7*9?L|l!MLaR9UBNIqQ_-TSh3-j9>`~O-Kw60EPVCPLxkje?<6eQ521(f- z5hlxDmwD;EfRd0UqCX@4|6 z-Yo6$JLxz5_k`@+_Ztbgm;!Cef0AwD(*!@$&le$;eDZ^zjR{UH$SI!_0^(1eC;tdX z5I!psJOlrE`iGeQArf{+l=j2Ff8a1a_m@h)@VuNpT1bY=^e+AUlAaXB;%^@lxcpA%*GbU)M5nq~unW!v{=E^u z9>}DRz7vh_k;vb&TUY^h8_Cbx-~;%P%zxPzH|nEhU$k_dkJD%6m+!_1rR(3%iP*sO zC-7aSWAkD@2 z&(n7?eb-Y=|7S=ml6v~3OuzIT>5)YLzJh<B`fjE_Yifw>%jNcZxgTkg`FH)B zmA~uXEa8+3Cd~2Y>HYfGz>?`_9=G%}k6ZeqUa^{bZu;+L()&3=%YS0&AF~Tn$LSq- z7(YZ77t_D1*8NjU*dvvb_;a}(`X~Gl${q)J_4F$;xQpZ0ALF_IPLd8Y|9x!#{>=66 z_ZJ{>r}U>TG{ybFchgVPcldVCJn7&5J=4h7H+oKX&8C0JJn475(pt(VKKA74UpY_u z;4dxx)KEHoR{tBAKCAz!7n|dHUp}24r? zzc=Re+4_4f9=Po}ja{DdbN~PV literal 0 HcmV?d00001 diff --git a/src/segwayrmp/lib/ctrl_x86_64 b/src/segwayrmp/lib/ctrl_x86_64 new file mode 100755 index 0000000000000000000000000000000000000000..bcc4f167a80496104010d405118872d267748adb GIT binary patch literal 378600 zcmeFa3w%^X(mp&13^&1v3M(o~KxIJ%K}11_4#;swm*}8G@d^luL{M1BAfSEHN-60m zYx56^Q}Yk~1nzv#WFh`)4p!d|9mSKPe;EPG?{6q3*|K)?}f$d=b1F-hsNmSAvd{hSbHZ-C={B0Td zzm|bdMFu|iXTaYN{B!Xy{f~BaKspflYW!z=phW5_PfPYH{c<&7Mb65ua_cO>pAp`ys8Q@=KfS-{;p6fES_oWPc`e%TL zGw^vh1O8hX;Kdo>)fx12aR&TvGr(&yz)#4aA1ecXmkjb8n~6^bcwGiQzl1(>@h|;v zS_XN}$pF6+4B8vN(G2x|p8;Nw0lp>!|HT>Pxi$lzr!&A$%fRQ94DhWPiPW#E5L2L4B7==Zxb;0H3)`&b72E*bFe$^Z{#;4?mhoRc!N_oEE_Z^!_@HAB5s z8Sqa+y}9_8{`X7<{67G(Jv;A;cJ)tZg8ZNie7?=V=Pw!X?*qKOd9x%#dwqy^u3~s| zl5fhHlk%s`D4bV#Me+QS!g-VOPoF*K>cUCWE}vcKn=<8!tL9uiWq!%Dc_mY(DAaZl z=gzstS2TOhoOxtCw`AtL!f7+eeyC4prc9r6^^7USR~MJKkgFmkg$q&h{E~Td7NtQw zh(dbJG=sEop^=edht0gg=?i>C^A}w`9l{sRn|Jk`DYNHHpH@;l=jya70G{Q7gvb2i zE3Te4+Y2ixzN&DB)Lk_F>Jp<6Ei5T?aj%?HoX$UTwbTH8OjnAYj|vM*d__gGBlBna z(CX=P7x}2D8O8H_^XJYhzPhByS2SmC;ngg>diqs!eRI(Q=yb}IVi1oSHD&(%>C>(* z@=c#TXMQ26ib@J+&sNyrH8)Z+AGqkP>9eLxpE+wv(X?Vn94VPTbJ{%LRkKJ@GH3Rj zYYON2t|%;-TRelLC39x^rWegGEGeEpx3Ew^vmwG&g;xPa1pMzSnU2h~5~MCKzIp}} zTv#}ZC=_zq{OQyZP-o1Epna@R${a=wqWP z-Q|l5=glD_wA)uaXF3!h)3n?Gk>37P|1Y0i`>(-%&gQdEqNFJ4@z6fs9BV%qfS zh4bf&q-f=oDeOr-6t0?v?p{#j^x3?^Lf@|@oH_3FDJKj$VaNzKJshhC2Y#}f8g`(`I0n+-T)D(A1ofKPUS_#XJ9(obikO+5@X;PeO1-$(hpyR zxVaA&HsIzy&}0KnnVi3=2HdeBmd!Naa6sF;AFyLnVxWa%RWYoLLfOGH3`KvPEy&NFEYYg}=40yc(cee^r z-eACc8~BX|{15})WWWzK;I;uj%z!r=aA!}H#VrQ>a0B1BH)V%M81OCzysrVzG2pod zyte^Y993bi0au<#!3P@fBMm-74fs(8e53(C+JFZQ_y7YQGT>ZmJAYvVKF|T;d$IvP z#(+;X;Kv#8nFf5Y0iSEYhZyjM2K;yfUS_~KpF4jQ2K)pEi0?`RKHPvWH{cTd=&}b4 z_y_}kg#qVU%=ueoz)yC7_^vYGBMo?s0XO|*y#YVPz;7_%qYZeY0Uu+)n+$lK0k;kK zsRq2+fS+c-TMT&6fcvz6rq3H|z`GdmaRxlcfS+!_dmHfa20Yh*TLyff0YAfl4>jPw zGTMnGT>nY{%Zq1*?>j8t_p0_Aa5A|FdoVe4%AECE2YF zq4G^#Ui7t&IPjBxzSg6A;xo`Uh!pcPNttMB#oy80nCDcUXpnq1^PIvHHIo0~W8^t? zCss**C-a=L6AwuK3+6dhCn_cX3GTVy@)hVxCiSVyfg{W}Z`VA}slh z%rlfq1SP+gd4^Dlp^|@wc}~%ZT**JdJg4SFj^rO=o>OwdC;5Ar=Tw|%-V4Cde_)no2ZfeV&*y3CRRy)9`l@H6AwuKO6EDWCMqR=IrE%S6J?UW zhiMf(Lmw8U1iK&u5i+N6+iLm6yG0!P85tRHX%yX(t43+!|%yWuNO6>`A4?@K<0CqZ<2gB<~j8x8YG|1Jg2-wjpTo5LY`AyVwL1~ zGS4Y4@qpyNV4hQ3qEhmoFwZG1Q6~BKndelNm@E0WnCBFhm@4^~nIFV_Sn?a0=Tw#m zN`5W#42cs%CI1ZboYE4xl7E7EPGyN4$v?zAr?7-i^7k;$sVmXENBW<6PFaa2$=}30 zL+eC?{6qTry{N>DZYD$zz{vzf%B_-xc z{#@oc6(y!h{w(G>1tr3gAIChWocCXp-oW0>a@lgN>Lf95&0 zBz%%TlzC1miROPv|1%$CzDe@knCBFdXpnq1^PD;oHIo0~Bjh<{Bvwg&C-a;t5)VlJ z3+6dRBq}BU3GI!o-RI-Bl(Azr)y96B!3U{bm@uaAEf`8rz=l1NuKo=RU$8c!@fK- z`sQV!=qI7_ZO!3H6XO1t!&$yiyvKR+mG?QYT6--3&8|RSXdx8O+X00YgyQ}LzC)v0 zLebAk4uLB^1vqrYJuYo+DjE{#yHxmJ`Xaq>Di8Xn2BFmUNQLiBFBfy^S<7SQ~~Ab9*X7tfSla}8n8q7sP&Hp zUKYhEqhQ~>2$pCM(JxID0fQ;bD#2*!mQXa(P+q#FLrE?^JC+=ZPk%|z^;w{^AAzf_ z0(xuWZluthXU@s;*#%H-C}v?2s=>6x=DiAVC|YOl2cuk86Y0L5wc3kdSjkhpm=9~r zkI{XCDfOH~%$|zsJ-5!Ik+Pq`#Hobo4!>cag25Du)Kh zC9rHArX(!~lue0)8skDG#{~OeOvK0BW*AP9e&h2L_ z{f!p%z_MQGCHq^1HmLj~l-cK^@=7}&o_1+XWOuEVWJzySqIzVwXu;oS3ydG?Mo&Bl zPD;GasISaQW(8K~Cj+bBj5cg&%Fe<^hpdKp&t>e;tcIcuc9-bJnlC!&(yW?68=@~S zeJj#!eK*nfZgz#g@l(V-t9@g#N=`uTWu40|IjXEQIV|woVh#l>`5Z*MkwV`GDv>Yo z3PKK0EO+Q5`vd1u;w%DA@=%mr=WvU3N7+*>yHwSBIZA5bVJ__iCZ4W-7+7pKy~ zjaFOrBvIRPaySeeD(&N4wQZ-`KF)X4wucoU&U@cg+m*Br86pi(V41a@YTN$rs%_7= zqP7PZF1l*_gU*TCw!3QEo(IuJQ|O}a9JSpJEuc7%EA;VGeStR@t;;P2K4K>(RK_A4fk-^XYRHjzXn*ZTt zxJom;P8bH3eF2*R(?`g3Iha=3Pmgsh_e(u$=F(*2d6OnMjOT!Hne`3DESm_6 z4y?9zhz=G2OX*;f%VuXAM^^?cDt9iLLz~pPSi~xBMirIz2FRyI@mE?GGcdX#M(Ed0 z1=CSMne`QQ@zuYpizVMc7rPLNGaiGrx<9FW17Ji=rDSrZopum z8CdpG2UnZLi}yj?+oNv^{}ilbk#C9ZUTW< z0mF2Ci>1EEb)d;_!H56*^Rs+A0~c=C891({C~AFI3Az+lJA!Q;_`)xe$J(zUSv1P} zPQ1`gxI+8VuN~8jL1@)`qhJp3$X{bDRup_art5+_NVbRA#{)ZYX{vQP96U@*)&!Yh z1S!d;>|3%u*oe}SooY(f#JXPm%8_gb>_|y=Kl-YTWM2^b4qzu<1fo}G-Lzz9q)YZ1 z?qTgiXXPo$RwC)@>~+>P$d&8@S2BNlk~I?hUtdBp-jeZ3w(?A6rcXhow4SG6@UV%U zK8TfLwG;)0_=iEp1xK=nk4Fj+t7Sn?;(#)q_h&NyBbX--RCItnPS{O=1=d?TF$Uhm zvOIZ`GUe$o8@mAOax`YA7{IN>z699Hq2C0%({y)(&ZFmbVEzZ94`yq48Q9yJ!MZhD zp&GX48P%Fys4ehyjflRuubYgp6(|GK2$?o+*R9wkEh{5z6JSN)2jc565YWH)NKR0sXS$?8O{#sxx2T7t)eb2TeRd5#k_RZ$#=20~>X#P$ z{YAZ=4M$7Y%?QOh9z75k^d7@%5PAMt7{X`7@GpvWYuwNNL9!9a$5gTj$xSM0Bl*2b zHpi@Wq2;02_?H^gs`F4f9WeLV=RgyRBUhu@F8pM`#jDH+4OfDc`0Y=Ut*x$+PiQDUo-scy*~EE$fHW>s>ATXHQ+u)jf<$W|TamP|uQWo4=fXOTwhkI9NGvcm`! zQ}sWGs!;z()DIb&PpGwa46n6zo|q;JrZg?f%GVrO-ag)urBG6oW!hUxmVeH5WjR|w zv?;4`tV~R3%39h=H9yv4)#tOHoPtyiQ-#-vKv@td8v=EJKpi2Fzt;Mud#$yrN3Hek z{u1*7mNo)|cJv&)1*c$Pdbt)7q zXu(kGDPtN#=`PzHN^$>UUGE2rgmscDXIRMesW_CpRC$HCzku5ifNoYuXK0$2RCbM~ zxpbOI^RZZBo!vvV^bZMu5d2pWT8BmoPAlz4;bf<95`?-q zf1?5v&ep9ipGOE)IJyyHMcB2P$`wgGuLxiEl^-~294vjF;~-5?NaqsCa*^h~3Z~J@ z76|7co~RH95wVYp_}D*)=yE$mA$26u?)RN4`^(^Pk@izaA0aTc-*S;Y6s5UHyBW5| z^VSmS&o0tr>5Xu%Zs~cU8@5k|!I=KV9#&Jk>5vBU}IHU>jYw3c$qug0wJl zjC}|}DRNdGeV25fV*n7hv(iQuDxjz=N-D{fv@h_>7g&~uO#=hxVBk0+_jRh{O6}1J zX#1jVhzdZ^n)n88SrunRrfbR9o&a@-H)Cz3XrMh0r!&kngD@0*(Y{>raN)YC@9Wm) zQZxsMA)j{*s#8PV4?fAmJcT#8g*Nya)yDIF2h+2&soR*UB6bIRJrwm{g_2OT*VX)r zEo1+OVt26bQ8rDLU9QS#1t_BhpsYZZosX};8nK0D9(BTJF^ zd2Gm_ruV)HJsFDrP!!D$m2b?h;3xd^9W+NYhS)HdTrhxsR7<6QbP;s6oqX$-@hB4v zX}?`k$(&TOcPg2iN)FUX*zZtDrs^g~)LoD1+pT*JI-qXZQxMLVvpG4e8uhKJ_zD=cXX8LzXV?W%ti2K-& z5pqWprS!kPNp;OLJ+rVUmlPbhsJwfDqk3XCNRtNu^so!MkeutR?X*`}m+%X@q4;X% zL?4P<+t*4$CiY@oNntOk1c7Wa6wBv?-rdn~EyPiQrK&YLNCL9*Dg zRnS1CSEJ`u)l)HAnqtsblRMwhu+P7>d5oh{bQ3*(rS`F-W7!Y!ufm z+m2621vT8!jHDnu??Xeiw~9YUa7?hDC*oRO!iGF=e#k~FV<|@Y7QFHuAZLR1hjM`x7c$=zfVFMXXpvuvFHxNSc(k;rJB5hneTD_RYSFK^^00LPz$e6d`6*h!xms+L}{Gl~RB6~aoA!Osd9sz%^BkP6e z%!y~qx95bSr7fUX<}xU`0NDjPTV6AentDTx@~Ik%C|bu4dnilX|0^$g1DXQpFbxHR z{J~ki)QT^s&f0^Pkg|uDvPf05`(=?o7VZg@FLWl@d(_5AXON0Vi2L7CaD-AK+}U2-Z)w|D(6R1gbyL__}u?;8Dk zDB80gnaeb$^z?hJ4N1RUj%w_uKf_*Ya~9U*e{^JVY)Ek$3gW*|wkVhiC^#|{qlx~P zf{GSm!R}ES@b3T<`@LQY;r}qgQjDjj`6y6CAqCfe;(5h$&Q*pqhW!L>oPMX+)ijMq zzpOlLslt0!*L0Y|8>R8MrKIpKR(RcMnBe!#9m4MbjYp@g@TMuej`a%f6@{08wkaPM zxoe4BU8wN(=z9O8@HS{Xu45IyD-_;|x*gXlyt_4CXW|jLx^yA*nOCf8FyF32}*RH9ybo2c>`$yzHwwZfR)|0ei#_B!mywAu6es?nXq zJoZMzdPZbpYNU21@g7&7nFa6C>!0J(z2Cv_g1g}(=>5b@Nnhr2`bv-bc#j#1(@SkQ zz4nfWlXhwLFZ)R&d!Ugx7spV?u8{wJmtCG>_h=h-*Mpr*;)x$&v-bNRpycZA7iRD zu|FdU+>vkz4^@Q6wjsP2gpN2C+GL3Hs2&Xq-tmevz~#E>SE8|AZMga=&JnISOJKeb z=S#Lv+7VNPJ=+kz`gTg3`*0*`i1SM=&ObMM#ktGnIzn;%?(}p6T>!53E!eJB+G$p! z_%fGp&l%E=Z`%;&fw204-?G%7&lm&F;gKzXgEtUs0`YL-l)5k$*LBa%8D({E>~u z6mH)HmiF`b09v)68F5Px(;PP7BQ$_u7}QW9|D$%d9MjU)@;;nC*MXsmR}Q! z6~MV!yPa)SdZ;DZn%6!oLd}&d_8t8Fu_lH6S8_;V2yi_fZz~E4e4JTqpu|H!q z4cZuOh;mClZ_hYXTLRQ-dT#)J06+zMm%%V%))u3%2(c2me44jh$Ei&1wnCz{ER{#1cjqz1F3gdUkcgZ3zmTx=!`KPN{)cA zot$jPk^r*1A-k0NBb{Z}TZdVWVE%U<1VvuwWEFXpll4camdAA#$5`oney@stg(8>t zV!+tBxqlTSn5DCiz$To=mTyO(rtB^hEvRa1dsw+*DB*Oe+jO< z!(8b<06A8)NEL4Tn+yTiP7U-N84J~+usgaP@mnVvbP}8SyH5ZDEFK0O!<-G1!}@nO zyF8X(rHW`w?|@vH*uUPCGh3j*-2L~_axso$5g-@TpBddTHVSTUqJ!T8iPt!GzD^C~ zL)L<(^r13I4}n`ARP)J1Fb|>yl(`W`prm4z$7HVZmNr!`L6ypXV14NST2}fTfDb?F znSczfGS0O$p6=uo3+BQ(CAlHL=XodZT0`7FN2A zOBoX4ERZ5VaINnsVde0)AHk&{Rc7eIxmwLZ#*Q13#E_6=et`StK$uR?VjpOZoV8;r$RWYbu1p-X-W zP}Y3%BKUHN@oDt?&s8iG}2%?#0>)#QvCdnG8K9XnLqY-1%M)6Cj8 zcAxj@BmcE2H-v$<`-{+qA38I&q2;vDpp7AT=i(Z{9khYq;+o*NfG?EQj84Gea-<17 z>O*V)di%Qr?EQuu;PN=s%LA9bIi>w%UBZ{H;%D$IuJOHm&*+eni|5+Bml`X;cPYDn zj5C}rdd*OiTK`5P&A@Jk3-4Irzo<&O=hHRN_3xo;=>1@T?EX|%Jnt34A4NJ9jt@=O zHM-i>@vl)Gm^Y<#Z2!!5vjuIWzxP#B`m~C%(f3^zHt-9+qkTf?qG)*hS_~pzb$@)U z=K!)hV69qVeG7~lL?>$S->C-w%DnW!fB)a*X2-Ya0xHqnuZ5Lkn&V)l*Xa4dHjTBcvWRy?p8()LUQ=dO1;BE{n%#bZ{@IAIe@xv=m5;#Tw( zlBj4yQzxe`m(|;X6{0xx#0pR1#q3U54aBU6R4(S@DSm%c{EBPtrXDE1TQAmw(H304 z+Jo+5WONYh3f*-Ek~2XCTb!5D<&hv?>*_MZ3ZTokOW@sHPe$)QL{S>OaFB;`e@%He zDD6{W2+|AVs)+^iuU9F?mDfryaLu)apqMoKO(b=*aZx?1Ce?Iw$PQd-cROTd75Mo) zlHCqsw8@aHr$@39U3KexNcJ$9(LTmj6ANM#=;H4di)4cU8b^?l>|`XhWO9!_+vyVs zHrW(xRa?RSwK83>ULL_dKsl9NM8WuQhX{6hHL)PYI$eCJ66{!j9w$f%_D3W=f_ZfI z0@tRF5kH+K+P;SNKc5v_8KZ{w5s*X;?SZ_&oie-k#{|Y48_Ms|H8r zp}~jB@){~&j0pc~#qG~l-NuV!20{)H*} ztJ=~R@ftwpK*HnmUjM5oW~5R~A6GGfmbQvHw=PXFJN}%mn8Q7ac@yQdgiEl~V`s5F zG|^M4i3Ke@ql?d5D2nM1(ES7{7j`?6@GP@x4tG2Yl(LTf9*%gRZssm z^}Myw(;nzy@000WPK~8J?N*et%Zulr%lD@dsV*lL$k*%QshHF-7TD!a5v02OK_q1| z>1cHM-_Z~4cR4o*v2PC|@93m%QxZ+kRlavMB;vyzBGIYU!~*$XUHp2)9i4{~q()}| zNj*9{dOXo^Q!3BsR8qbBM7mV$iIh~UQBFOLrBt8GrV@rmu$owq>MmV8Qb{!sprr&U zsTLurrILBYaNhq#R?YzVOWFV#k%c;O^;K?07u`_$U2CTWJ;3@LU68y&fPMj54)9z7 zb`;=f2bd?o4gwtJ00#;%TY$fGfCmXMYr%e~=x_}*lQFBs4Fn!|+->6>NT%B8w9v&| zAea*C%pxWo#XQGqT&!@4pOxZ=8854*4acKW91n3g&TqqU?+QvN^?rk-)EjAo)tJJ1 z&B0pG2J4v=)?*IVHEpnNPGQ~PU@dHeRg}WI*uk3H1}m7t8sT95#)}2x*ee&M_xf_+ zmiB60!m4eYOSK~YY5}+f58HJ|`Uj>rv~(;wx)n}`p_$c!BT*#x2G-=`UjacsU<)Gp zW|T|06NkeF<9WwF)lctU^wD zkwjM(*W8Zb=hX-5>6SuleN-bZZx8WflxpL6*FnVTlgklPiTiA#Yokx4h#qu^?)WL9 zYf?nB9iqDoBA5HwDa6wi;;fo6X)VMfy*mR3SdI9|Z%B)x_zVOJa{Q$yIrsSwu$l;M zAasrawEwn6EXi;=qsF^NBv{jX$8BW*7M+7qu~RQdi)V_mMVPjh-S!L zsg$#fqMXjMXR$cPQy7!S8IW(!nCQFZE2r0ah~`h!1JtS1|Oi(2z1T4s-7SHTQCjpu)@zUvUNb zB`~g+7#!kbnH?>l4tce_M`tB+$P^jp6FxiqH(5@8nI5FpzFuvt@&UTI4)c+om=7XIxw*b%hLVXh)vT!spJ6Ou z_N~WZXzf1rI1&yRdK{?q$Q6y!<02fFC_SDeONKUj{OAPf`rPAhTqVlpbr46g?hn=+TC8 z{Cj%bf!6L*kInF0(Bm;mk6eH$Jr2WRi_+s)5;V8b(O+%u&;9m!r@vzUr!l(S3FGhwSfvCw z2O=rfI$W&P*oeuMmCbfEU^}F|3GNx~$Wd0t+X2eTUcqJO3X6*yU~&<4g9O%k5w#R! z6e53htRXT;@xjpz^2<_a9I@y3p|M|Q-c8{YmT+OWHU0gFG*A?xeMa^oH7!#T{9U3Y=naf>ZY~cIZL${OZ)^E7o9u%9H$&u8{OKk9$@|~$9+QRp-{23-XBDOn<8WSseCp%_Y}4k|2{@b$#Y-_L z^0B$fm>}{EHvMm`qMHA}mqgurjcHw9X3jYR&VEEdJT|PNaeG7G~K5c;jDB%$p zzP?j<-#U2jyLb&$M0x;lEr4$5nJy!m^(6Z)JT+Q?(Hxw?QH(k=h;+YORpCBGTIu5D zwI`DOoGB7y_}#tf-ZU4soSNOQKsgn*a|$e+54-4DiC7>H>EZ+?Ej_!BAV`h#V~~Ui zZfNqmqo}8SE}1xfbd9lJj7N&x;SVQ=D`uyQw_}VxiYfJcv)^su#b}I-E49NP&+G3N z1yMwj|VzWNOvH8o=JBgwN|Td zJ(%HDFj<C#|-OK9^z%6Ao*yIL&N5`)9w0kA%SEl)(L5f#1Lr2W{JQl@F!?D z9MiQ&rwcsmFCuW8GlP%+>Y4%8|M$2Zwg^e_8Ka#Jb3MytDXjAxtW(-xjZ9$;cCfDX z`X71$z1wc>!2|SJf!k{^pkV%7(dk{WRSe9XU9lro^A2y*A2+W;^VFXG6gX_CD};`G z_HHq0W6%C5XfI{bx1*dU-S^V;J*dTs(%2dIQeLDfKf44SeiI-1V2C!hnpmiKv@YH< zT?PYp#s?ClLW{$ZOzk`1H8WI;jxA0lFK0}ws)BPe*Q~g(u|3UHU}oFp7A5YZ1DTGN zW+pyFojIKi&klv0rR)c{bhN?Wf(y>dekMp5F7`7pi}o}6$aMQTc4hna^Wa}x`$2c2 zox$blZiF?abe@ZH>ikLEjkLq^a1JzgdNr{?o~4T)x?D8Jt^2R;ay9oUk{-=@Hq5fg z&C%V{Ufof&M?me}#v9-fZ5b9xDb*uUWdGI1n=hXW%u4cIsNVRC9n*<(7n>9H4#J%4P$*h%NX1rDsWYVqh}ozH&hP&_Z< zpZ8ySeOrt~%s(BUdB`oy+0oi{(&Y7FQ_;};p3U1F-QS00$)XWANUvS zUsUHGAjtL-P_mxn2>Uq%@6ipgCmfmgnsysnwmh)9V>U+Qs11?s_CqMP!$42w5Qn$a zt=h8E+O7*;vin2x(HHF?zOXye^+o#gwQz}~Ty?T7=7e=+~>kdh_+^++VU)%oY?B0C#`@HYMlSj#8&A`Z20 z?u}mJfj7pzOg!#I6np*CD8h}G*iiWlb(F6#Z!Fi3$Ngc+26M*8Co{6Cj|F>TyA2DXE8c8bXab<%J<`kp>jncCR%#-2NN;@I#7=Z}x&ud@&q#YdcAHfVpLOFmPX_#(H{V%q$=)pQkBb@iu-?%Spv%!iaf|<5hV-h z+%gCcksYa?lAJbzGCp{n(tg16e2vOCIeF}c5x>#NbA%u-20{F1RbC`w9@99>Yar9toC$af zYDB)4h&LbY8_-^qzNt&$uHS@=_8#ouEUgJF{T64V_P6iz(XzU%$ieowKMDFnDfCaE zgvwC7u<_!tmyEr1>}6x8=*R~1m%2J??~qMsY%Tk{-3gaD%Gw(ljtfAocZfHt@PCH{ z@?Ya?%;5`0$$beG`}Nq#2XEd%!4b)R2x9ia`_>{?>)(J+<&hNTr>Mj@$8#PqQ3ogX zXP-fAgcQ&lBc$)Z>N{MR9tjPg@mngP8nk@JXftk^n-&>>CG8iFZ(6i25Lyqc4NIcO zp>*%+ao@gALSqqCUnMpT@elXu2g$XfsI?rq<)OQI$7nbbgYa_2mg!46hssNrx0Z5; zyzzFmBEh(ba6c1b`Arkltugq$2z*_B&4k#cRTE+b ztI)I+;Pi@iPn-s2CZ3od{YO5=oLs7nv|)Q6y;}LEp&-3biG}w(Au|CPxy60D7B+jq zApnm+u2w`oMy2d!aFZP9o@0u49&uv%WdHSCMA+Y~fNwbX9o~yS_A+&yI1`n;e7kwJd)Q>1EpiR&8IV*v1vx0RVy3FqYh|*yb}ma-VGV{#M>aMD3v% zj!_J+RSd6V$?0Hdf52;Q@w|Wb1>loENs|sxr~&!Pn@!Z-M3wg+;FYj|+iMi+=O9Dt z3l-OyME&wjpe|Ef7ZGqXP*Y77+3Z4;t4_J>F{uA*{br%In@Lvl^XNL%(JQyrxxtIM zV#PzC+Dj_?j#pI2@xkj6tgjF2(~FVUc#G2QMQ+onTJ1;Wc?#JT+aE-n$yNKYX}4db zH+cEUs{!@E@v1cJdUIc9qg>mfo&P@7A<^P})si4CQ0# z0#$mgqIL8W_n!~njnf&Vi*pVEN@OT>?wvNF;gy%yEK8F|ka@LCfBdsgtRfkV5p{iLqGRzeeRcGML19 zqsnD7F2(bTl5+yHmI<*Smmn>QAEkwp!`Q#z{E0H)kAuB9cU6_1pSoWLd~Tu?LV4x+ zC3vfLAC6QEiyPcqWNM_~#pb4}nvtq%;@If-XX1J^FYWheQ(c~_E+?_SQ(ZjFjoMG) zH)GwRT>@*)?T9S}R@DFyl%SivQRQ^ApOu^wP(%3(Q?fKt?3nNTiHMl76)S>l!r1V( z``JHAyK@rDXwvKlCCI$Cf=uxUGSMT*>H84moOT4cwv8aiYC+t0O~w7+!IwgN_sNY- z+QVlA!0sNzCAQQMYUjbz^T8g`-25_-LV`YwTuUHUPg z*BC0o-;H}F;>pNI)zLeJW1ohZO>HrM;FhmyxUpWB~=L5oWo;XnLRLWn|UPKY#+DP z9Te>&ocGaBAS}ik3iN*99bl$s;I}}glL5T8K_~x+2V@LAr`~#SO}w9)Kh&!W=E9CK z#HT5!dh5X?ok@S|!5A-TA#{`Jtp^8aRQ=Y2Y%k@%U^S?8`^`!e_`nW$pR+7rlcE(3Wb#pzy=#whUzYiR0~6vh99EOCENFM1wZfP1Pjx3z20S|=dE*%d?I z7!=d!7GDq+6j;!(b4|!PW2K{KU6RrKAl)+Ip<#>wS^Is4A%2 z8t+vNKkwD;0NnqQ#w2DjEJB>&YD_=>_edL>op%B=eeS|;5meCxGibt05|!Dm&VK2? zL_^qOC~Z)}{8hI*-mAC`x~=g2lZdxNLFp^mJqX0@qP&s7#|m#?slkC2HHtY>4r zC?KR;RtY`>#&>U0_7m^by$$bmcL<4`P!Cy7$?$L%CTm7O2$iBctLZl>caTcsQ&mWB zzB`q!zf00Bi5eoZ>G*d0)BZbAF)mygp2mFb?d_3D256)vi`FgCQ&A+kGB z&R7I{fg)%l1YPS$`SP72jYv6!k~tQEcslB+A=E~M=de4=I+T;F9vXp@U=(D(@CjQ_ zCoz@e;v~-3jNl~Ne>Ici3q2$%*L)q%M z{~sC(J^dLDEH%8$SI0c7k+c(i#LH>5>XKVhoT|66l?;0Qi@dmNb?`K?rLu-yGSPrJJ)mLF><+Pxd?RxDrjqV`B<8BX7+ zG@s2|c?V5}W|ZF)TI;{=n=3!L@Xe6>&|)|5LyN^Vcxjx^dBAXodYH3k?<^{zfMPhO zGF_yfdQAH*VDS;Bh=iR&vGcoxqGLyfq7#F$GjgJ1Luwo!MstQ$wBqw?ZPB#dgtKB3x zRuPL#ytc}3I|;5(1Q#KBiHG29gTT4mfMYAXsFm)vpLH1HliA z%tmilIcfA_gJ3gOKUhXj1;O7v1b;IKoJ$kp?H&R}6vGGY_YmA<5a?T8Y{Gm&pNUkl zgD#i7F4pL2_q|9G6q4CUo#c>+wGK3D7-h5}N3~%t2>c#`-3vtp(rD*;2rKvqt2i`z z9+I0CiXIQO27zsB16c69}(Gw1uesq9ZRTN zV%j^gt01rs1tw>|*guPyrm#`vWY9QQVuj{$p?Ls&!1P`Z&F>AG0>elbfCRe6Qh_ux zJv0{?H0K*M;}p%KisnQQ%>aYu0)u9MMZ=?J)Z_Ee>@0CiVOGs#gXVoKejpo9t3mUs z!qRq7ZO~k3&^)SWc-{?~rb&c=f>BRIL@YxlKiuhXA=fVp6e}n<&pmo$@6$WCNJLT zD)}18v+D1!Bfm|O#{rQ)A$eXOKxPXv469~fl(gAvJSXOCilkPr2&77FT%yJsNx3|8 z;`_l^8*nLtxXam`sk5*C1#hYqY(rT~wX^9I!S)Jyo6mMetN!^~(ff6zPApr1mucVw*am>25NJa@DH*Rz zHlrj4c4RSB!;S`v>Mqnp+}}sTKE@WDdYCUcoR=L!@t!YHa&T36zRr_Xsp{QAE$LoPmn5umMEN*lGlVA74QNq2#Dg0!)= zjEiYWYW*55+~#TFcHlcL3@pWlhOgY(hE{GHjVCW|!R2Cd(JkGUv8A=a$*Q(^RgEHP zQ9rA3R}L8HHv-x}F2h7=*)kS~P)-_ByvHy0%feT$Dc#aHDsEZoyzhzcwbIx&(12as z274N?6Q^NhtM`n%W+&S6sOfDbVq;s~hzYX6()*@vN=`1fZ0N;?UX~n_(uut^K#s%R-kwfm8-=~^l-*ZXC<#W)S6N8N=cx40fP z2Ym6AO2Mv*@P0BXwW}d=M4^^+;!pB8E;vAfSivq_xHj?iCTKL`b=b!Pn+}^pSxldX z`vUqNh9s{agUc2l1MrUl*JW#NkTm7{d$-4G9$2{@n!E2w0}J$&45L8UX41I!=SkpU z)SRMmCYpjR_(d^ynvu||ooPm5TcsUg`2XcJvp=U9%qyd;Eerg~o4vD)ZiXm7ZECzt zS)Qjye`-#Ymj!!gK|Ea-%Hm#PQwTp-x<;t2AT1~wI5yPQ9288UfZR4zQ5@WyE%k>z|T z78moOUtH^@_;P%b=-uwL1oKyzh`46oO@%W}72$5!5pEW8bq2qE! zqP^sLJVRkgeRb9s?cxy9K~#Lv>UXb_EEj>gi_sD`W9g=3>0y5!(lMg=-bS^B)&`7L6Lqc5P1Hx5!Rk>{|A}9WBbl_rE4u)bWtBSa4z{?$q!OC4{ZB zU+u_%ACEWJz<=Oy^Q;`K{5V;MqHoxpQ0V$epySS_8C&I;jLJ>ip@Pe|hDJH1;LbIs z#qrVn%@W>}VAeuiT%&TT5iTl-456S&^2(qaAqiIRafU6}%aN$5A3BjM_*j0U!jvCM z8;`k3x)rCeKu8^#=BA4xO(^N5B-tNdsa+-=f}WKo1um4pc4c!0vx*3Tdkz@#^ zEN(XB&PB0E<7&?pBiexHMwJZQ+d{CXYaN2I%+;%I<|$~9g5+z?(#}iZqP?6|zfjlY zhSzPIx=kJ-Qo(sK#6G~y$Vs}Rdze9QM}2N^hn5OUOsifwH50TKZ_yJ`QtQ&6Lo@K- zpc!e>I4e*_E{HSj6I&!MZGktRjNsvG)kw_BJ$(N{&%}HECgER5{LeCa;hZEYh% zS^9i#FhHYLixcysL&R6_(zISYEo>CqF2|sA`neFi#stDMbSaZ#!m6{RoSSyzuHQyqDgVpK-;A z2zP;A0xPj&$hWDYCA1#EIfvNz@wvdtg3ZylR1r1{IF9sC6#Kdl6Mwn8YjWL_qA%Bq zp&2aVcHl+$cpLPt3R$keKsuEfc6=?YRxCD}gPL3Ff^ZD7pofz|gtu}dek&Ii_b@6_ z*K=TLY9E$Da?%zH!(ATy$yiPf1WT7%_HZF`u!|dJ^^UYZC`@N{st6-Y4Y8PXs@1CQ z<-#E4>+{k%%Rq)pjdB3sRqDb(R=^`A4Wj-Xv~xguInvmYVUhA2YY>WPXQ2QCfzghZ zWhjw3n4HE9$9;|Nk>==z9Q++8V|3rD!XM$)IjuU(b+Vc7{HPMFCl>63$NnKQT8G#Y zj$>50)dG8O8Ex%Za-37ZTD1~uYY#8Z(y9+8tfirOcIsCMQTeQ ztmYT1xgspAV!=tuzcj1u9E@TbQrP3Me_}VWH+?57rsC&7L&k2R3M=aDm3ZLERk@f1 zjJxe_qKDN{rm~e8W!TT`VoLBOsxl-{onB`T{&^C3SUr@Y`M2XkY103i_^|zE;B6}H zp1pBRkB;RAqv++o(Tp=O`r!3bCsIxAAHg}+i@RLfcroFnpTl`KNXybUNL7eh(uFoy z8$2;fY~F}aWTU_-RgTx|o-jC@K#YGuKi)B>4#x`ivgyiUpV=n3%Sla(MbUy?AmJOq zFk?02sSb=HtHt>N^9K1Lb9n<82gtK{r=EE|5$~s+2G_$Ogx{^6$VEG^T=WL8LT-)h zk5p}NY&L)$Bss1F*}G?}7h;%r055C6S{Z!t9!G_0cz?yI_Vh~(8N{<|)d|#Rq zV*!s^^dhM$Y@64@KE>S%aqnW`rg!M5G7+#5(|ZpI+-cN@bJg6 zd6U+nZr|?jq78Ug$IE0C4Nq45>g?~(-|a;cB2t|_*N6mW80qH_qbVX&Ur5Yp37PuQ(s$mPX5ut12Xlt9C0ZRd2$LbAT-@_PvPd5F* zF$;S{Wu@=`0LzL36G3E^3$4Ab`~gbQ4of?KpDSg4(xW2i`n#*pgQJ zyQuwLb>zT!nQ=2)G(=M%37papG;qkPEhm z**d*BUrtta*j|JpT-(u7PL2T=9jBb`bO@^-nZgrJ#^9#uF}9~&pvB^$|Ao0EHOt@* z&K{_94-ZGPaW^E*xY+G5rLm~MTavy7mJ7e*Zh75A?K$y1Rs=bC8;FlTZy`U4 zSXs=(o{CYv0#5S*;NTm(!{wzb+^ZhF>2S5N>f-?5HN@oQFY0|kXuZ5A28*u1(of-i zxPgytc$@|VZg~rN5@;O0vOuqh%u6(lsGxf3J_=1 zz%Q>zO)gpWQ90T}Wx*ggxR+7L6$?bjw~TXO>O2EO6nB4k4usld>;;yd3X5~kGjI;n zQMEu2GMs5N;e1Gb%@1eDvLo^3kupbDfpHTRp6D<66_gy?9Xvw@T+W}HQ1L*Sy5$IK z8Hy;YoDBRGhNO>T09L}*Gvx})U)C+Rs-W&F9<5Dt3S$LT?diFVpyQRG>p=Gtg56!2 zI0}_jCXV2zIZruzTPg;{AfO|YBV4@UYo|_jtgyae5|aDnEOZCl$2W|h5LpmO544q- zKIO;M)P(SyvI+ReNeD?8pRU{}LKuL?wM ziWSuc66=$qW3492Lku(qN?>0VY(=O_8CpVF8}Nm&q?Y>`TP~-aZ=(Z9UWT@Qfbaw_ zO}25&j9?j&3Y(SHP~OzJ!un9L42J;Qq7K%hwMc&`L6~|kZr9rAjx;oE{^jr}oh_4S zZm|wYcaO5R&5LOT+vu1Q)uZ-Uv2pb-3=HAXIJNa!{ePfm|FYZDvy=bd>)9UvXL>e! z+W+aEMQ7KDEvT{68Dr-^-i==%+%*R1|NY%KddmN@ZVY0e{OoST<(PtxU<2BHPC(Rd z^v>gIia~^Km(k}U6ltL+N<}0pMrMQ#SFa-UdG3XuZA%KB0)62p{f01SLrfLEk=93i zc@t+x#iX~JQ9lKYsT0wI-UEjx>Yz80D#9I-x1>$ET$?o_YD27ph>2n&$WqhFS2~Hw zgy%}YkjVrh;0GXptp>sw-zY8U*^)ct6f&?HpZPch65M8RT&VnEv!3B5V|T)hG}B!m zeLH3}PHuWi!{jD28i0_85j94m$OB(nKqTEOt9N>OvqoC)Mb@ZHI2+#_ZzDHG9wrEa%hpu-oCVv>G-oAdVkMn6ZH2iSiq>N@ zvx-;mHdPeVROpuud#>3vC|}J5Qw!F%m<8U4lU;{zHr-tgZc($r7C32vr)GoHa!~vA z>*bTSI4g1LqE;{k%E<}VBJ%w{R$pbMo3bLg ztSKtax*~k8V3*gNOKe0I5C#t0S{Jpp)!}j`{+#D*U=*?7cWYfG!>czE8=i-WU7>k1s@53FO zOr0nU_9%z!smD2nY~AM$R}P4=FUt@P?}j&Vb769btRmb!PhFeRR-skoRx4b?x-TWG7Kt`N}W(RTCtKxv-)1lZCP zc6%z)@x@GUo&UMUyW6#{lc+O%1h3~-%?QQRFTT?+48s_ZEtN*?8s0*_(FqjaQm)}G zjCp~lTmw-&fg=4UN%d&v?guU#aR&>#Xo{r@5w%8U1K0!!Z1u8b)LvDA-%Uc-NGMok zgo6DVuo2v;*4mww?1)c{^35FV2(j0>1DQWBgN8WAt+E|_&fB!K&A3OH{!8a`!$ud= zOj_hJa}!mytAfXg>ZYD!GJR3kcGQJX9`{XRr5yMz`nPMax9dcNKgnkl>A+_f-VcjZ zZLkA%MhLEAWa;Gg3Yj?I7qQjU{^K;nGa55teGWvn`%J{>jEZXwsT*5s z33u;StviRuO=h#{sv&P_)Bn8XMvDz4{5M)YB;VU|j6E6Yu%m4?-1GX8DcS7Wi_~6Y zV~elHp$CY`_ScVU`>VgzI?`&5jBHyX8)vQfm8duSZAdHSewezEqaH_c2OoREPJixB z`5m=D#(caj{aL$P8(pK^hbLJeGH5PH@5_mzJMo(mMB?>8L6#?;o$D4HfQ(Tv&ztux zIIqfOA)!~-YTc%B%`7uPR6kOu4}NCB$EFT`F7+Jze7=`EA9C;OzkBf0GwtBV8#IcZ z+e}N^!$h1-i1kC!5c@cc6?#0#nR?W6B3r+f<*watn!s60c6l+z;Z{ zt-^b5)d?ZTF-(cqrEhOZ&xaTpu!$oAf_)bzho^d?ac50Q!lVh|kHG7mPTe(p@C=@!76LxY3i zYVrDCOJmc@bKLUFP~KjH&CWT^;mVtcjzprmp%6kBQbM;-^n4H{^yo4Oo2`d6G!yDr z1?cP5BO%R5;-5TVg0p3w>^2D|z?=yso^y1C8OuG%lk;C4dh$%Vtn^)9B&-;Rb2u3; zSKehzYhdX^Ub9ygTk~;s@|Ot}{hI4q-AHAXyuF{x9&T$Ujkw~R|0-`5ZC20t zG#WM{#$d-v?U?ndx{I?Librig3UdRiL2q!y3J@*ep$EvJ&NAnO%==zcA{valpt$%i z*HOGT?FYf3u*V$#GmfTXJ|oaMO?Czz2uw`H;Bf%>bv_f`M_Q>JxURUpT63gEx#yx> zS&Aex^WG+NXH}ARK~qnBH5j@OsqMtK9Iswa^Lu7Xlw5M2U1#@t%fMB}m|<1IPDhKl z6(|*pJ~H2h0rvl3t~^J$<5@I2E6R|Hk3pjoZ6@_3@*2iU>Ouo`f|5G>QpArbaCcE> z`lBpEjX4*0&l|AvZPSt_jdCl)JDeyr?ji7%7rNp_sMWcdU>p(H)IEySwhYG;j9=}Pj4pQ{ zNm#;REd|tTJNF-2P>vCUN1ND{wUx*=GW#d!#WgRQ495!Y3`X;}_I`7v+gyP_%kJ0I4Iw-V34z_)(LK;=<8RI zKNxgfRo?iYc7FX0e(oF?WW9lL>C|jE#sXLG-9ZM+^ic{O5d5IpEl?CNOae|Ucoa~M zSIHb4GYhOIes-0)Gkm=lnIg?EsZQkx#1#$VBIuQvFxet zwxMMqfl$eMz&vrfS4sQujq+rQc;&QP@%x|=n^83T@TUy6lPPDd9Do~bLsUdAZluzL zB>wr(L1++T1$h9uS*L+59aoPZPs75OP}POwxd!GPKhGm&7r{s{m|=nK6vk;mB3zO3 zNmDdC_8{Mg(kzYv74+$cO|eEmaEPOD1cFNkxO=xH1N$K^d+nl}$k!d7!cYuwfJ)|! zvYM}_?P9so8}DMePE!t6Vrne0yF*=yT^MK53a1)ZwYmHD1bmAfxxf>UUKnyVMH4-1 zgN^Vm-tn(Ppt@jBJ^-cOr@eCQPx%4N`Ru!3a4o4^H*iu=1ytgD)J*RBvedMIn57X1 zgQ=VO5}u_bRqp_nEfso)V_uOhIC+H(uD+%mG~Q{MFMGh|W!!AM^qj&eSiHx1NAljX zOgT@Z2updA*tns~ zwa0=JoX2YD?l6_W>HaVnMZ*)EX`7~!dd}t)5HbK)_vrJ%8@^s??hAB5Y9dwc z1yT=%LcOyn#VPD5%3;gBJn0+Ql^i@wb;J8DOE`w%M1oy1 zoNhpHwSrJ#!eTT{+>6AkIN`{z5#L6uWs`8?o_sLvpdv>PF;8H6jF_Dsj)%vr)P2me z82PIwb>6Vc@%tTa&kG|D7kU~j<*5d|-laYr*9lm??@993)&;e(zj%47*Uzi13v2sB z8{D5$TW_OnkJYBj+iu%>v$msBweguzY)#UyyHQlF^(mIC_@xK#uJh=KP7BQd7gR3wO2D8?-BSLM{0kCLU89g!w;m6q z!2%i!cgLE;8S-5)!eq;ZJ^eGCbDE2pz9&FSO{CLX}lx3Vb>oP|h}M}iTC zGqz-rJztxWpQJ)u(o?YsWMdh`fd#b5m5q@sC+QG-3KhJ7+mzD1J1(w~f zw19Ka;4s|BU{Be#!C@Wv%^L2+Gp8%tK9ZTf>5*{zPT5_yCVE6ehH>TSa@6~ zZ_7H3Z_gX4b?WLQ-AOYz=(%D8)7<^5Xi~^`qY1WOkhRRG&n~7rS+0GH-yK1mXXJKIRH!#*6gD?Z; z74J3gZwQF6s)DDklg8NnPefm^y2O2o5L5VwD}Y9W>M#moM4e?oE`;MW$H$o?CxY(` z&6gULAG{jghW(4f9rmY!{d!*wev0PHlTEH-f#5ojTr%TJms% zx@jkgqCgXN#2d&TY7it)Ni+I@kvri=PSSM%4-fF2=+L8C$WJ3GWpK8&L^U^(ks;Y= zh1H@|gQXe^Qyq(>)7=;hVgUfn)qTzJk)^ny2leU-k4n!J7}j8T+w36}e516|t{$H5 zH)sQmz{WqI$*_QbgRufc3sx8Hm>f2yvw9VRq`O3liGrA41P6I=ptA25v5l=@vMdMZ zc!{ZCPV5oqxJ4RmCovbp9WG)=)J*A?5HtiWdJQq3GWXq z`xuI;wLb4cbc~0A{MHk41I+_|>2rZen^?pjD#sg{cq);y3c}_2g3qCMOHl-Kun!I_ zdX;fX5s*~2pPN%RJ_bFPQbPBhN(tCjP}fEqWxX zB4}#gmyw$Z!i$CU8Z&tm9P`9pcsi9&cn4PF#mezsU60mzJmDGC&t!JI{$2P6dA2;d zL6(pz=*Ii^kAj1T<=wju9f0?bBU>A^_=NKYNuB}U?_VuQ;w9V#==(iMC=1Y{8tFW@ zs4i7>;09s)|1kG1@KsgE;{Og14G1Pai%NBaQbBnH!IqaAgrmWNraUYP7(#M@Xh?FC z90&>$4bdE96nmwml`6JcY1NANsvv>{M3T0)(&}wWQH>KB}qGoZok5?Y+<5 zNlvu)-v8(GPb;(cnl-a#&6+i9)?=^p_hIg*%v|LF!>}@x?{9wxM#|59Su@U31iu^u zU9i1u9ld1Ka_6ZWq0l}c&WpZau1|HJLkv~!bH-kkPxIX6KFgpsX!Z_r)t`~U$2sn} zpryvH8tudxo*&8zjGnsw%Ym=gs@AcJmWn^E0gh7+ZGB*V_x%^$-$kuYeZXmnvo4WYjQOhgEvhB9<^QT!&TsL_5^)d% z_r5<7{;}_x@>2q2#|bFcVo ztYxL&o57gva5YyKc+GEyAzh|%+HsP!wtAqftMpbqsX*)bPAYXbwK4H$;uce6u4Atu zeS`BAw+yAG<>c0*7GWY1=(2%Cq%rWiY>?}VNM-p|5lJFa33nxw)j*~8V$WXEy62Z& zY@+n&}t0O!aS++M*^K&EU}uAh#V8q-fMO#E!v9mh~12DE2^cFh_E68GrkZH~9x&zBsk z7SmYlEE{betXU3~K}nHkydY)4FJY03DNE!vryx44aGC!)GBno68DcG3N|TRu-;{FQ-o3V3Go;ihm=bz({W2F_w@FBQ znt0*@q@DQY`tSVEX9g0+>S!NHMLdb%&+wj4iu}QdBD2w|J))R+MQU5E+~DH8rq}!g z0UK+Ix=Jd3$dhz_wPrw4$tNH7U+JRjHc3)aNeRMab}x==h1&|Ti*Pq>Pi-V!lusMY zu8b!_Pe3cNihZgH9d=?@ynb+s{)8|NQtSRkUk!Dv?88>HC zYX&MJ`Q#T8#<}RaO_G$fBBJsq`NW}Z&&I}@imrv|+P&MZv#T`&g-Aa6Ap}{ER%O<0 zlBDE?__fsUB1(I1qi0N&T?=h-xk}9nt7{|!g$j_{53YC7b(a<9Lp;oznC^` zC(Wzy+O8EQobhZjeM1y`sjiVsR9XNRAFnTWv(#;pq@#uMTb@Qu| zirQlrdK*QxJ@4y68Bcaq|EggX`v!@$)w%t(i2!t?g9g;6~F9`+UtGstuI1(_a$XDYcYTJ0-MJ zw^N*wYLk{^Tw@P5{sL@W8~;(l#?xQkv|P*wd&6%}+MmARr%2=ZOinZsFW(ywaJOGT z8u?xXyjSj&_BHaoNd@e&k^9gbfkwXghg}=_0lUXW?igqqdE*7z$Uo!NYvg-L+t?V| z7?8ffFFg&p5$QKh2{rf|a${2Ir6KS8t2Sg~=)nNv1AfLcszVRL_`xZm1M9!yBI>wM zxrY^2Gtl`R;s*$h`*r<8Xmg;TCYPU>A_lUVf;P*w60+as7|7Px6j=3gYENJprGykf@q(|DCjY6s`j_f zV@V78AGVJTlX+?oe%;`*`)*<~m6;B(jm>H2YJ+ zT5Idhdj2s4*7d2S4y!c7YPz3QKhk=cYkmwrO3<0d)D%5sWS;w^*AS^HuIo&t*BJ#q z$(vD#PeS(IXB3W4lD?CO-HMUg_@ri4>!A5RkeZ&cm(~ud;G=VlkZ3p6KcT$95Nzp2 z@G1m4XLPh8OJm}Ib4mq7b1L*LtHPVK`O$S*6|xSQz$vGmU)`TA5x+ps_%YtRx?|ib zjndpoI|1i2M3}~WERmNLrbLW-hR6$T+}V8f8Z(1+Bb80K=NRtkcm2#XS_h_FIW=|F zWm20irA_lnd*=IHOMBvMr?l3)eT=-1>?@6OSU%NJ%PgOwJ6Xb%B6SIKzr2`LR4H1P zid6%3t!mXO8tb(f?hXmkoQctNkp(xGsQEb}3kiwM$v~ACv;UP$p*I=ESWNtTU8{J2 zjf~G$Xq=tVWZW%}`-|PUFYB2*O{HZfOvTaIB~!hd-8MNIXD@`oWvFCe-TRh?0w&oV zb=M4bC)ujs+MG)~4oh!OlV^-6-$@&%s|Y8po)%a^xBzLr6@)MFqALgvskxI^n8e#o zcG3#k`bpU72<={CL@eV@;Ty9mq=EKsy^B4x!gEdgianl*Jtkzq38;Cnbl?o2dVWtV zVLXyfi?*`>SAW^gN1XV8^s&d(4^jxXjxPHlyt#4|`H%aN7`htIH~N`dKumwDpHr_r})m^RM6>JqLS( zEeprpKY;u?1g3%N%|VD4wO7?&`oKSJ>0GfZ{@_2HG{R(Op`7|suhXPF$@U+AWTl*D z?B;m1T$V`^3+A#w`4v655QVM3YgieD!mKSIX&3X4UrN%BbT%~fD>TEW#th3t*# ziyUK+qgkrnw$n^&4Rjk#+Rhs-mPFS*6^(4emju2Jtq*PAHPx@l$G$)l)X(2u7kY|w z1~ldLv(#Fgwdse+D?eHSo!O<`06LKH23?=e(W{#>qoJK#aaY~a84Yc34DA-xJJ-q` z3^lSVc#zm^d)1LYgN9&G6)mbHJFAWyHxJb1`9WZOZrW3qwshq9z! zkUf6jaB1s`)L1_9I9j;lSWZ7WeRNL~mx^XbpKnmGX(ynoUaB>ZUL?9lvRM@ava9z< zPH(%Vo^F-hSkoeD{AJf~YUfd#;>9XSi2mk->?a#*-gGlG)-)#`WA0;Jjd10F!#&)) zCw*ramCBAPUy4-r?hen{Qe@pGNz1OUk>ccBL7bVhJ95SjoX+7-Ei=2$@POrcXE2!U zQ9;%_4f#3}9t^#U*oII2r30Pve-WHE_?*$kiZ6y|xySP>KAzQk zRGaBFi?9vVde@dOq%6<=)oJ;@*`)ebTmD|T@Fv!ddJ-FD&e_GQrIYOvyysVJwEJWz7;FO)t8+4+5%C)! z;-C1q(P_aisxc5?LtBi>RIS%2H|L;)qg377nhJNtRX3dea-UN&#MD%4v2RfOsEOG! zB!_GwttoW3I;uLT9&75y9ujay>vzxxLMO;08BRFWDk~LQM4d~t!w@xfBa*Wyrh#uX zMRLYkz0I}Q0zLW)lS<9zNzFt<9@C|U=>y%EwxzpFdpL>gX_6zw#@ovts-x7zFA-Py zlzNt^th(d8Rn9lIZmm*`0HeAIaI-5wtFwjIB5m`lQuY7b13k3wvgN_-SFXr#bW>l;zL=m}c4Z~dGd=W12hApm%ZTx@;dE!4{f}HIiPANo zOz8P+BVYBmyS8}s$*!K~Ys+A5&JlTs-xL$&bm8|?7*XGa-T007_;qQwM7Zx&khz8$ zX?Fc~M?vpDhWq54su|$95pg{;zl*ZUk9d!nMLItVXk4(Qc zzM?*Lc0XcNh(e$f@w4-RY<=pv4*E;NvpzLlUirMDKJ^TJva(0+&yF4{JjB5kbe8&V zU%_XkaX_U$^?m0>CZhbR2A^DO@cjMF)QQHoV$Y__2z=agB$>pC&D{n#`CXc+jN`h^ zbDzp#p5GsYOx_8u#@HpWGeKFis(#&QQ59tZRx@k7=BY1C-Zw0_p zMZQ>xyv9{-_1T0KZ`N-tI#GMXHYOL0A>aQNZ?4B%LXX7Lc9nmUU;ZrQZ|bhJCadC7 zl-A;n2?Y?rD8`4s=A-x~O1s=&+WSDolUHie! zf4dD_=;g)yJ(!iEgGR`$q!l3XWu;c?Od6T0+K#&u&W^LrL< zOhULjj%A8ZjP8+7F1jkDZj+>D6GI3v5#gx=eJPExH+YTK90T826XRc)S#9g<^jVG; zZAcZ`sbeDrZrVYUgyAb&Pt{^ybn;Pd`d?M9#@Mqb$y8mw-><*yS4^T~+et9pdrTLe zW2=n}CV7gAm40tYvIycrWOv$#*wLt=No)Fi10cF-H~)6k385pY-r1eDK4_2FkTg~K zi#7@{vEg0`QDbFl^ffJHAW#ypOVYh+t3HX61g|~)IG!)I1<}mm)YNDHW~=uw#7vyh zTE|JDewx>XW<`SL`R+9Tl=}H;z9%#j49(YEO#P+zlPsO}R+XE;!HBM(#5%Rmb0z6D zPa2L|GYD?z@2H^lH(iUmT#EV$%_dvk7lAeY;bT&=2}Pyq^#;J_Yw#gejETYp)TOx( z@&&La&8W+E6KAlB;^H~^SBY~mR9UCjZ&x>A4DD-kqW_4#Pxsi#k1l)8V!Twd`he@Y zFZ(0NSg~rQVh9%Zy1f6&EE){t{jj``5fPnUQGe+l48K@5RO(5SXe_cWR+C0;EN$lh zfXZ~z7UAZqnKgFuD5CX#F(s$T>M#9>Ga%A1e^RX_Zx}g(??})XJ8+`ItS#iG)@?Gj zCP#>!2Hhm)j%DG8HRYfsN|c7J(>}m&dU$z*)2|~4>$$lMoN91lt{?Nu&?Y+$W@MKa zYH(T^Dkefav+OI06op~DgMgrZFDVZzuu=&^(*TR}#n z=~b?3+lsa9>IR(3r8hc?9YHyW>HY|npr$#fL5hm>Y129|qd#?OTBM)crVO8Usn1uX z5xvuRkGjblD3Mb#o|oB*q+LBqed^5*NYjQkrte5Sn-aNO?TN+^+jKlOhWPsJVCWf+ zSCrz%B+Ykpz`c*&y&}Ca)F3%H$I|4$Lk?_qV2cA|0uOSjhUtn$Mr*a%^`Tm+&TFY! zoz2++vipN?eH2fXI2h7e zp^ht56+G~vA0H90ipGBqy>NdBY8pcfsF&Q2I=NSB?udMd++%JS?&`-dVosp6>d?}2 zR@1iWHIJze>zP}9_Ic>(30eqLF@*zCRK;pMCI){I?|9VJ4kOv`?eheBfW!Bin zUr|>q6R#TGmy~zuY387dQHm}HM~QAO+vjn4LX@6FG}@u5kJsYPnIpB<^m}hbp+YB( z^?fq&9Efz&;p_F-Ucw{RC~%S9jD3POPS2r$behR1Cfs4CPL6h zGOL|FGE|j5a`wjbk@L5vk6gSxePp;HedNkR=_4a8=_A**`@C;WHZ8$PNe8~ zNW*9RgMJOetlRl`Pk9PP{j1lt3+P84Qa*Te^6B6$VkoovOOMrwnw&N+L4kFfjIs`K zT)dBT`;-P|=QT%dc7>$Le6$UI+VQ5TGc+LJ&i@a5=x32H21R$r5Yws}jFH@^UzgizKC1(-#*#r|qbz;JLcM>VZjh=TmI zXmJ<X)g zlTy7$h}0tVL8@sosYOUy`kg0sBmF3m&ujmW{p~Ns^w9pM!Un1BZyvS%T@r@PV^PHL z+MoK?Z4yaXWeB$aTej2wKH3I9?RaQuD-#gX{v2;}s%I?Cgo?DkpQtn58OTMm)WOGX zkf3*cwzD(Qy<0>r(LE#7G@iE=Y+9n=|FVAze_Hf)DXn^s6vNv-(-C)k}`DRp_{#5_fJp5fpuvOdbO$*&Q7v?2Yo}fuD_bFeC>yB<;)^>x0<~{>m>-B zZuw&hOeAuQi%f~NZkZHN1d|GPsmx2Ud@1rBKH2ovE89(X_tffBFM1Etl~2s-Q_thE zE{l-mmr+^n$lxpkBh@JYGr-(`oZ`Rc+*#Q61t|X74u$zC+PZ#+;)mp3LXv+i$yu3` zLdVzsme)pJX=V8=wBl6WcR24TyGSg&KDC|{BE*#H_7pzd_-=4DKSqWPN|LjL$2B~1 z=*5-tiMv$FTL4DNR(>R_ZN4kzIZ#|J6h_MG{d~OQlXR3}CX&h*Szpv*vX;1#4sza+ zbiXuEed=59`X&8#cS(OshU~hHo5jHSev7xds;%&01cSmWO`NAnEIgBn0no1iy&Hgo-zI7ksEvZ9HTIKaID#s%D?y zR~o_lc!F1b(pB(3usq@k&d~s$qF)h|@^b|@>n~MWo+J3fWMU;_Kqn8=Hfn4^rH#Y4lKl^X-J3S#-W_X`8|h(mikyN5c0jI_UJx z9w}o_U->Mnx?zNzf8t8-2sbixaIp+rt+rF;_o)$JxrlB}3U#dAQMK*^t0GL=TutLs z8TTW(^+s(|G+j;~%Z(QwB1-(2h@xMgbrYptH~U+-I@Pu0iBSAp zDfp@C_HJ}3?WlPlvd3IW{!X(S2Qp|=FC|qsWJ;xuuYH69iaskN_iNqmXjTsj)eoBV zStPJMgFHP6U4MEezBHB{?Z*+CLGQLD*M~~UqB?%GDQPwiP&8yl(-H@TPx&Yk$bN!jg+KKVZM<4q4~~nPIqb#*^4V zM%KMpk`)`rlVO%@$u8%1@CgZ)4>LG$QN1(dY-?Z4y$7OS~tB=C|^YQD0tOp13Y0`3%M!pi|Teky)7kX;6{cCs6eTa);K|@#M z>QYz!H!ZGbZsa$9yyY@S#B&r?7ubG(1#3W#4yVDr1;%r;>r!|825!;R!OApsjd?qj zH*-2mTn>Iu?hGLSvDz3>Q#Y7QN1H_sNycc&BVT>%i)I>YGBuIOs}<@_eTIa+St!#d zdj+el93+rbZ_;*!RGL&rW+#Se{T_KpW?d7hrMOUxvw*|p3<692a)Aq|EbmHO^MdAg zXfzneJk-f7_hRsCxOJ&Rv_i63HV6HiA5ano6Wt7-N}c4>zq&aSoeZgOyJ_w(E+Lk= z(ks1YE`=t>-YnXb{iVpEW$EuWyq|tbDE5AOMr!6PAI7 zGeQlqviCaULek_ayIInOK^E`!Blb88otX zQ}e}V`i5y(q!ejxsc2`+*nAr)?wtAJ4?5$m=FClMm3WE+*(ISPm#2Vih zRXD;9@CkdeE3DeD)Friz!rZ!?=%80|Oq6fnbq8U-;fYxN9I>Pa#U7*x{ot1pXDg%c z`4}D4=P^yI&+*XJ4q7zw4A1h*p54oM{8m$SEhCdM+BoCcJ=-1rZ2ie5vU;s3P65M+ z$O-1asYCgdALH{|5^MG%Q)2n3|nz~4xf{s-B zK1@HSlSd}31LW74^=FIm2B~MiAu+~bexF{x`%q6t^q_}-+<@)NrUXwYqj7#7=9hg; z(ORTj2sR%nu9U&5g*?pXh>N1L83RwP&1ij0GCRYkNTRN1X?4eG>30`_iZ=K@=DuN# zl{kt$ix>AOHayjL#SU6&t+P$>zO;d@le(o1XdT`yZBXke-O~EEnk`<@q{MT4CmfaO z@xe-pkG`(Tj`e$2#^X>+KMqk`7XKagak4)B(X!I-+KoBzCTFOhHIJ9Ye$-*{ zMym!&VC*+f`kGu>VfsvZ%^AAJ$~Vxap`?+9B{~@$i95@6n>W;i#}<`pd)7r{XJmqV z+V=17_*Rx!fLZ5Vd7w93oWk_=$E$E#@3BVKdV(=gTArUm8pTZ_Z|N@3eUjlYj3hKU zLH1DF22`zk>%7&npDM8cQ7WAe32Q@df#7VeWRmL!BfIGEBVV`a@JFim_w{vnXWQAC zLCKvR@DNws4pa$%IDPGW?FX%4tzR*Dq@1bet(xc*>3AqjU8Ej?-l-lTW*DePXg3}~ zCOSd3i-e8aGNuMn@9K_$6$SjWesFb1f9Ip)jsX=okF<&@`Xg1<9m6W@>W)PfCsub1 zs<@G8J|OO**4l1m4QpE+%(PTLS@2bIS(}{T^Cc9w%?KuxwT%xZRJ0A_)cIQ`@zS;m zD(H@o{W;`A>$InC1S<;Kz+sMEx@zq&125`-)pqcPj0{Xh20Z@Dvf&(i7PEA)VA`bl zSrX7wv>I4zF&ZK9C5JWDUL`+y+2KXyVuH+aBQ5-%37g*SD9MUl!x|8e_V8YwQfO zknxGBiI`qvtW!5nBwOl01To}i>O4)W)M9!aQw!f*!Bf#L5&UKOM|g4Q!&Q{KrVEw1 zlF7~UZA`kms)KwY-Se0aB-*_rO}axu?es2Ve0E!z5uxK~C%b}?!6Gg`LYyj(47CmY zT8Eh4)V>S9Y(cZzp*awwQArI=YO5SU5C(2J_c=5h4bAyZIdGP26gk3qG)4Z%XIO# zb;Cb_2K1PSH2WF9bei337OZ|-H|F1V8{T+=q~yCPg`|v-l&`rdU#BA45tcfgM$QSDl$mVL zOE+p8&j?e;?XRSp-MQ~bV+-c2u9&kKaRsxH%w49x(o0E|@o4Ho6V7EvQ$NI+Yrkln zE=(x`%TgPXh){#b#@O%m!vu}VlzeeykZ=-o>p;k23ruyS{c+Pel4Y1@old(Qzs2ab zMfy`zc}mBpowVb}w7!k861Oy6Pg!rIdmPf(d+$1q#W|->n&tk)AY~Ijvl=NTXhcZU zXX6^Yx}4Ij+)}69k2$7|?#Q`Le~L-CtD$L~M^#k8&Z)jES13m{H0qQ3)GxXkS`LP` zGa7j=I-hePp=RO6sUSzSJ9VLfak(+{n!(6gHW}U&(3V~udQAsmvs7W$1S0QL%bjIo zv+GiS(8vTyA}F0(BTd=d`fZH>Qdg6`ZvJcTciBD0=*48^ zhgpcn>Q8@Fgn&W2=l%ZrXT~1BB67vnulMRg&&g?E>gQSJw;Y>gvdK`-5Z1cf1$8l=dJz1h`>WS&m)p*-eg1Z z7JRfk$qBsFI}b{wn|v{f(No0bA~`Ec8bhl2HZJ+^ChQ?8gdphx*iBJ(hlHKGfGSp& z^3&|PQ+3uO>jCiK{*txNk^dy}8#{DAAZtCz^swfG)VcNu52Qu8(r{AfP=y@LVq&847sZWIU2A}vNVFYM5P#OI zqP@>m-Sm5B%OGBtIv5(S%E96m2Vcn+Y7V+&zk9mPb5HYs=DMfLO)x9&=>%f}UYEX{ zp(fi*8MS||^SP%JA&b4(rWx8PwKwn=#1uj3+l4T>U)K^8D?A7eHpSm?GaEo=kZArJHf1wp@jLr8KonG@XjE#33 z3X9kq?`SQ9k+?Ysfsg%s-thzG4Z&(}RG-@z`)|c`skR#ee0H_v6J7C>8-C(cyRB4H zoI2mut=!*gT{)cQDc3x{b*dBpb(i5 z>leoCVvy)S79`{}mk<)T$w0=1p;rO8lm7~n*ciL)ckZT+ls}fY`qTSr z{aY8Ce9B;e$KfQ=5dHF&Jz_+?G`IMHp7JDX(r@TWMCxhK(BHi#?Q7mmld4P?{-60P z_B~g)`<}86p~E{f4kkeEE;#O)4Q!ngNPp^}KkU#Z^}bQqUz zXjmy@0c^d@!V=3Lw!8chpqKrmAT1lKl7csq6>eiqkN-)|_(t9kloJZc+Kem)Xl9v3 zi9zrx6Puj0E=RIrZ~fUn-a8}X^&I9EMVK8?=QL;hH|jLyhZ`qKKM;If*5Inw%+Kv{ znap4-DP?2quPtsYgP)dgOg3M=qDJ9? zSh4jghShl5SMrTw&rxynu5_FR@@>gV+b3kx!Jsj=&?TB}TG0$9;=SFHda^eygQ*7g zsivpPZ?3(m!8)zG#^lV>J#%yGNgXe`bHpq}%te*WoW(4h!BmlR(!_#5qXOEDqdt0{ zGMR-&^kZmc{944VO({97Woul%4RPI*PJvqp-gL{0*EuMNx z+|<2eR`k?S*8V{|%Ij)g6{nekW2Rua#>E**dumDgP@?&kIYP$%=od0my0BbaAiu2< z5Ku{bYnAj3^#Nrydo7?kwDV#r}5<@abWH1B^ma`ZkUId$)s#&=WDVX1V;EdKjyhqcjO)$cT-n9X%Ip zmXs5#n63+CZ8bKa$Ba&3n314x?@tj;;lJ24P3n9g965$a_llx?`3e+&P56 zt^-U^=-ztljsT7R#vJ@LaED0tpu2Co!)t`FOz;u|i+wr3YMA7J6@jogWBOlX>~gg1 z`5T=@CU|7TK2mJgsyeGl{)|8GF{3kOPGl7GXpTnSWWLj`3Uh9qi`}EWL@bz)0oIT-5LEK$pm&Zvya{F>}wP163xn{+!l3&X*5 zuzDUwQgEYsN=tq>)x6Nze%UOAC>zYx76K=q{(u%{%4dZC?d&+Uwj!KEt>?L1Rud)L zT>(}T9afSr!7AdhdKgx^L@B4@+MO?qRjv%WMvMNGSBrPsP@`i~>frbQU&N%yFS+d6 z=73?|ITQ>dyMF;(#`H9jJEX_8ovx%Nkj!vXfi1=!oyDwb$>nv!91MMDLGWmavs{hW z=(=jsLdE2}SJSF8Q)8qvzihgbFD%XSoOzNMdMBqZPp?JjdbxC>F?J5qylCh(SttOB z=&}~w<*KQUpZPYwQJ2}tWR!%y7_aO}ZiA!#5o#wxmAIu)%ng+E9-OoAoc}`hU;DFX zy4>0GbOu&A$Y9Q0^OYB~V)^6?p+0_%xZ9g_IQI&T#gu!@uc7A4szzvUqq2@~Zk3t5 zG<~-sgrtS_Xih66!FI4xQJ2E{MzRbo;?A=zc`S zJ6EZv-zyQZ(?pu!n})^P>a1O&TD@G!-BG{rC*%pqG23mJ<6yRq``;1X9mk!uop{IW-4?SU z!SSOe^LM{2W3@~8H{=qGhG+!avKh?_9Zt@R}qex=!!N;rkJh z6?$LCBJh%K$mGrGDB`UmoDDkW`!z4qa*l8n6xzB*yGV?%L%v@?4L^o;w~jQ|%az!% zO8nT)6ohp9&z}$~sex+;$m&Nc>dB+Ut5iYqSuu{fIBydT z+@Z#-eu8ZKdhb%Wv|acjPgPRBmUV@-(d$~V^m|XEYsqM^*%Oc3O;I>^)L;nc%xmDZ zgJS+(XFKcFU}wvUu6vEv>vp=({jnR@*So)&TR*!6r|mPy5wxWa0W!wlek-Os9NEsh zOjNPzRQFXoX+t!ljoOnzbST}H6b{13P|;AE(~mRHNBlAOwB}4G$j2}^5&x-%mx>8u3HAovq#?Vj${(~RwL`I*S zWsaQJxN@#WBsy&uH9dR4r>6B?E?ZnD$G@h!$G<)zt0%J=<#hI7MmWCc=s+YV;=YAl zIV59*J>wfF)k%$-RPN5aL3|rir-sC}(7$nee9|&Bzx2r6ND}PqnO#B!Vu2QJJV6u}JQerH zS3I=@e|9GNd=4$&Rj@ku$7pIPkN;$ofEzacmv?#K`nSVpb7QDVs@>CdA&q+ffnc@Z z#;hgoGv>2EPS&cWw!TKVAvs9BfzKRoWvXu6R)MQQ`$B=PgdJ~-qQwol2WFoaGj8mt9waHd?j6{d>_{x zR^i*X^)l^ST8JmKTtBU8*^!V6`%{nce_!ngu<1( zmEpjnoZ2_N<^^~gg`+v1D&Wk6Wv;G}xCz~vUvj~3>u(iHHFem$bHA%ct8zqLsA{C% z9Ku72vZ>x9dlgpXIj8V`t+SlMoi5Zx{JQ5Qf8Fe=Y0>xGE0q5@yIcKVmiqf^!68?P z3`MCHUA?b)B_D<{XpdMVhpWMsMpT!#T*{RLW{y z&2(>LLS4!*dr1PMfdakJkR|PL3*>`b|{CBo0nazza&*1 z>+`YTiVRM`vMDBKjoeD3s;H}60-xvj0m~-fe*zhZLjPf2pTz=r!<^c)>-6%6`11>3 z^K}vWcM{uj4T)c)PA=luROgYiVz87MO*FJMcA7aLMW7qnhGfO?YSb%cq&d=eY?1_U zThn*&)?n^W+;GRb4e|Asb^Ab*RlGpkX(Xmp#pCO^)nhG0@+VAj^GxgZn;UDSfn+8n zDG9FG9Lg>{WX1~TLW>+Z_$0o_ISg^1w2L+bF7u36uIXw}=f9N1pvt9w5C(fsPgc6V z8`EFxO2YJ9Wf~mD$L{gQtLkGp%xQKKXKn8`OfiS{20R_3SV-5?Vh2MX-gq$d_s5wM ze57?v7~{Hhv9{0wQ2SLPnqSVu+Eh#)jaQ&&W~CbQoMj01r|$?I5aSE&cPuY-kfekB zCb@uR`(kPQCb={1Puy;$vwi2(8lB=p1SZr!Bpr|fnKBVWpmU+e^{|-(-2jyR+YXj__tmsEM6IMJK{pN-&1cg_xf$_4^#b?jm({cmDOEk9@juxsFe&i!DB`PDq#;5cyT3J(T;W z-5NuA%Fg3mN7=4n(oT3LjqD^&EJbc7P8>a5tw&OqiMKJv@>P@CbM*LatU4GH+PYGb zh)})g@pdE$W?dpPdwRjvF1^5+-BVexMEDZrn}DrJrq#SRIkH)Q<3gFx?&@{BJ?r@< z^}z$aDLzax%gh01!uCXc>Pyeq)T%M|7NRKE`ZKm^k`AX7lCy-y5zh+1`o*{EQw9%w zXcFD0Z)ZAhji#J-SZ$3*w#|utBFrOwQJwL!4eq$*G)-_a^2HZ@O;d_4HlvG;-E^U+ z7$^cPy+C?`(Zx=J*WMT8>O&3Q%qWAxAl`_d&3o_1 zdw;IQ6~#ku=@o2K)6%crU#mZhh~7AIDPD{7)kYb>JwgJg*A zkpVe7`uq|Fn`B_jj&e(zUTKxBpgs%Gr46v0M`j3psEWtU=8;$|^#Sv^k;i+?BMStn z)#h<4k8922HXbA9aXXL2=5Z&F%grOEn!3b1V&bVcm`98^b&h##&fa-Vq}aY>oP7ym za0|ePnU{>SvUiUA^5jb=PQGM3iEkYYwebU%>yh7T%i%Wx<%t2cZq}=a9Xh7#LDCPf z(Qlv|;>NR`TyoZ|u12&{n_)Qc+ucgfQN3DysM;g!PFnSZu%h|;3!AT^`zU6k!Aot1 zgX$-!Ocy0eR@7UPe3qLmN_Udwa2%*kZbwpP(hwf%1VO#!qNH(ZGd9xxfxF}0c;0Jj z7Ko!wGor6Y->aSdVeR~Ou1uH_<+q<>a(luNA!LQ&L)e?A_FAdBCLXKJ>Ek@cYIFKJ zk4IRDkVkBsphSWsea4`3&QP=SHpw$t_=-ki(g~uo53@#}I4ODn>od#0EXwe;udH&V z){03^+F$OTCY4v26`Q4Nb_!1?MUrIG(0$}QgYzpua=UvD%O^4T9TUCDj%JzwE)Uc? z`HrDx*UQyW$}HQQ7^uritKX<1)Tci6Bb)d^RYI~Eq^WS?JD9h))=D@h1`<=(y}}@t z`T|&Q#aqApZ$0XX{(n~sj<2MlIPBryX>SuDb~x2RTA2uO_>kry$F%<-hx@4qX>Ib& zg)-0(Bv89lr*>HN2+v*nm)Hj>PZr4Y8pDb!HO35o);TNo(W#hJKCJ8&h7i&*!Hxo_i4CEa+DRg8lCt8n) zf^~0`fXn&Pg0E3S?$6+@-QhcAf*?XJU3G-?{o(&I$V73+hMPy zYkKIy3Hx>SFxrMu0*V*O^^PMc&pk-Y#~#kXCUQ`P57++6W$GLk18~Dz~SB5{oeo1Lu z3Jz2JMbA|HOcs;QBTPD3gW=y!=6P~fE#@3uj}a=?hCXGu{gm0{@o|T$ThgQZ328P> zp>6YjmA<22PWq1d$CvGUr{6eMJwnHc9Y1Y|5pEs|5)>pQ*b(X^LV>muiq2*HzIFPY zYpAr)d)13^((7R8Q?}qav63c*e0-?w8hKme9I?AhchucWd&at#RDFR1n%@%(l+%@)71 zY)txj8^je@>F3R`tZ84LcKyugZ>G(kHg8t_@XPP9t@+vYqXo{L7X9bU=tr|g9_34q zwCsKV>>K;SkLc<(f32{`{mx}FEBeW-=tnc6?@o)KPJs4GO7^7RN8VwsmbP&5v_;bv zPrGSa?kgJ;g?{h~hARBX!6SDc$Qp-bjS2kCt;j2@u&0--jO3S;g@*=k`ZB;OxALu{ zd;a}swEi#8*TtUMG-r0s+tJ#;YNy?n?^1||p zaG5wU@EzQfn#fm+% z5w-M|D(aufS1`wGE{fJc?K zRTqwqYVB_P9ocQCZHD^Tpo;;P$43g|FHk=ZIZCSQ)Nov{HB2V2*H8gzd(%fUiC2Va zf!w8Gd_%abtfb6Z8YwI)kfyRqOIC-=N|r4%54k*f_4XwNJ2hR-SX}PPl7g@`4`1Q* zE?W}p;RRaXS=UYfYVPdoW`xAlrq7!*%XztEa?bp@+0M)O$)VYyIai0SoqmIpGGTIP z&YbJ!=o^-V_rb1mOC#kgjJms*N81*c7@sBCREVKNt+}2DDOzKPD+{~kaM)ShQC*za zP-{hA@$%VHSNW6rx(SRRQdznZ{!9{8B~$DY>73=#*(w4UDunLJmWRn#?g)@b(B2n; zOuC#Vwgu{w(QK>b$Ft5~FSyDl3j>bUrAKP@O;bSgchMAU>@w)~E zv-2vi4>Ni&4q)_%WjhGFppbD&Ji5Iyud;AuWTjnR8V(n@?Jt(hElx`3jT)at8#EL~ zqx@TfLiprxk)Kx(o33(v7Nsi-zaSbZ zE5*Ig{gA5W|)`ZD+cO1su6HeLNqet6wU2bDw7p}}(NyIVP9xEc{ zR#sNpQ|VNKMPbWrcY~c4wo01hgN1b6`HQia8(ghX`U$Vw?yBz5tT;&5dt{V-WB{JmjxZDDbEDek1KME?!v z6^)iQwew3>u8b5H5=}~1W-wwTmf$d4W{R=qttk!L!^Wsa?5VC0mk$#QE{hb88IVYW zS){1IUK*Y(5)L;WD%gDfCK{xuo*K_!dTP2setS@DPVV2|wF3=m-GF(r-6b8>5eQGV zZToAHFj1suga+XR#snedXd=Lps94D4&ybRUg4WP5c(j$Ox&T2UgjTxg5>XR8`@&}F zLDa7YDrYR5Y`av_F75!?6O|X+1!Z)rS6nh$q8|;O#VMONFW9r`kKz~01EM&=gK{K; z+nc+^i86F{VHjlO1vIegoss0!SjiWN24qTvA(NeE2t1Tokuu?CYXYETdk3hl)=2yGf%y;;f1(!wIsPqgb0B6gQR*aixBLnP6qYG8HA zXu|Js5d+tFX2<5Z1MaOczE^b zDefo!aiR~&`mY2dj{DVa=L@u?rXdNKbRHn8^Wv(2bkxcjJcPonluRKaUd`j;3g9Ky-AD~-4yjfEu1$?o`>a#Za^EoSt$ z7cxj+FEfwDlchb&RTg*P_QriQDl#U5B zNqC|Bdyh{N?W^r;9~BpNM6TiNAYA*?}9^4zSv|^tWqJ8w zi-i?yxune1(LU2+CB|AVYe&;rJ5p4*%;089$hHikOhYjHNTZ&8c1tr*Uq_|*cU^!*zP_^~>ZU{pdQMjy7BKSlwvrq~fJG^}HpaH5U z{_*lB$>l8vNzf`LpI5LF8Os@bnQhpm;j)#5j3abn^hq}y9fN=hb68pk& z7ustH2Mc88f?Kn{@|CaHjw~#>IZu{mC`T9e=&L;R@B-0JqH>^reNp*zn)}r zt?`;KgPSBF+~ncqqv(#20w(NK+|SLOBeN{%W8tRu!sN5snb^W0j1VK{+uORjtUog?}-j5>@<#V^@@{47L)QXO4%nJ^m7T<8S(eOckux{1g58 zFP->V{Kx%^{Ks|WU(VDApXoKe+u^P3X|rrh=gRqWsk6@!46wVQJR=2HUXp(cv;L)p z#Rbk1iQA_V))Xl&Es89s{RiOa3cBNsd9db72L9&J)vvjBrc5DLmf}U0MkKnii7xWX z2*^k=PRes6Lgf1!&cemC(z2^7uPH86*XS*sD-T+ePRw7oe8kDRLf%V$QB5xLR+Np2c8t zok}LF>%T^qC{XC;<(1zuU35GnuOe@LX#r++NoMw~pQ+c+N0%szCM>HMYB6fd)(|TK zIG~}{mAZ3sZDi%raG5T$VUY7m@H6&2j7L+-!}&I;>W`NwN3RB7z5*`8%H6c7B1>_2OfFZhWY9$(YP>?go$5)!~ozu})sT#=rlw z(#&kpC) z)n@!?;*E;A><$_~ghL7-c@fQtN@avC{5MA1m4yT{#y3k|7pEb7QAtT@ZZMaNca|Eu z=O|`^Ze6`#bm;ndqrWmH(|!E%m&Tkxt||G@;vYP`zmMmtCm{ay;VHN%TwY3;=5%v6lb>OiXFq+=M+AvA-^zkq zmO=s?BwadFpx62`dH6uDO=J+f+vlX;x)`@Sx@@=doc<`C$6{KLn^;236*u24zpLNG zc5xz$l;d0E%FXZMf>jQ)5GS3~Y~>}$UHv;NUfQ7(Sl>E?NxUIzgqYq!oXYUb2?hLf zNss?5w#=H$LfQ2Doc|XZ*{8?!x|4v!h-DRX;qXe^{XeNoSC)4nAh964G_ri*@Cb~| zf26S&*d-&SkX}+yvU1_@Wp=m!FCHm|F4fg>SIQqcYPzG!8MIUGT-{kr?lZ3q2a+N+5DGD=|Bx8_}s=M4idV<>? z#sBQ`XVKZ{B*`T(mX=`OU5=TI4xFz^CW12fEc$8r`90ImT~j{Kt(w!8!q7__J-WLM zNIu&Rq-z^%dLY@~gh{Y&1NDk#c&EtjtP|Spp21O@B7&rXK_LcX+&hzuTzBRnGmcyt zI0}YZGOD|O#K}xWn7|ejLrCZ4L=2mk-T%x?V0opJRrJ{{F88n!?OVN+6Xv*8&!q@o zf8maNrpxv!-||ZQ2rD|peo1WzJWic{JzU1Zot8$icz>L+=UbMKpQuB0|O_Noo zZfbQ@u1HjDbkUuIgXpbZ$?M}^ny}50L%TS#Qp0?v9ED5mQp#m*!`T>e?24^5t0%Nt znuGBU^w|j_yBp3>NOM>cROT{$V-QL7Z)4a+xf*~7sx0xCPh{<-%PM{1P5pmzejNRg zlPbARS1+(R-V;dp40`IeFmthpBTwVJr%U9?^uk{2Luld9%afs(Cx^b9DPZI!1#5aX z6UVd??cW2n-$t0)XG*Wm)CVWH?ZK?fo`SOd%=!4yn*aREmR(1yz7hNJqwns$g5en@ zaK7~Ir=v$-u6g@EUwZqcN5})pJ4kA2{NxCh>xe-NW@hayof4%i&?%b4S#G{iSy}E} zv;3i1CQ25`;LhCC9!&f=dHAIT4%Q9xdd9lU*)+ICcSMNYt!2gZJs%M{wO&;yZ5_)x%Uo})cW0To7!1cmz+l*dp7pm+{pOQHELTn8tGo_ zOqVVv+cVj^bIv)K1#1WAimK3+)reS5H!pKl*%Lm*PD8JMEq=yozW`9U#7Hl&(?En>H_G&twIceXyCVwV;%;rF=c& z;ME|nl6^NJEf~e>unxI;hIvg%#O%qrc8})DD@KvbPKci3QloaUEYvtEpApuvoeJn` zvy(cT#gjsNj-Fw4lFW;@EKMqZgRhIn<-gJVcLDzmblwFg_91;&B1l%DbPrm4q&ZtE zJG5fPYs{PwexgX?P;F3b0W$OG7+er-R>NgEiC~hFWGD&d5C)5V-rrT zf^XB=_mf@7yrpc$lEZB#l|vWXiQruOcN=lkb&N(fhbPb%hx3Tp+43fr;N6sBvm)w} z*k9LPE;9~g=%ruJg4VJ%iIV=dI3D-^mwpppDRud;5AX6{2YE&BGYcl;mIF)Ms!W#r zmUDcNdHr}6dsOSPJ8%h#^GJHg=vG%)>z|`#V>onXH{FE}-q;IxR7{sz>7oOzG{1N$ z2Uu_M^X=AO%dE+2OF81v=arP$vr3AWJI!~UY_#XlSoVzYD%>Rqatwe^8J2r5Jm(IdP#}v; zUH=H4Q5ublPBRo91vqeSfD5{btN zY1DS4Hd+_?2#NoVadxG>RdmZL2+KAcU8W$n7}e?;w{X=(hSW*9Z#TsByZ(h*|U~%#X!bnF0+P*t>MdfZ)j=nI6i!Wo_%=nE__oo z@!!w8y!&zT{HHGXzdP^!?~cd6$bZ(bMQH;E4C-%12>UB74eplZ6_tmrin0h+|Kfe| z_|N$73I6*%|Gmq9Dfh?Y=kTA%YH_~GfqM2z^Na(Kks*z*5D;W7rd+&YZU7`;x2fhC#J*&I`kTPlw(4g5m)FXVE5fhyM{A0SA~~av-8R< z_J4qDEba{9zanc|WVtmrTxwmHUtwKavdWqf4z6^&x=ML1rP(??rQMopjYv6?vehcG zDpQ`ba#FUW)LJuA&gnbl-gGpdVp%Pvo$+R#tyP_IE5ouffZKRKdv#}gFz@fwbjBwF zH{R75UjUqYcW1m3_`7Ild^6CxhihAa6M)UYSAiYCXX>Em_Ov-0JL6M2|gxE?t8bgrTUP6YlA zxBzHvg&z2mN1+G)0k{)*^7o(z&IEPz@5Os zk3$b!4D0~@8aVh&-hTi+@EC9b@MB;laL5zT1Fr<`1Qr3Cfe!*ZfNuc@f5EcWZG#?o z<`1C-c~O=xd3<_a0BqWT#vpD_4*^?%F9EIdv0I=G{1li4{Mwt)1K$8v0Z;rd=z;eE8-Py&TY#?t ztqZUdpbb3v*U$sc0xkhw0IULz1#SgS0X6`)0$YG5{|5Tu*fY=uHUqPO*EK^ATnMZJ z76G>c?*cXe$Nvs`U@6f0l4TtQ+Q7N|W?mNX2f!u3e*mk1=f4d-@FHLXuoBn;yfOy; zh4imh=z&Y#fgX5Y8}z`cW6%Si25trZ9@qf9_^;3dbAi?f@IV{*CtwzE+uxuE=DiC& z@E~w2ux~r`zzOd`54`w&=to-CCm%o$y!7wT1JgU82mTsZ1swJd=z-S)8-V`}YymF$ z1p13CYZuT4p7JU5zz}c=a1F2u_%v`UFb-@0Mvg-d{L(+6C*XV?Xah%fLJzzbxCHnq zunM>=4n1%eumO026_2+7vw+qp+6QO@FHVWavw&-WOMp)UtAL*Zw*trZiN_m&9|2o{ zKjC6rYqVv(4YYx&{KRDz@G{^Mp#0=z74W81=z;5j4Zz2MEx_NN0R0&1eIoS0KLN9V zOVXeRF6|FJ@IK&H;KKu;2ae=7&Rc+cf!0{`3ABNO2SN|L3b+IqJsEo7)iHSe^y_B)-+020d^HFbg;qxCD6qmCysf58Mj;-VEr0pM;@h93Ala4K*Jx5+I6o;)`mUkkioUOc`9I32hfm1+Q4UTh8~z-3_bAACC~%Mmq8EQR}MY! z{0Q{GCxAFX>qVdq{24F{_!e*pFuDqQ;P}p&^wSuZZ-XA#XD#%= z5x^zD@xUtJY~WVl1HcC0PGAf0CqU~;;%cA`Yy)NiA6&z0d=HP!By&=B*omp>IGBeEvb`f%kqV9*+SJ0MkN@OTZDpoQJr)5x5Gt0{9-V z7MQyw9^VH1DXn{9uUGz5@UMb@CxAbyc$>6E;P1b+GyeU4ytwtxuI}6SoBccyZ!u07v9H7d+E;3_dg@$(d|^6v&e6nwcK->2B4KMcMC{0#xTVW9N~|1|h70KNM6J=L?HA$^I#?&^%= z3KIA}A&>u5@W1E`1!yD|D3+UK+0cB`sjN)7IOR!QTyDeURHfu1nBw0e>6#Wc_zH_$u%}@!NLa176=b41Q#NXZ#F* z`Nq7B{ewRjJX4K?e8&6~KLo!w20Wo$0>3ID-&F83!6(!2BJh*IpW>&Vm7re>{vz-v z`SDjJ@LRy20e+w#e{}-C8+;1*&3=5Jf7c9RUx&f30pA?Jzv1DJgCBQaXZ*r|{)Tz_ z8*+kWO}xJ|9tzNBdGu4kF9yFRfUofIi@?7C{_X(&P7l8p{1-QN#_tc{@A2?kz~2i# znSOSIUk!e^pWf%+4})I|{!4y*p0YRX5B^T@7y0qw1b)bgru-3pe0~By75szHU+2g7 zxyF-!5%^cYe_@_#o`fAI6a zncTkCg3kq?%s#h(4}%}&=f7OptNrc<|8Kp}9|pg=7yNPX>w3Wt8NjWjz2K*UkM@FJ z1pfYB@LY&sZR!QT1^h$c&-B;dn764v_y@q>;>Y({=IQ@1_`~3r1@OiJ==cwQ*te3~ z=MWsv#l7ICf}a4MrIy6_V8SDnZxQ&Jz2Mh^zo{4gTfi>|pUggXgO@$4{sI5p&-34h z!C$|*GyZ~KzCO=-`Z*5%82DuUV+aG!P2WyVKNb9k;FHlW0>A7#$?4aEKMp?G__YOm z#Y5~J1nPI1SHIohi?$>m9}k0H06y9Ha2)(%@X6xSA%j>O1HUAozlEOurh;z+pC7>A zH!#xW=S^t{~ zen&6(Md0^GZ%gIHjqhjQ-}k+G!cwqy;oM>nP#F*lKA^$SMemu{Ds|D8q?#o?pBG+T! zPJOxy-GYSN2f(L;$DJkW<(nrQ0skqyll9Ynr?Phg{e^z|r3wBQfWHg;*8=n8S$!mj z$TtK0j%Sk77l3~m{4f3d`@E(F2>k}|CEJttv&X&FEAAoze?`t0ih@UMU$>Mws$LO(OWALs@D|JZvID5gu|;s%}kPUDeeC)lEY;4K&T%PS6d_C@M~fIH9&Up%UjI3W=zgphBX)4y~d=#NdDv zVu*^^8jV9VPQ)aNk!Vyj#@8vL)c-tZpSo3rHecSgzV-dvrT0EXlubq5i!w{v+Tmc%FCHb?*S13b?*(1%AQC9sEh@ z0zRQ&zb}QoaNzqEmB0t~?#O*sqW@!8e=qQ_fe$Uli~M+7ftNkix1Y<08&DE>pY;bm z5%{QL{Y8HAF5rjkB7ZmVOLmceG4Shw|E^fSXOmmMmB2fm-jREx1b@)Qdx8H6cwh5( zEAYDC^*w%lRhXZ^hnKYf5V!psfzLp!(pM$r7yPhY!23VDBlm}r{J(eecLV?9@8L%* z!N<7xV&ES?wAA;ox+AHj!( z;Zoo~FUCEWy6xKt{9nNPx_@*5pZyZ{FiP^v0>kpVf&T*dAtiXhPrVrUv%vcrUn_zC zbr*Oq@PF+B-wM3!<-VT}d~m>z1%7skeLpJHANUo(?<>LYa`7(Ub${HEyR!se>EhkM z?*Klh1TVDDV&Lxp@9RBsCGf^qcH~Yg$uBQ@Y~NnsX8=FB1TXkOwgP_)_(3JOINF)t zhmX&I_ceYRf!86{ZTI5*@@Ov4Kfv38_cgw{fp-Cayg0w-H*WhZ2L3MazSf_Wz+TXB6_U1pXTEDaClvdwMVMZ-KvAg1_e4w-xxhH~M~l^TF_kf%o;E+6er& zz{ixVU&Gz?s|)xaH}A-eEiPXkU!?xPKLGwxG46TJwQn)->;JSvg7ow6i5}TVLf089 zfqxC$Q(V61J2!tX@HgM=d;Dz${vPmXaei;mwciH^!s~zD#rg-l^Dlk-iMxP53>?c$ z;rT+Qx6~i_eZa>T<3;;qi-ErcytNpY$4ixeCGfX^Pb|4VjC1b~y}-@4cjRhH>X&ls zw-xwzz~3yvUvqI^7WTh`@n3>(a`8ssN50!P-UYnu?>ln;EVkeCq1!**z+VM^X$k%l z7heo~_xE<>ep6EZLvHying4yn36$Wsx_B?}Ifzm13*QQS%ZG@2D9Jz2&F`y+AMc|b zxw4Y>HQe@X1pd;;J8}~Y{N=}|ynd;AnJc-uemd~6ok?;TL6e*@b8(_O6pz~=!!ro?`6B+|Yv;H!aS zm=)Tm$Pd>I{0`vf72}@5KH*~E#=rX3zY_Qa;C<=u1>OmKX^H;J-1glH{BGbAit(cU z^YurJDDdlxaZh0%t`Ydu&vxXlD8ZMw`n!NX1iYsN7rzhNryKb2|K7#?2R;+{ze@6N zbM>zTUjO-y++iiS1PV}pFYv>G?_JWrlU4uX(bw1t{IV~0@_T{LybSbN18f}W{MbHE z6|L|r@MnP^S&Vz+=9UGo19{Th^;@q1V6^b7X!Z!_@)y4Q5Rnc{J?J!TVH~2aPeN? z{|&sY7%z(B*b3bH-HzNB#kl8FH@~k5aY(>_TY^9A;*G%1+=2J^61>aByMW&Wysz=o z4g5~veT~1xz@OVi{*}Pr*hT(c;Q!u5{;j~va(%zQ_~5L+7WfS%fr9)R<;}VJ zdx5{>%jNDb(SNtAe=G1a%5u3MmEiMT+=mUeUf|c3;LBaS5%})@TyFo8`pt05?*e{u zdEfcFf%Cf;iDLcY-cs$i82GEZz*hqQ9q_*9S1<4z@tuxE#ri$6vBC9sEAZ{Wb0zkF z#PZwSnKuSr7a(8v<_Mf9(49_ynSik2Jw{2HYf2QyJ z8-cIh1-=FNd%*j$-@u~v8t@-_HqFAOEbx=6bGa)^+V^tRzBHM2=z`3vHM!imWaRtE zBQLPTyMYg>&E-0a@gEo3a53+8V_m?@`{i=ql;B^ucsKBO zvbjF@Zx#ceSfA_j{-}IdHg<3hghCpVI%pF9qJ0|EwGMUx4?uzApwod;q??QLNunxWBIi z{xa}WOYp+}OE2(#19Q2XO7QF4`fUZ?1H8PXeLQaa_=X|QsVSG6=!Js(`1OwSQh};J z@Kr5n{}TO^T>V|ZUjm*j#*6j`yEXnuG43h&uNMP95#RZ`zoh)T-SSrg-;VEkEiAGB zeAoV7;B)X@ufFzYw*vn;zVr1%bC~t>;lb(O_zu`HCHjwW^)~|FV>G_2QewXh5a#a! zehYAHvliMyl8*47x)_BefgiZ0>2%2U-R2H0`GXh@t9aBUv9xN{(-*)JXVa) zDA?Bp{0ZR6Vti%+?*_gOc(@p!DtH#W#lU|B{LW&0(#2lSEd?E`A=A7^E_YP1j7OXd z9D~mQKOXowC3s;E^&h|=1HM-=UbKf9z{}5{fj?1pr;+_`SeSF3DfmCkli3j77&ea+#! zsDE~@Pe17Mz()YzT&&+y_`bt7;2#2CR)YWBwJ(GXj5&w){hT=j__4ddX8@nS3w%EC zvw-(CN0$P>4ET%^`wIKGcL9F@cwg)I^T6NOMfux+Z`lPNYR4P^-cwS3!H+ov_;GV` zxtmMy>)rO70sLLyx0T>Gx%hnMKdf*4OM$-wd`-z5U**p6yMWI>qVMvb2mT>&&INZ4 z7ro1E1O6UxJPs9b*+y04F9Zk27rVfR0QVh<`B!4!*{*#vfFE^KF89k4{7M&}5B!gF z`?hZ>@E3tUR+9e_H~(G0=O2^HZ7a6l^S;}@&jW8iHkW&_1i#nCw*h}1cy|ddi#*#b zv^)Gf-F?r`A;7DFFDc1?v8#Uu@QZ=3^+O=PhI-fdDM0=6fhSJJ{4QC8Pj~NeOM#zs zO5gU~1^gc1eXSqQ1Ahc~sHFYM-S*oC{C0eI{iqUrj*Ew|aBszT+CM76-*fRH!0-K0 z-|x9IfS2RD@O|~qeBiGDPn76)T>VRdKaKCu2TO3ji{AzOzB6;VXG_|@*KPmjfzLS$ zXAqR&54-p_;9mmA<8YyWiu|OZJ#l|IyKj65@Jis97w7jZcJsrCSqJ7Z2fNuld*K_Fe!2b#yxB5c<)0BB?{A~mNFW`OF9}kD- zIl0mpTnPhF`G){c0WWz@^{gz^ANUI3Cl;6Q5l2N0c=LgO0DM6SE*(I8De&FS&E-xh z!6lH3_+7v+1%5#ZF86=l6P^eDDe&WnPjI4Fc_ujNE4`DP>=nKVPV>^TsZQIa{;5v; z#pU}r9j80(olaY)(>%e+LJsm1oB)q)Gb+X*9_>7w>qkBR_wWCXMimKM>fWGQ%#@8C>yyssY$5!lV zOkbxbCtp|i*Q}faSidD{tk<}$)0gwT2!C2kedmDbBtMG&w3re7PVCFC0oRp_P=%J& zNh77xGZRAO`2j8@_{-ZpRV%iH?UrAs(|Nh=IjJ97OR;w7^a&9W#4d)af8Nedb^3ls z@PF%c-Y%{Ff8S-hw9C#4D|JT>)YmckI$2+5>FYdwJzHNd)z@qFb(OxZ)7Pi<^>uxH zPhY>(SHB)0mHIkRU&rX{WPP2buk-ZvY<;~{U$52IRrgzy#9iy+4 z^>voM&ePYk_4QJHy;fgW>FYXueOg~%*Vp&-^-F#AtDqD-7wPLjeI28(ll66$zRuIv zv-R~-eZ5v+SLy3IeSKPAU)R_7^z}=9^=Eba>#L;x_kRYA2Bmc7#h95t@Mn6wzA}G# zz_Kfh9Ps=)G~gZ)R(L4vMD)6lS8?Zhp`Lm~uD5KE>%2$hI`nb5)@+pPZTfonCP{mG z<+}PQxo&(*u0fgt^0=*%zSsA|cH>O;WAKYy5IW@O(@(`=$)F~wa=~sF*-#4#&IHGCDE}ay(M6sIXYublNlK#VQ|vipMqd6_Q2e`4PXI|3K1F^G zZW5xfZoXi*+$GX^{bPQUm!G~|1peN~_z?ZpOL_TWw~72b z-%g5kQsl>AT1k6evr2#mWqf}xlgJ;nB`-g1wTS#>m*e5XPxA8l1>=@o>;E<{-+Qm< zugc1G=TEWc>3*iR|F3@#iHCPt-xr7G<*$BK>Y0t}l$;-dmE%M5#BvmZ=l=}XCOJ4r* zc_M#qiBusW@?+o2%a1)?lqP~mxw?17h3o2Tq;ay}s4bPUNA1efkZ@)D9)kSq)M1M4Vb`Y(dAa?+j`0Q;&g zAUjZg2iO6ga8%ad*#ee7uoj=z3b6f+ibT@zj~Gub-{SmZ64uwdN4QmD`L(mgE4YW5jVV?uhqu@XMWV*s7l|biE=1M<^H;bmi|oNXLrp$aUKg3bM5{`yh)iQ* zm`bdUTup6lDzP>)lgJ2jDDte245#Xm%C?P>9TXdF9t442Bl#bW!8qQ%9zKzulIO9pLVr`=sA0~MI!1-vL7zZHDj&n|s%idJn?mRbPB!+_-c!fH~ zo8$)$X7hCj&Ex2-PDNYm0os?bOp7NQ*h>_75xJKul8?*53=N6#n3P^16-N0Z%n(P0 zU^O{0cK=oo$|@6s1L@E$uTts@S&`M-FZz|34v76%&k(nzwej}+Pjhg55U3i`@BaJH8@_obnq#34I-eb%L zfoiTDB*Z0JvhBJgbQGKQ94&K%WDK0K!HKIGN0w$s2RF~+Y1%^6uDW!r*Qp$t%7$N<$GfM`5yXy1(Qbk zo2=lvk_v9wxq=Jw&1HMlq7|)M$R39W1JEy{Ez8D- zDPp|>gUdQdTh>z8QPxS?w)Vz|Et^0(Xnh(4J@Gc=jarjoRaqBrJX!0qIOs{_H(MXW zg0jh^+wD`%Jj*DX(jPKYtu^SMvZ>_Hv<6dV+6VZYYyFhvPCFD8JHfi$A$>dOWfo8U zDVtUSdZV?$rJu3BQu5ni{!50J&!GOzY~}L6`}iztMiql^g5nn@Lj+7CoFjehu) z<(02s_l0@OE5DU}5#}wge3cU5EwB6@CBR!=`MnefY(SyWzyZI83hN`#frCgIRxh3r z0tb^0z=BI~^AuY93iedzG3EMQV7uJ!T@*th<+L0<6S( zrDjhDTNYEYX{RzgBRXqXRNV7F@8kKtZv^Hr2+9Em)&2CLrT#MuscA*j6 zf)5TerKHL5e##tE`+*Z_v-ZByRkDw&o>H=};wmNk-3$RyLP{wa#)+@qZdPDSSTnl; zsA4weCHfi865H8_=K4^a9oY;ehV=~?c2qjO;Rw(%(jm)xBybDiK8^}PCJkN?2ge9TRpQJz8rcZO)sw)valUZ`D^0H9i{gCa2&PP~|38iM zjU$*gn~?Y7INvyeHRf0(mc;qS5gcH?fXlKt-#CIp@f&EkdB^$25o}e76>$#j;4qa~ z9p@WIuuUb_#`(q(9AR>;T_5KgM{uOFZDX8o9Kq4%UMQ#6@E(U$sC+hhC-FJUydj`o zK7uP)UyCmv!COhcHr6~~@#Q19iWQGy!TAuKS011aHSAaeH89D27ntJiljkOk z3ch?K`SKAQZ<3$n%SW(7Xuf;|I~5(~%SZS!mKo;DM|g=M`SKCIT#*}Kf|H>k!B*tE z8~Wyhnji~?`M#V40#kX zfxUq?M_TE1v)Uma8MY0X@J=^_QeS^i^^IpX#B`1 z=50iKaG-msIx_k*z}{PjA#dbZYP%UG)JAJw0&U}W^o(dNZ+C{e^+oGQo7Oa}Q_+5; zJ@&DubQ{quX|MG)G)C)5`>Y!~K{tF3HD%T*l<(gPe%Lw@`lF5CfS<$*KY_|Wv)q|z zfIxI4GpO5gbdd%^W*&pKSUYdF z0qZ6ViC8;DqE-SH#@gQkowd5rB(Zkxjx<~2!HKm`0^Mf4sA!J!cI$E$)m{O9hjp2v zcLzPynkIa7?o5j<7;9(K&ZbWX?^O2PP!X5{G8&JuFsp7P*m2rpSocySLE2{xp8~pq zWd#iH(EwuE4m#!57> zv6`(tp*PXM%CuRhK{C<6h8SgSRe4E|Rt=YEp!#;hyMr0xFCtMMcom<@+;>4__yOkL z3gT@d{5q;ywv6UhpNs}K%nD}?^xE^fjf#l!|Jw5w7!^^O1|v~?MU19It?e^F$0=N) zrbk6$E&A$e>pj%EqT(d*A5>MXNV2M5%i=(`S~3<&`uu!)yx~pljf|Dwz_!3B4BBPM z=#YfTI2DVOsa=T!&}WnY2gO=V0<)Iga&kHX|s6OHj%Powiv&E#YHoPm`kHRxXe0!M(qEIstE$f~+1-CF3PbgPnA z%R;)f&_(Ii!m^NVEp$=3wa`WB)(naaELKmfn7rH1t zLU++C=$!OO?k{@J$84)A<5N%IDKy5~s*X?5uBs|korTF+)mfOFLd)c=>MTsos!mo{ zCTCSA&5_9|v`o&bPBl5LpTdHw39Mp=^<&Z#Y35X`5#3#-UTUN1=zX~4U?&2f5V9i8!{Qn2doFluV#JI)(A9V zriS4%HLBe*wQRSnkvbm6$&k*(38z1RdLw-ehLxFa#iz&c{uDBqN|sd~_y?4x7NB&= zR5g_KO;_T>Oy7l1PkIJEeR$nO-m2l}A(46?&8Ef2uo==^&W&^yW7AC6Lm|rWAW^kD ze-}2$)_fm?T6`=ca51vatsc~aDk$5lTMB(%-6D16f-JQ3d38&n&#PMseO}#C=yRc^ z&#POc&)Fx{gIQFEYP0Ggv}TgE4}1;PLrG7z_)t~dN_vX*4a*%y8>U+Cl5XR0pDmTR z3k+2WGzTBRs)w^$;V~qCLNMURuxhKZQ|L9-jWt2(#_IvrggD#+R-AO0bX2|J);O#} z+S(tPY9cHytD2=I%4TWC0|C0LCbkLLyjP*TT3fx=os1=?xwiI57B#2~?7GiE8tPV7 zTPLk}1I!URZ3JEeJi9jZE;G$OYIql56xGIQba|jbebOH9ffy}yp)ypdJP^dEx@~4aWYm2y za2zrf3QI)NW7Ajj8EmT(Mv^5=N*2TU-u4d~TeAdNjOPk?62eY9rLCwLhQ2C2M zs2;u32-A(#@1au(QTX~ilr+M0WA$5iIXK~;Ln_-wL&B${kn9LfpfJy%&yHlbdt{d< z$-Suh1`mH=xIDlI*6<44H5wWfiKNjm;!1M47uBF{OW`_{(y#})9`R{b-woYqvw!7b zcvZ2w(RBT*9%f$aK2)QBW)sMObvyd9e?PwYM6IVOlN|~=Zatd;UC*oux#6D-QdKr* z)OAfez!f!6wDeFqFI3km=$Una2Zvt zhD6K2@gNOr3)-qhdHOuonGkPjrY@gVj+xLhh;+b+LK|Xl`#>%W*P<&l`c1eoG|a?({SxhM3tk1U-S%e%sCptw;#8c8#&p3%H3Ji=_a7h}yFYr|VBbGnvEHir`(8XHG@6&5>LiEN{E53p|<3(eJ@R%Nx}}V)d6m z#@t;!hIqH=?BRNru@`UX!7VU#3qns-a||~cAEW#<^Chq>@1inMJs^U*n%}8c>bLhq z4*dNV?Z!W|=bB0!in<_=dzU|RRHGmLX6Dq3ws-mFqZ+%Y)$nl6THgD$*2Y&k4o%H{ zKy#Z;KkiJ!^mx>p$MU}%)tuQ&3i`1wu<4ky<{4(WhsAoAZ#ha=Vil5uCO{MiEVP&` z|7}(N7aVu^`%o^h*NceM#vieF-Z8HM7aL(x=-*TZ&+^$#XPi3Uz%Q&%N9TH$AKr9^ zVScEwgN(uaA#?L3lLqp89{d|57bqWc6no)1a~n9P?=I{)Zc`nDqNS`JCE;0qSYsKS zrsi`dA(UkV`LuaD5~@cKRrK=Sz^5zmKa3WI>SxSAnmvtazD{G_nlrHZ!v?wG!p380 z;66Hi5|5x}&s;oYw0(&=W6mMzSw6LG28+6l&xoGoN4BkDZSP;8u-R?bPeSS$ zKC5_^AKJ!uXLIW!h0Pp(({NFGiY|FPRiDSQk6ETfj>N;j2m#O2GHquOKUWmO-5BH> zGYiwbuWoZJAfNsOeM@aRJ%XLCXj~VfqkKjMT3Bz+ybcC;pLUJ}9D<4W{eTf24U*qf z31DU!{(bPFLpuDk6)lk?dV7w$INnC?nUw~Sbc3UVNNyll5=6p1UJrM1yv>tIa_7c7 z=w!<2%{%Vgc!#tTTmdJScj+dQ5^O@UJWv*(HR3k)eQ`SaQ@KrjUs9vEO?}%r3B_&d z`3 zrrXq4rV=ylUMldb#B7^xQ(wS*2o}z@={EJ*CjH_k*mRrvLM9DfU}FFqzNku^Y4fh@ zi<__Fa;{CcsjpJ)t1q(YHua@UHuz6%x=np)^9fuow&^zY)tE0MvBc&***Cy^8<%A^ z-KM^wCa2nUHr=MaR+U&`({1V-rV^`dx=np;DzVn4+tjB6HEg;~eIu1^8*RExeWT4c zaOp+J5H4lqpFwr-bC#*yroI)duX3CEZY3#hQ{Qc@xwuVzt61?U;)WJeM}Rs)>{Het z%&sT*LL?OT{X92eICPsv=r;9@H_4CCZR+a~nr>5Hr=p{DoBA(PyAX7n`j;q@Zd3o| zirj!g$}==1bRa&a0Erp?J#mTBZCYMUj)(hzf%NGRPytPWs;fwHA25))izN2}t@L7& zAK}BQx|JmN0jfoAR`s(W183vTI@sQWu@u&B=qG#6D?u8{Luv1&28e717b zkeJL0>UgIR$2xatR2ilb%^@AUWjAo5+@cGvP<_QMy5OywfJM1Q7hI(TxJ4JdM+wlc z6TFuKvPBmt*d53k(%GSYSukOHQb^L ztygNeMHhPXEUJ+$y3iWik4JUdW2C4~w&+5SlPz0xp^c#9H{eV<*i!MCr3A9Bech|y`6_>kf;VJAw8F@$Ll{6V1 zZqbFO4ge?F7T)`6SIIuAdP>Q@imR0Dw-N%Pgp{&m7*}|1(RsK<7oK?%fQluKGZ85@ z>YWIeDcO?4@7#h6Slp6xVx(nD&WV$jEjcGaTDIhz3evJA=Onq5$d;T_Nxp2!IaREX zY{@y9HK1in&Z(ySBE!QiIj3$N01tQUBV~ueG}*C_>@@-$^01 z>?0kdWye0!Nm_R7BNIr=j(ud}pO9B}>?2(lgD*SwkxAssj(ub@>Gm{t>?2dSK*)}L zWGeZxV;`CJ2p&yj$38NR)sh|i$TU_TW3$V$`0-Hc1CI}0&y_K5Po<=N|MBUY% zMl3GtC-*dB3DUBs5v$-x;v%yz5DzyS;-P`aC7TWL`d?B5oh*p-%@=>B(Bfo?H&A`M;o)XOJbp70Wr3CWtUd+u^hhT70cN#= zI02&EY=|tQx#A&DjH1&{dB_uECPP|0)vS<$I#sl2uo6WHG3wXK-=0;(cj z+X^+r#cNwJiG3pPy00sC|2;lK zY<>$fP2FVj?(51ykAbBIe`QNy@K?4-1JZphv<&{rmcrn#Y$*)>%9g_57g`2?Ws3}c zy00q-vnX+2R}P^y;=ZmNN?P34m1>ZP`?_)%Z4mc$WgFM%*;0uY^Of)!9=fk9hqGEy zy00sLLQve-DSJ0OL8!5j3d-1^`#KfkSQ7VjDok43*C~fp5chQ|!s4>3SyE9pOS9pj z`#KfdO8v?Ooen)q{ahW>;X>1;!-b|3TAD5$E;L;_Txhy@(72_j(s)76shy-V(AXo8h7Jxhg@;p<}=~l8-!mY`W8k()pZuXkT#Dc;hyU zf|5p*&gaZJ6<9#$b9I~YBGUO>J%Y0(O6PO+NOoH7C!8S;@7Rb5k9iR z6&P$lfhdIw#@qQ)ETi`Jfe?!R0UU&!YIj-mR_2WJA-`6+^^$6(^Je{`q_zd?keO1q z0k09#%!l!mmuIff#nrw-!_p#|4QojcvukEY-r7qsyYtMsd7YzaNR?#Ym}d^4q-L(j zXMeazvO||%cO02-T+ykjZtyLRe`XJNd-~lQfD)!duKoqK$P-k9sAwa51q-NZ-@~ZP7{H%}Gp}5&#o)bBe`ZhJS2XLQb`30W zfxpruZVQ+faiA!ZHc)mRmHwU%6#Shk7gQk(>l^2teu`n9kS{emnezM5rsK5yajyJc zlt2AA_%-*ZfM@x9qwb&VfZaYFCqiervL`~eLFwKtuX{izO>4@#l@4}gja%Tj^cmmz zF(u7o!4CDL#RawVmrFCS?*CML@UBCH>0t6KT>)ctJg_4FM0f1fB>BarKjW%HgUd<( zPeOwO49WX`eDF0?L%)Ep`VNqm@(Yyh!M!G%eu1(*>0mW%MlO}@#mFU}&7j4yaTEy| zLE6D@XejSr9rowYe`VuUWDWfSWu40a`UCj7pAo(l9}YjjU>@%}RIhBp{UH5;_4o`w zi4W&H2q2`itZOq;Hhl(VlP&>?4D=b4O{Ns^sb3R+i1@TS1RqO<)89ox@2;tUXMb4| z6WQv(yxr{I>l4s6?{|?;vg240!f;lD2IIJo_h*4%!TO z_D{SBjTW^hV~qJF;Mr!tvwsr#%{Bv`{gX+zNBR2Xmw;!R0nh%ajQy38e;?-Sfah`*@azx#4XpBi zql(@?qb&mE&mbLq4Ilk5z_g1tM#qYEO9Y%49V?cKeU8zwV%@p|Sd5MpYn2k9W5rUj z&oMeyta~Y7sn}=xfJ>pmX6&X6$pQn(~Vz_Bm8X^Q@yWX*P$y zc#xx+vCmBJ8QOwRqeNj{c^ zZSy-MPDs*;AJ(zYNpOs?j(tv|kr8}r-jB<up{?zV2V2^&rKL9I`PwV;)lnZo=qGRh(i^ydxGe#$VWQii_#E)FA$PKV8DzVQzDD846t1`+j!X-u@ceI+EjCi{C zfNZSkNieFFr>k0dx~i3@tGX!mIX2{a$XF`&Io8^rs{~`8W5eEu0>ftPbF7W*fX&$F z*l>=msLj~t*a*^To3YQakt`}}Gxj+)ig_E+9vtW@_Bl5CMZhZdIUZpEu%%+3<284I zjxzQ+UdusksJmdijhrX6$pk;U%akQ%?|aiG8;D ziV|;p9ef@89It$s<*L}{_(*0@cj)*ib%%zr)aMV-Ab)@>zKVTLSRXT&ihWLu&;ow3geiG8*i`ptCk(pA+qW2iWTJx+%DQ|#y%(7InLYd z%dyxb+CPO%ht1gMM0+JcgeYUxOTT#KXbnJ5?`xNB;f#>j9!>6IQK{ym}NC6qeCg3J*qJg3+_BqkG9VEVd z4C7R;C>&9e+y{Uh{*j}Tq;%=bE#Ni%z^KYxl~MzIh(Q1 zsRU=qq3Xt(s^BD=YmZ0krIPBoQevM|l}AI=QnAnJQIlyuW1rI!`)o7zIjv)#{QL`Kvid9z*Kb>28_@$V5&L`14hT=ssU5gSr{-v%Ydos zR0GDAcwDwjhb{5Atld<*C?40AcwDx?0k*{BhOx>Vq@KQYJgzPAxO;+sxcvY$R86Cu zb8U&oodW&>TjFuaUt~)>F6m|VVxU#~l3tOI$K`mmbUf~ZYzK+QeHSFYfra%klc9XT zE{eysN1zEaHJc$*quMP~%XZ5enc{d{!qp#8Pqp%YR+q%%vMhgq`@xywcwE-ES~)bU zl|!>y9GW^Fm)bJL@wjY;YUR+ZRu0W-acJsz+%!;p&&n_k0ih;@Wmq~Mm(K^v_Ue{G zpI5g?UAagIEqz|yQs{FXkE{B;x~0(PLQ9`lw@9B$JT8msP;FK{gw{;5B_5abWLx5K zNl&rqm8l*^8>ZS4kIPwtcwEAWkd;cf@wlv3OyY3~S~?#0GSI3UYl6~^5|7K_7O>+0 zYr>?X>IJOEVHMK0#N)EKtZJ5;D4WHN$7PROI;NI^pGu}STxh!5aG~jhmZqx>7n)AT z)T*Yd4HueDXlc6Iur!^-)Uw_kw#3w`W-)Y3?Jr=DKR`=#H0?-`{=jbdR15J`5b_dk z>1f*J;Mjw@uoy%cifgDlL0wd=rbAQcv@OxJ&5&uf&%tM1oL0EewA38@3<~Z7p$65R zMogkby!M zm*pkTr{sFJndLn?FS#$7&+tTPoYjzL9>Id1YQmx{?(dW&)=3ek29~C z!6ri|$py~6hJ}oh9f0qnz1>eboY;%T`YjWnZ~EFMwc+ zYW`&;RX?icU&aLl@u|AwewpvMGlv`I8XsQw5T`r%%n^pURuZ$@-bQ}&zAK>`U5d4b zy)<+fE4ug!U2e5o?jXk0nyr*>$9l@YgQ1jvX3t-tNk&MUj1Z~l$6#CD)g=`rPgOKz zlr!6~5Ab1TKbfdh8G778=P;Bv9FfXd67b-wrkeyBD?whPKfonSO)MfxZ-Y@j8uTy^ zE0W3k%?o-j14z9Y5_!Ehfkx1HK`+-!rI(1(n>EU>0Bz(jOMJ#V7VfL!qCdG#T=YAi z=eRE#@BbSvdheC}VCuCiP`k2#_b}SMo(X^8U--;B?n(bo9QXfApM5~SRZ%u$0UFyn z38T-nCgbkou}%Z+wdJ%i@7LJyDcgTKWbzpfyoMR7@qyE@FbMHQ#+&*>Xx0T_Y5%#p zB|nU`>O6c~i{VKAvQ6NGwLkqvl;Vg#eLcF#GgJ0{H!DXbn=@W@u!n+kBC2g6lA74;!h`krX&9Jl{VHYNBrsEq8Uzb z#GgJDcfVzh_|tis&PGT4>7<`=#GlStx065pYp}{!p^D+fSr{0wUT1Z$MLPw8&j2%= zV;ew+wtx&6!H;lx4-%@mbO@t$3-hQDM)9;q3!Zir!f35h0tHWdwBTtEYft+==paWt z?IaCHJnf|EX>Z0=d)i5cwWpoO6FEhmcBjbG?i6|2ogz=WQ{-uPiahO3k*D1ePy2yT zpEhFfwDVXkr^wUp?Cfa|qM5a)U6JBxr+tR@v_s7!BOxVf#M3TniahNHP>p!nl^XH1 z)4^th|A>1DJneTNQ9*l*3aSe@;%O&4>WHVEblNHMv^zzfc1Jwzl+m7c4iVjGK`J4ol&~-y*wvnOM?C8+x5g>*tUKaaXN8&_ z@vL)l&2+@GPWeT7&-#G?!d4BMJ{*X`&!A>b*p`{I9{h0d703tlVTaBa%gP}{_q!wR zcXimIvz_xw4m)(dB`t>?I^U6&!w#Jtq~)+fCr4V`?~Y+IA?|m_R0(mvJ06t~_q*d$ z330zWWhx==cgL?1;(o_jid@pf{qET2pO6suyHo6bcZ%KbPOoZ-=-f)uQ0E>xx3T7O?xEwl-){rYuliYyR@Oj`R&sAd zLUGG*2T|N&_q#LRBwxAToerVtes?+*tzzh-m$A$!-S5#QilqBJdbuJuz_OUQ-|s@c zIYsXGcoT0~mU6#a%KdIB_q$c(evc2~_hQ1z{T^@4fp+MAj}PO0 z!f@z*kGGK>aOi%I59dIOI&{CsN03fCbic<(vZ$;>_j`O4^V0p!fv()|@zK8qtlaO3 z2;(rr%Ke_GSpqsj_j{t2H%dd@G!u2CO^5FHL_gA=2;J|AENQPp_j{tAw9ldYJ<&j? zd6~lv{6v2qCm43>LVkZ;v*ycfrkLsQl{8#nkxGW zobXfV>$Rzl&x5*_sm?+zQ=Nrc3N5uvbrx!w>MYbU)mf;e&{E5ka=*4abepCou+=*p zx=m9P*|k$0x=mAEe8`&V&~2KU#Qr_Np`#@=xh@2^sd~stO<`HH9lA|ZQ}+S?aEETw z)HK>T*P)9pHGMYt3!IC{-<$kJ4&A1y8KjpvbepF3CA|Xexec0%e3q%9EX-0qOH27I ztsCF_z(N?GFPEJ_8(o;5>Y) zp1uM^4f~*m!xr1S4e0085wC$A;Sn20Qj6g*3O98WY13ikZE7xQk3%11>S)qlhY_}^ zV^|_~Z+>5g#Ie*KR=(2opldK6)o@O?6goQH!UmDyEVOiVx~0(3>6SuAr&|ggEwprW zTKQbtRY#-;v#1V--p2G0+BQkqnI1}dvO`~Kx|Q@4hrZJEFxoKHp|3RE#z!1@90=bI zHLCHnuQWY;3+khSKhr-U81|##+N$g*CX_>$cU6#0X*l$iR)sjm0#2NCm~>P=`AVxpzg3J)_*4VwWe_#$ z_uInCS6c04pwOYOv^u&5prO{R>Zn*vU#ZY(hrZJ47{8z2?9f+Q9j6uAS6ZE*X7%

pH-R(pOsBMnj_XmDY~nv{S*KwIkVS%2!&~;8_9* zf8Zk+8KtkZU!x+CH2SF{2cqR!ud`4I8%vZ}Q43%S6}!daAUWhG{K`H;?7$%gasd~5Ema{TKg5xvpP zkwlkEj=c&wCNM{v zH-O&L%a94j0sImg`4{B-EP1L;;U%NehISg>PpNtML?vfjFBeqpF-VA^4X&XBcd+0J zZ-bV;#+9b~tm%`iLbbO}*%67;jzuMQkf-dx`LE2^{11+-h?n!}yAwp^09SMKG-|b# zm2YTtU;(Y=04($Ju6Ez|&<2a>zg3sEX!J5S?utM+4DJcN`HK=m7HcYEUQP3k5qcw@giBsF%W)i$?aOQRcM(pa0@H;i06#s zB-=_i_qn*wX1{I%x=(%qWNH!e2s@=|2Catkej1&*Mf0mav!{iJaF~lcL5&>iB6rXZ?gRkkl7l)mJ`hs~Gx8HN+mFe8 zbn?jTla$_9C+B9pyyfiYVHh)}i`0LAUH`*W{SQH@miOylXp{88KdKoBsb;`I;Zs02 z+(XOuP|6S2Rk@D!z@OQ3B_w1rk8>w;Lx$bnstQ~+R|y*HAc1WMHRoPv$N%OXcyDLwM2 zoo!r68*iZ%ao5Jfrz2V6+BlB+lchFRme}|pl;HUzZ=-5l@>Ju(oxnmGe#frzDmBj^ zDP|N5{|FLdxW8cdLp1A4lT)lx=O{Gp5dfPiIQG6Y^~lO9!@t(axmjiSzts*Z&H|Cf z{YI(tESJVT1xj$2FEN}vWq8^sXCVV8vdjKqhK~@VEttbUv*({QVNHL9<_Gto9H0Nt zCUl5JAL`^x>HUv%a&~qc$J;iOdOXX!i-zkG*CO6mb9swQqxmFec}Lah{lmqOqMP|f zE*O7N=wli!S`35if!9qgm6vODw5UL3nm?iDmlS%?_tDL;0q5M%oWbAM{5R%(T3Y&h zXaj%x#(Y3MY4#i@1?rn0%KaQ!o1S9+2TWND56>RS zMx!lm-oZDq-2GJN{r7BP-{zv9L2>prO6;#B@cf^>nCcGDjXlq3Sd~S(L#aPZE4a>8 z(1^a2g=3_}8G8Yd8@fh;HDrckK5x zH(~UMW~W5+Sn%;$S)!RdrMbUR&U_7XI52%m^Y(*xw)rQnW?zZsDG+1cYw~@0>z5IQi@4BHISox1w_YV&e3w0BqRUY-e{Ezv9hfZL@PcS(~%iri0zTVZ}>+0`d_WLP+(*YuQy(|9@SNav zcr_dD7!4LCb6Y=7)vE~ZslmcJ&^Cp)!kq}kJ%UtCsPo;SNopc_A5FE7} zEdHq{7V^}f#t%PH$;cj-atsT-P?vI^h+}-+34yxfvk>V12m*+1se6$lZl2gU)fmZN z95(0hX4|fFPjYj=kKDuP>@w%j1&CE|*eQ6MGUw2(>RCS57&(Wk_r1@9-I;wQTN5<# z&+M6q%GD(~UT0DOzo0bY)YHzv5}LQ9me>I+Ak2uIx_NAjgCx0rp)s^Ii}YS>j@|Zw z4E{FD1-dsvb{IEFM8LcJw+n||ku4h@wcdzU}Bux=tdcDyw1expv)8c)$0 z>yBjRiDD=Ec62wYZjQ`Hs}vUUZO~fxA(xTeNU{-v--6)3>J|Fj=sYvNjWYzMB@B0| zgupaom@R=hJO4!K4vfbiI4G_3*Yiq_LOTlTOOHYu4~{+x?Z*U5jzXJEP>w?5WX}JF zk(`LehVZP!3%PgjI_B)_a5RGYa5R$q!s>gJ*T2L^`Ueh5V|n?5(zZ}U{l0|nThjT1 z(n#kIN+X>=D2=pxP#P2NL1|352cK>HF?)VQ5N_z!j?m=m9A>kgB#>9&JL1|352cQsO z`Q@NA_UX$=hTB1qs}4#d_x(Kge{fKmKkzYfmPfrPhhMk)56(=ZO`%H29)SNC-hP>v z(IDm3I$5~M~V+#sNsF16K3b{(CkgEzEawP}+>a(WgEHe9m1dEYC9+GkvnSC&6?u~vz zvoC=7teLnee7McBH^5rZt`)bv1>MSz*22OoB zi%e)ai_E^U3hL81YRq1HKMRsT9x5@^S!DJDsvsO5X5alX1XA*qSw%`95ADO!pw1$L znn(Was@YJa=C`hzb!pseQWD6c)JP!DW~!01$m}(zKqO6jj5O8BS!DL(WXoA(_C_V5 zelEynQcT_DHVe= zS#c$hhfA6f;?UldSEA1%3r<}EP9*|)zH*i9qpBx?Jc=uUJny4NMM=3|TY^9y9zqtJ z`2sTQgRp37sA*4#BvgDtLd7Q}RD43B=pd}nkT_)IAgoYp4`_7|R%qBUEJyt`N~n!& zIS4B>d<)oe5LRdeX*mchG?GPS)lZ{@Mlmnr6WoKaLZhbu_6Kgmr#g)+T=p1ss_?(? zUjGH_)e$Y>ad(3)r;&xn^Y|4xjV#q0}R8lWX8ov+oXNg;L%PD+K$!^XwDlzEDCrujyAgDZbk-V2`3jD+W~+yEk}F}G5!wRQ zSXiS+t~wSmatrNKF@=#8%&%e!BeycUiYbh&QUYJ$aUyb$5@75?YXU zE*jx2M9#X4DzoIQyQnft&bo`nl?L_mQ_%!zIqNQ3L0ZnbizeR#Eoa?DE6JC$?xI!f z20804nqfD{S$END$}f_$?xJ<)p*sEmM}$6RtpNt+k6AmA#xk}f7H7Z9PshX(r1QtD zu@YQAA3y>6n6++dP*ElE`j@GJd&%(z8KsOWi8pZMzXg4p&dswBKjnagk0CCU;uY*FDMi4J~i zQ<VT*j*1P>dSMUI! zeXaKgf=-g2X>~P&t|Wbc)l2yl>4U6us54D^mX#)5MS8Y1jd?Sq=U8u1UY$gBxV5=I z=o<2mw05J;TGDf^9_Fp%XzaFrN11-4Pp}N~v!v%+Ny;}+et|Wb`umeU-D+c98cCmN zoy4*RkUrZwm-Il==UR&?-$eR+>p9ZuNV^|f`!TON#_l5PWtOFmv0G%_!@TN*vc=Xn z{Xwe}%9dDfGw(3!S!yk&d>iR2t!1Q#lU`;mW!@2_e_@?X{Ub?VZQVGjr0q$iU8t#uCRF47yVXK2qP(!JJZ(vwL)V|X^TA~9tX zMxq?Nm>M;n4cW1%Y>!rB<6_qmILQ95!Eb)I&dx%UkZEt0a~ICoU0BE1?dkk z5=PxnCV;5roHgXYxoYR<;HU%Vs-yfetD%0{r8+8BOUw~zIdHBz)&LnfaIRV%TdEJ7 zt4>gJh$DOz2-P2M%+a-kXz~+z$c;I=4;&qHL_>7U5!Z4ZbHq*y-HW{6M!KeOj1ID+aoP|b%t>ejn_(Zc$NDEpBlmn^Jb!{j#F<6XXNp^^1q zNihE~SgYz1O;GiQtLkM|2`;aC#@3pDQEMfQ--9F2@;;x} z6Cra?VZNGYKG+{jb-=gfeMvL>pJW{g?>nS;@?{8eAiW;z=1n#mAv@BcynSD#L=HLyoJy-4OyY0Epk{tRB;>2*A8 z*1rxQi+MR()F%fEX{Xm~5YIckNavkir1MTM(yr5s3D@bxgzNNT!gYEv;X1vTaGhRE zxK6KM!$SAh0r(5T?ym#T;2(B+(H-(1IK9?EoBQhkPb1;}I>0kf;5xnN0dt*ROsvQ| zy_j&FUQGN4POs-tj{EBX?<3DnzYf6q>R$&Sng4YF);#~~0IWEjUgv@54^T&leaafB z^^sh@DJ$+@^4y)AUgYP09YE3iW&?g5fV4ibtqfy9JH1%E`jUfxi6Z$W2mj@Y+<>CX zGqfob1ee|}IK6)OhXQut^!g7yUH7A$|M?FEuzCKMKNNsdYJ7PA3gJV3D8R3ND8R!5 z0qqI3VEY68DbY#^-jQ%nzTGtusUP|g0ZIX%dMt4s2xw2E6A)9A2LjsDc_T=Q&(5B4 zH4>G|XIH6wc9qI!mlB^Hw9I~iS|(tF$UcRZ&4IV^N{G!2wN%OtlkE`;F24|5J zzi9C6J3%YIXz*NFRQUzRV3A)mSmYNC7WqYkMSjs>kzZ73@rwp;{D0Vc4=6i|qiuL* z?(FW&+7ZnDjqSRrlOAQWg9O|B6#w2LP1ew$>}E}FddM4;4@AGnVLRJ&;MUS_LZG`Wtj-qDa8 zWEV{ivWq4kAdaz%o(E6{(AY&&Vi&FJNX>i#0VN~9U6!ilkqrWXAPL>lziG6190*=~6(_?Q1EOycKpbG-hoy=CdXj+d=lPjasdTg3p z8J(WUs?;u;HWvhx2KFyWp`{M9WKfE3;Ze%corpu|;%<^3Be{Bv6ZJ`Jnq5 z$_L%gP(J8>hVnu8GnCJ~kOFi#2fbcC=zfOs+00jqX!#t%dOt(?p!*rhyP2;R(ej>W z0jou{yoY0?7SZw^cC}hW%X>Hh)FP^|T13mu{R}Be33sAZW{wyOB-{B#3nV9mu|NvK z7c7uOsDuUbWbkDyko=ziCoGWs_I#NIlFhajNH*JAAc?=iS|C40b4r7saZL512S$=x z3nV-7UtILSMsTHKyTrOzem1RnVqwY^y?2qV2h)g!DK7`pK-<9gZNS2mAFwdx#lqCc zh&}f}YI|YgMI)~_@*Gk3AkF-(&E$8_Jw-l&iAT~!Qg#}T8jZ}e<%^cM$!5+Oh0K-m ziAwy)X8xR+KOBuW5sHD$e3hB!$k!&(Z!=dh^IZ9?Bv#wZNz6P?za?vIX4yz&p3lz% zyee(x6&=XDfL{jaJT~(g7XKglz9(KbnN7!Rgv`U;Emufe2AxII{3f4#*X74&mU)^~ zBxoGXJF|xU<>@!S_%uhRmdewyUwGP5MMida*|%x)v^A#ub7(KEo3KlFcL_7fBcV5N zw(Liic9DXAg;vDBfr6jM1$T)Hwj4?}ca##3f1$*9*f_MR9pe&BGg$RD?hOVTB8B|n z2=Cj-_B^-UJUJ>jJ==V8ULyS*CMFpBf-`w`n_w?y$b zLjR+}dL zg8GiEs7ZWQO?vpYB>lqgk5ZcLG3gO0GJoNj%QR;zPycuO82Z)m(e`{ukTbC~psqhW zK~ksgWl9Vpbs9+>{J;@P;>x&=i%IG+Hu_-7r}R`Ez7KKtxx?V5V%*{9k@_ANnFo#W zgApApvE?4-!Ibzx0c+gIQ5@8*_>~zsVF27X2HR)EART5#?LcC4xuVYfLQRaD>$rpX zg20xK`jk^+Jn^qRTx;%&8Q|`U;tPV{cd)hX#9wUi(UbD$_B|5g3j&VT-)MNZHD zVK5oVCBj>IAkGo0BQuSp_UU1YF+h#S0BY@mKx*NaP!oH+P#gXO@|LzXkS>i?+1>tj1Z({ z%t!0F;wTuvsEh9|CmJudm%Lo&(WrT^? zGQvb`8DS!}jPO9?*fMev60v2349AucCSrG>tC09NEF=A(7F$NB<;Rwhn?WG9jNFYx zY#Cvq-&#hPh%F;be7R+Wyv6Q7G{?l25iVpKSVq`hV;Lc6EhB8XwTzG+EhD=luQVWy z6vvb;kVTETJ0T&tvAtvi%LwzWWkg_O86jL6`~vjKc(k^$jIerR84*w|BLc1^svQ52 zdLLNhF$G~68G-+dI}mdQy922Y(D5ktMaLg5ImYqlJc4SKpryDpI0e7CbMcd3fFCO3 z-B$xJRtK&LD4zhv6H=eib=mpq z12k0EWquIyFrT5it_+s=044R<{BUFl96dHatRsB!-%yq6x<6n=U#06-LD&5W5ad3> zblIf zx-Q{=rRx&M=(<}0Gbm`4L+3N^Mie5k zuDcU*s-WvW9uwI@ny0$1t2SO+QGUmk7KD5UAInj-8#{A>xSsM ze?}pz>mCGrqw7v*J>mnD?qs&rb-Avo4^VmnVf6t@Ph?eA*JWAy0C8b9x^6ulmj;L7 z*J!*yBu()FDxbD5KI}&0Jr>zkH}2XMOb}+%HH}0hm(q&*0F`$$-)g)o0b7liBV{#ScDU7eISs7FOW10>Z2D79 ziam1_T4iR6(RkTTqw&fc#dEwWF6#%b(Rc+xHC{nbpBo}j=Z4L;8ZVn|HD2Pcuo~~(XpYf!mw+{^ z>$3ZduFD>_-Zq4-w+-3nO2rl#UH2pmyw!DicQ+2)2a?fs1w<0MF1eJ01@Z$23*_Zs zf%>09o^dl$ed2Ya1ZL!n)hyT8hAKW^Mn1yCBqPVy-%L^Q5}96!-<1_v3EXX%`D3oo zrynOd4otD~=l1Q0)vigzT|uC@+k7eU&pgWDLc%h*E&H>|Q(5JK=3y#+*mw*d9?8D= z$FZ7gBs*vkFQJxJT+bwrA@vn2O!;Z1yzZl|ARa|h^cQPs`z1Nq{dhy~(73V;me^Lg z|7dqxWcY=wf2*+uciR|uM1l{#NxXF{H1~k`;SL})ObBga3AMk%N{bwsZyEeOV|=KH zIKZ@x57||88i5r0R2~z+-5r^!{8*JjSD6N0?`hdhC!)mviWK^pNQT}oI#MH z=g;uJ6+H=C(Q^)%HKOP7WIHTFG5_ORiDE=g!dCPoY(-DPR`etsi=Irxq9+rv=*dJZ zdNL7a_AP|e5 zltW|DlZk#SdNL7Ho&>Gv$(CEulk_Nh_972= zejt_Nn6d@2=*dr)&BgZ4ebbD5tJSuh+V3o5Mp9^u8`1NmAf7lb!)i%w+0 zaL~R-X!bqwL3sT}K&a%tM|h)vlm)|E$sZam`yL>3=Qc5!L9$?I_B}x6_V1Dm_dUWj zLWZ(nc=rV48d)&B_F*Kd$d6M+aw-dk_cB{$!Eha6l?B5=`ySz-eUI<~;uu-*Ie>#@ z!ASN!@*UC46uz02-1mrPbEqpR#zk`^mttHrmkWzdum+$GmIb5kKY(n$Gn!AiLWyi4 z%@ZOEC0B@SIfcC>vvgNW#K?ltqITp|56FVac7D=pL>8rkE;H zV5&qM&_xPNO?v|pfJlL<%|5_0(+R5-n3_RYrNGq8Pf%8+ zz|^b{kgrl;YBuv#3QWx*tot6Rxh`Op0#n`0S1B;nGZm9brNC4V$4I5XR1dparNC4V zCxA+U3ab>D>S3dwQq3?u5E7EEi#5Y^;Z(FR#ZGHLorA^1@=H_55izm6|9BvXYj*i% zoG~IMmah^7iizbn2m-~#@*9beJGnwmc@;6SqJnFxiis5&VybI)MV7F-W>@5df{2L~ zdBQ3tR#XyJF|neG%cF{k71hjFF|neK{i0%GMS=aIVq!%-@mHvrSkbgIno}Blg2y5( zW}-6mtO|>nEPGjm#Y~O^p~7M&PgsS;OeGt^rHqT52#cw+=>{G=4k@K8yV32W@N>Ls z+0g{yNDDlLgK+XzfX6UD6RyJ|lO3ncx))`$GJjjbrwLDBen!YWES~i*Ff~q#E@gM~#wO=> zEH%C}r3#&;veqs}*4pMoCG%m@koyM6s6Q0OXx{`f_NUdNdLjo9@i_gMCm!0G)&r`YA4A>hE}l|xR( z{(pCm<(D6aZEt&|xLNZ23^Ky&4@=8LQDHzwS=n#!l1V^ES;*EnAp<(fB59cfbd)6t z2O$GG%2I?iprb5JSOYrB$_Z;gM_C174d^J7%j-0tqfE3o4d^JV><5kpbd*(*g-#6a zACM>fM9%_x2f0b|>^iB>@n3N1E67RlX2w8nW=v7f3@+=(vlMS;3|0vO7mz@1W=zSs zls6JV&x;PXrfei8rf@MqD^?KZyEqa5%X!h^b_Dgj=v+zjf zTd{)q8fF&i&5Zv-tk@akYn^h46(6!9+J-{CnNh;bLUS`?1;h#l^<`A75KzSm^5>ZI zqCw`)&48t3^t@;#W6p~PncKfjGAdRG85JuUk!#M24zIl#i7feXvLt843T9ieg0K}U z*k%ng3-xBkaF=p0@c?l;oQRKUv@-)L=S4?yGh+qBiVsOt#frUAV@Aaa$yKqUAH|*M zMf{ZE{S+eRyy&R=2^6k?Sg|RdD3L9sc`8;&u8I{4fS^PO2@!}DLCI5?FbO(kM2qMi zReo}^{0;ms-9AuJ64l+q3^(MxU=S3&=CdQEGMJM$p#*pVl zC#yMG^jnjxV}tZtlPpkv({D|3@J)=#rk(LX&x=k4^&l6XKMYeW;%f}aumP}~x^B;l zPQQOKmM2l*%yo^Tz?thBMS(NdHHI&t_sn&T;ali?b6sP|*m`qaWA16xVy|n=-NORr zy2e~36Xv?c+~DgPbF2BpT-TU;kOa(ijk)op9Jnum!zDTT_~N?8KO(U-w;5Y$&Wp}r zJREynV-BA|Ue|aP{yQRXY2OQ#l@-R+;M> znO|kDYZRCY9Ik65oLYlcRGh>*Q*{2TI9b4Bn0tzVYr&ab*BJd4O+5&Oa1`F2EX#Kz zQ_q|#Mh9h!-synVcO%8^nwly4@i(LwnZ!WtcvFA`s)gYv@&YjjY) zjj%=s<%bj2=%D-v!WtcvZzrtLLHQ2C8Xc4$MOdSQ@*5G>=%D;))~nG$`7wkwIw(Jm zI2s+4?=%D;$p6;O0LHQ|!H99E&4Z{5r9hCnj@ijUq zzcFEr4$5yrc(p_a@#LHMIvyjn2 z)p%S(oQPa)2SDDUtDV%Qz^l4#4j*y#JJ>#|a#Fl;tLpY$ks~*KRF|9tP;dIEp0q{Y+R&VBV_J_Rbqgrpy4tX|wbr+S}!m8k* zEZBd_##{57UDJLlT2~PLx*+;>LGeq>P(a$xb*#mkWe9hRuus5bcey`E%SVh0C z>14L**ENIu3Tp=W71m5-RjOatOd==LulXU9^WbYHGd9&;dHObBIc>c*%Avh_+Inqv zCSXy!YUR{mRl92Q>?&2eYR!eBrNPl0%qKv-F145xBqFx1^*&PIVAd6NFj;F|ksYi- zVhU@dQ(ci2YD8>Zk+o<d}?59Vcx#T*TC4qeCBIlY+(Um4U8=;B;1c)qW_o)jOAo4jA3O3 z2FAGs35+dhV65ErSQwwiQxg~~=u^l;K>}k75*S-(r9Oy>1-gZeDHO{}a1;PpBtl2e zFRvfji8`di>qiZAc>O3crqe`W?eO|h107yJYM{f-U60b?=B~$($MM&X(hg@VVf{v| zN@EGlU60`wb;uvXPS#k$`muyHmau*tdFT%Hu1CJ-z1j#Kfh~yg#9NVha(*e&M#@`mhoq%X0A zjj2uGNF+Fo>4C0mOb>LO!rFC>>4C0mOb>LOx$9B7&fN7VUDue_t{ZgMW2kpMO1C)X zuE*QKPia6-%w3P$11t@`jbC{c_X8l8K011Sc~kjq$dOpWrpz3Gj>Hl+Wt3~i5-O~* zgiYB6z|mO34eoj*<|QAs1e!@Itp0@Q zz`q?)NNmYo$y6j0VoUa>WicE+zfRs}&*0bbDQb9|KaT9cr>Nm|5e|LYlD+AKBY*w` zz%vLZeSSB+nTO%?obl;V;LUmw`7JJv2@zr*LHV%{9WQ%ksRdvpH`oNoVG%v!IT z`HOsBD(3b40l!OpUMlAGOvAic>hn@DujdrNXZyTV%+xI>VcDJXYsUyC`phrvL~t+gQc_Dt z^oV^crz4frZAFl$Bb5{m;3IaO9FbH~zk(o5ai!0bfiSp<2q|bz$twW014!|K3&k5_ zTXv~vZnSrm^|MuJ+PlgwBb!jb0j?4R+Plhb5Cq!0%5Ee=LheTkwmuU?eOj1<#RMIn zE>*#{gadG}H~yDxv|u}e3ArCFI4p&(@p-ILa0KZ(KEsECW$Z}bm!R?^nIHIcsS1u} ze#+K@aGOtiSMUIF za6cNeIP=Ybic3{k&(W>u2xpGL)DcrvIQvrch1k2oIg(3LRXCSJ=p;G$_*w}O<5CrN zCy-Oo8P4b4nG)GTnn!zAxKMJ1$d<+ev6`}y!`<_Nrlzdq7@Tel z1zt>9$+42?7gJVpoFrC@DJ$72iJQcfm7L(Z=pr>`B_|4R>%^3moa{1u&iEpv${6}0 zrmW;eiAPYRHrdbi`VV2YBrhZA_}^l0U(S{X{^o>NvEdmkF!vxY3`j#}Gg}}Nk-2x^ zndG+G+`*=-^Z^9ftqXV&<)9PK|CQ^L4Fg=bBk7s&1{Qy0xO})(+ZAt{A-%IHHesRE(|1g5p!v ztr*9znd5gZ;H$~(z~|Lx72`S4GCr?9tC&Ez*8c&Wg4yoT*9l*GL8J?IPz)FG!b@vp6Z!tmQPU$uRhDP5Kj2K z`Yh8**!M4<4!HOT$@u#df7l1ePy4+3EYtQ&{Jz2vRI+AQ~5;<{7Wz;vQvqY@$=v? zJCzr&wfK9WOR`gc2e`xMRc6_#byz|={a*^qc|O%Yg;h;`9XVY-^`-38a^Q6PJpyyt zUF5%u9?VW<*Y@iEY%V$$1rl;CTQ1AWd>);Z%aI?)=e2CPJYnDGwQRXc))hG3t|ZiQ zH}J#Y0sPjjL;iCB3PdOn!jsYLf=S>aTO_JCj!kX*JHRmb2)|M)!1Drskof`&Jj8~N zP^>Y?mJ_=2Daz#uu}9=vF90l^m@jH4(jJj7vf~236`iGUt#nqt$j<8UdGA}k$i{T~ z2Ldx+WJgT$so5($SvoFXBzbc}S3Y++5@E0!zryYv01Es;W;6ct?j4Wfm5%@ngJ0rT zuqXoxmhB3DOVTu2cxSUs^{)fLjlzUeQA83Sh4V14-Ge>$%GJx8Iq%$KJoY6I*loTL?RJ-Y zWKFKHAg6DkE1QqzgL9-MiIqQE-aNf?Q2NT{PAk#|>q>*wXRvI#e>r=T!`ZMaOD_<- z!jD;p<52zL9}ezC<;wTMp?q&?_y(VUC4ogTpUtawM0&BQ80|Wp9lxzf_b)G=Woo%z zD>0mIZxF6DoZ9qt;ItvZD(VDdzKJDzGUo9^3`3)IUY+T@A1!Z`zOM85o-hJTnXDHk zq5m~6Ccy@i?AD=ZlqNw5ZN8Nw(`1sp%`z{VWnRELpjoCxs~OfCmJgF@Q8eirm$%(! zI6T?3?+WmzV>aBh5uGMuX45#hrMUeiihkFSUYTG@+-geL^j*t~r-JDUXFTeZDfqF=Dae+e zM|z)_ z?ND5y{*=q51r8+5N3(fPyPQI7yv%}Mxm+F4y*jI(k-o)E^ExS>m7eof&eJ*Z8bl zJ#f5~IM$TdGcLjNr?kZJwuG)q$K#GRwqp-x_?xV9A0hC_kF?~SF#+0*l)yfQKyRaT z**?-`97CBS2iZyC3_p?GHdpAmhTg+5y%%D7b1gm0Ik+^>b@>SNnhrR0evKeBYcDLp1GeNSt_#>ZJ5x@EMi zFD8ZMLf$!2kasQz3pL=5dbV#Bi>x?T$&6L%c;(i_9Ii4PjuBJfY6|$QLHNC42){QD z=Jyfd_aMvf1Ez*Q4&nEw%I{+3*Q6}Jq#*oOIuY6F_$^2CI2QTFIZCD{=J)(c+oQ*k zU#@t{;)%-QBJI*2D2u(LZ-dn2{?M{7OWZkTg=^d0P>1dRfzmD|@)g@())1f5DdjieFLJ&4j3mWh!+ z=e#;dpY@LX0ADEgAQpnzc;v?%(SvjX&no`a5QlUpe`63Yd=%}EjIqZG!oC>$9Ldcm zFF#tTXpb3mx9?Q)BJbOLodmrj_u&}KH%rz=vSiKYN`z0rXju@q)jnN1S{AJBwF~xe z#%;|eZOo*#y$-zBTF1t=4tb|HHYn@S6dYDwNy1_eM%dXD09$ur~nwt|{gw@=fm`+&D&50R=)!dvIWNuE(Ivn{eVs1_hGB+m% znVS=H*>*KICkC0D6MDU}n41$l{{#Nj+??p)nM`VKPV}%{YHn6o&CQ7(w(;LEH~VeR zpv{BL&Hixq!eDc=-+n7{#N6z6BtUntx!E7Nmgs}b&Hm{7iB5B~e|iKm9<=YamZ^hhPTK6|TqPe-W5Fs~W*NM5gw7!8L z&CO-clYuZ;K!nx!Nzz910RE-;z?hqZOK(9=`hDaC{cM$(n}f^9rkI<9Rf3@Im4cw| zl|)c;bGY>=Hj?J%a4|tOH;3C2rn#BNJ(#Esf@*FK4_ggb%+28uq^suUa2Y#N&CTJF z%vW=Bcr^3X+#H_Ed^IRu_}GQ2V2t>kaO+#KGS!B8lfwS&mq6_dGr91x6qrI1ng%C|^H&CTJpCjcc&ew-}H zsku44m)UA=4%ZP@b8~nfX}9<^H;4BVR&#Us0C8Y$W)^3@8Bj4dNA(r6*qUv5r z*Ei!{DY@bqIhRA|Bsux`S_u(jZjQPyMGoC7%kh#K_eyCV&CSt5$rU17HUUA25E3Fo z&CSuGKY|wBEAIw^n46OoT&vXFoXqGTt9vD3H8&@7I>e}Vn^W(1WA=)W-!tmfv_r-aqqocfHgnwwLf6IOF`%5j-cb2A*3nNV|c%9Dhen^V3d)ZCmZk%XF? zQ>Btnb8{+iPXmW)Zcarm?U8D3PNi`DqBS?CGLlepb1LVy_bMdR+?*QjP5=QlH>bw995gjIr^ZS`&CRKCl2CJVs#6kbZca^b zFF_eKH>V~FZ)$E%O?IzGJ;vOeE_(z+A?D_kF*m3B*r!FI?=H}GpY`L17Q>)l; znwxh-UKo&u%x1PgCL(jUK|*pF-z&L;&CRLJUFM6qIn|{w&CRLl0*kr1{3O;X=H~K~ z1*EyT{1gFcZmuYhk>m~dX~f4A=H?v!6LWJ#J#&n?nXhZ6eS2hly}3CvdJJ&X+?*ME z2VgNbXU6esrsn2MC$rVuoEgu#rRL_$1j1@=&P-%gYHrRGj$o zekcM)BMUywr3L;VlRBDMdc6_Esy}ifx^K8kvdydT41b5|e^7Jo1xAA?Tf<$kxvuPP z5Hr_sSGs!TtVWS)+g)Np7i)Z*a%_irx=YhkLlWP8`D+wCY?M?7<4L0^Vm7%4`J?Tz z`5ZD;A#dyxKhcs~8wze;9pwFnR|YVkZmI1dYj|ARLc7XHpux;bvpD~flsA|s?^+wS z{s6Z=NOqrR<1aMzKwOqTw{Jfn6s7UcYulF=*Wju9JbNC@!`*{SJjBv_exdX=ap|Ai z(q}^2b|2>8N$Exs`zcG0|3c~4 zl()5%xe?=TM-_uyN{hGG7WWppVdM5{t&57%o*lG3-NnDMnjJ+}T{)|`hN*993dX;W znB0s!%rHERj(J!S^RSuW!5P*;{Bgwp;BrM=5aZty0P+ALy%ZpiiufCVVMctIeK+R)34%r!wAK!Vn z9?OusJJPA8lko#(@jUa|^3%+}?dPBdu5n%@%Hmvr885px9?7cZ!zrka4x;O&6ZJJu*1n+UEt4PcC_D@L&e>f`-EGh?8 zN~=5UA+4%c@Yq{9E0irJlj=%xx6rL8DO}5*`hyuf_({lL8g`8aeb}4&i+R{%9ww_v zw~-a%rAaPfs!3Bzff5De*WtV5JI6G{6XjLlaia9BRyw~e(f`kw3p#XT_EIuYWZTed z<@%;ph2o5mFt-i8VmDyjHdI)*4ZY&2$k%N{uXrfBRksbjBJEkaZK$wr8+ygdfIszX zCz)~H`UUD9I^W2dop0*_C)%&WuW{b`7~s&UcMH)6Y14_(KO;J|>BQ-2uxFgN2$lsw zFb)5k85$Bc&Rh4f5VdK)@HRnp-ugAcH}F$Z_a}ntx8<=IZ?!9_uO#>!*5c9<`dg@7 zq;%SW7(D6S(#^DYX%{Kod>5doU8J;&u-ZjRrxRAYNa+m1Y8NS;$hZat#9ojr9B@4R=Y@P53NvY z7g1R4BBebXVT5$6oq$~%1hbG89*HIai#K-w+FPC(e&35Wwb0kb$0 z%zzp@0f(J-f{RI1?F4DmW$Xl!t9Akop_Alm#c3u)VmraX$f2F!<(SA8(mb^jNUqum z-UfmaAtXe`@fDBV(xOGT;{ojiXJL^uc7n;QTHMl-869M`6A-p`0v%+v6A-p`0>ai# zK<2HTfcY)PPQV6PI|1JtYbPN73Tr3uz)wQl(o*ji@Ch(>0@AT|0=_cVPC(e&2?$#| z0by$=AROBXn27BJOvH8qCSp4Q6S19uiP%oSL~JMcHaLv!1iK><+X=|9x~0KRz(i~( zXa<4UPQZmZwi9qAkL?6|gIa7SScXJwC*apJwi9sBVmkp7v7La4*iOJiY$xE_8ruoT zTWlv-j(TD{!9^H~4eSJLudx#lv~~iv+}a69FM|bUH1h(|klD-@$V6oBa3m!6EStN5 zoq+k)P9U(c6A(6b0@i8l1Olp^K)|(Np`t)Wk}J^Ew}4sggnwj#9Ohj`J#&nmfUj$& zeI&j=|H@AAISN@j!70Eub^_Ut61TKWC$p`cfb+!K2?$#|0jsih0+ww;`1uuSx%dWZDElq(SxrH+4yw!g2k+EHO?>tiN7S2TCl8ON<*R zvB?yaNJ)umQ{vZg9rwf~(xyaj!&(+7clijaPNS+iE_(@EYfYl-)VUAJ)1^(K?9>Z& zYCA#jFgOhY3MtL6e*=VGW8=2uf`Y$?^*=Oj0;JLwY254Dw%!&7J-O>Sw5YaKs{M

m0T<>v@LBdQ%VNefe|y4vOn}#?+&Lo zj7#4Ymwv!_;uhHh*8@K9*q$QiFCsF*zywZ_4NhvRBp|_xWlDxSq zVRguoufs`eiJ>(*rgeWz>u^KM8Fn1;_a*)agTHZ%|1R+#B6IsH=leOs0?z4eiT}dY zint)g@5IZdyl!iGl@ZuhOJnr+Ah8*oc0Vws7ssWKW@(vaGfl6ximTWxZQJ6aILggo z)pG3N8>BUc$$CR;-^mo5eK9tReZGmWB~;PjX05su74ollKKP)r^p!D7 zkKy6}Y0MI@60tE$+~8Mb$(zl58?!{%#w@)892>L5d>ga$B6@3yiCLP653Y?_S`OI8 zEWHWoSCu8Nhw%RoW0t-=TNToD#L?!&HNF_n|5JU2nkxD0k zgo#ulXd{&f(`3I3{x^|I1Z|`eb+-S-NTpLzl}0KJV?|#VsWbx!CQ?a2s)WI< zIJk44n9Ns1DxE?y0p@G4M#yNSQV+@4NF~O(WXX?{B{>_Z#B5awgLQ=eRiqMeOr#R$ zxEat5B9(^Wt>Ar;XfCt#C1be!VM#p%1}=nsZ_+&*dS7g?KP1~1XU$WUe1=Q zN;nXybSv`0fHWi~i7k+c$lUAkOmb^%?qHP=kxI|{p2{<-VDT@W=OCpt+{jVaG zSk;D+N}T8>Qt2){HjzrQS8XDds5$)yB9-nT855~QE2525dJy?>q>`wjCQ^w7L?z5j z5@7>_N58#LRJkyy!DCSgv(bwHRVB=3Q;-QnCCuh1HmFLN%@bCYFl(ZLFhNkv?CH|# zo=XiwSq;|7wbBqPwdaZ|>d@+*D^mPWtGmK#b?qVdufKr--;oJnEz#nAR;y=+mbCs0$Lea(qi^7j!71(4v;c_}CSjRgOu4MU= z5AiU;Te@z_cfE)2n6xQBeV|SG=>u(2*aRR=A81p4`aqlV({DrjOaPL=CID%=w8=jX z{gj_^8F0G%qY2OCKz93WS-`U>?k)0f0VDa@9L=r$JD5MG37Cr|L_I&3b@lpB5T|oQ*+*cx)()=}TZc}f%3z?wD}#X!S6Dl| zGLQ}zkB!QZ9CZ0DsJBvL*r)qb2@7X49PeXjBb6z#SpQEdCM9GoOuTFYxstb|c_Yyt zvrg7ON~D@PXm%O!J z*JN-YlgOJ+lV|4mBFQ zxt7+SOi=eDS#21s!EY3y#v~8P9}XbJ2l0Mn6>`jeB->*4BgvfEj}!z7k--gup!<WNzm>`5~lLG7ydW})ljM}+%OphN{YV!%+>hip-1sd^^Qe4A z3nf>GY`FpmN`#OQ8LE6ni{{_~_amDznazGAS3SEQse`Qhk%aAjqzDSk<4!~`;lyr-H+tzVD}@5zryZE{tyrBe&jU}#La#r>Dc{9zA|<{lCa&6By9I1 z3ETZh!ts726Y+i|6Y+i|6Y+i|6Y+i|6Y+i|6Y+i|4=|7SBma&>ydO!1`4)n$)xstaX{qD7b$+I$fvMT)QSTlU%tq?>`4&=B455p z*eGg65&3l6GoQNxb>W~a{MPYIm^A~dU>&o^O5Ca{5R32~#>kRy336CV4^4DW;sd5zI zjK75W8xgMbH?73)Xu`FADansvTN`{Hp;$SVqtoI~fb?8B?oiNg^BKBd+4%{o?eN#L z?0AlRr~fkH2^`?5{>_ACu)7?O*IZPV-hu*&2e@Qc*0QkA^AjuUwi2Fs*J))z$Kh7y z*OP}@t+#<&dJQsem5m&?7RNh)70A(oVUWgS>AeO31^%GpsEX9=g`YB?uViJ8L~7TU z<6-T2=v23MEPg%5I}SLN)kQp2n?=oj=o?e0l`XD41)bv5UXN^Ca{mif+_t@-v+Iol z%sRX=l-s{b0rtlK08fnqEa+1x&VQ8x>}`A-o+jD-?*WjdE_A%H!%)w*JPQ$_V(2Jo zcO8HNJ5pzjw^;(9~Uv)-naJyM#HX>Lqa@Ksj<@e1lKTxJxj)$j$v;C~ z^A0#1iTVZTNVl9?Oqf7uE=r^6+*W@JPfgS7uiO+!4ZlZDn1C87NDcdIlFJ^NF^ll!2M<2ENwe*<0^ zu=|=9^Vw>7cE>NZjtk?e?v1Nj9ar`FW>SD8P*syS@7_>COzP8N!0Fy_4_kGKP(9R8 zoe@*5s;~{XB&I4HUt&03tW>XvsWxB9N>3{}9wpa5p@dG4=`mM3VQoC8 zPxE2y(p{z8Qd4fXxZF6bIa+SF5>u`PQ`p_zRKJIwX|sn(E@|YfbN4jKof_qck?)jn zwxRo-hD|xtn@eSH{X%P57FX8C%AO;WT_uFUq*OM2Xk{~oRyK2JWwYYSAg-XL4Zmjl z#!8h>nJNeR>rP5Ep&wApWDZy8FXUaf0NGDjNO z^mWU1{B3&m@+N*@+;u_^f%Z+p?tMOOF5b!+O|+-FkNEsv@$GD3&pqjr5iAo;ay-)0 z{;`t$PLp^)ydccO(;e?F7YtdPR{}#;DA#HJ6=_^8So@nMo~A8C6JLp&c(q}vS7-Ot zzRqs5Lfq)v6{2AicG-nOZ*xO$Y)mhY?~!)dg@zsuSUHm%oGK+gepFFs#U*x+OPm^W zATA=Onn5$G$yoy&T*r6jK%qCs(7P?BcYjRpz?h!Q=L5}zF)cdO($j8SCgkXk)UY|( z-9^#`LwWsL=EKGOpl0`8?(!fPS8@R1y2xsz;-aqBk zzF+@b36)@I`RDd+h7Z5e`#3RlR(_I@4_Z7cKQ(F0$}?I}^fQyjtXx|}`tt-Q3{TF| zS?SvrH7(-{UutIMyrw^~N6JicL6f{wt$ZKV8vA5|k}1#p(w00e zJ;OIh&Qkf6G~8P`r%Apmzc$Ia%K9@2ecgKXv-R7APW2^C@_G1O!YuQxSu+%Cl`p4B zT!MZt%<@$hpCFsWlGRYjmFxn2{-73G6*uPDxG@)O(3lH0Xv~E}8*`E2eqNEDo9@LX zIbYk>XOauFZI{GtlZEEWgf27-n=a!NyU`$Tq3h0V26>6DJGUov-N76D42|4Nq$NAu zzhO%*t+B(hWP_G0*`Ou64Q>sxao_MH0@ZTFG|W(zOzoIv`Oxw zld0VBf(h|HD}Tx3M|zC$OnfV@{5rFMCD;*6LsJ^eeulzKO4S z_Dz%p{B_TK@mo(cRi16C)Hm@j!VX`0c@u4NG2X=YIe)K_=ij+o3q2f1}Z!;vOwy5T63G~ICY&~Es?d1|`h7?U*JaKg}TIB{q< zoIbQ0&WXF>mv?=!8_plp4H4JAnbHjp-KnTA#Ixa=2HOoYH|U0$8+60$q1`aY@NT+c zu1U^o8qX!C+aygl^bGBWdFH9JzGWiGHknRXs&8yJt4b6_!}%UMt;d?=cbtY@$l9weC+c@@SJq|%=AYYlev@VGRaXTdds^kIt}ZWU z8!_Nd@|=quO;PR}E^Sd*3R^EQM3aW7E+BuC3KJ{)m+J~*)7LF;ebN+o!gNs66A+x; zw_MtF*cYNkzwPRJ)vHqdJBA#D5|NnRHR)TI>wEim*RBXW-Pe83B$p0bf@bcIMk-ey znqpTPu59|Q4@jnld1?KN5H73#P-c!k2KZ zcv?z)WTb24$e-I6HrpY1+LqAs{GN7owSgGD9X}C|3xVGo0$6AbflXopk6Qvx!)YA# zo25jLDRF*W;-a|3&89?eBRxM*fR8W;jZbipZ#En(Xxf(K?iF%sHsR6 zWp#azeqiex{-mLDm}&YgEf`})AGoL3T8p$eoGKK&m2;csEyTmqOmcSXtA@a~hJa3x z(@jShIn^fdS!mtL^uu>-0jcdrrnV(g+l7YwoYq|p_I4Iq#Ndkz`33sw*yJK0HB8~; zJ46tUGrWy9h26f{aTgsjFcW@9HDC)VvEpV$WpFS5+`jwc5?k0#YoyN*3K+e)MWRo( zFf5y(m+frtsSffj!|)y&1GA?|F2UIzoVcBmmU{2j%>m3J2Hh;~|bTlU}eAQre9 ziwWHM8~0;#I}I7ooCtjj}Ov zQoBUiyl&drAXT%BY)MuIg=S_-%umkyX`yPvH zde%^LMmT43w+Y%GJ_#i8#61m|!-N{_)Aj8@A$d{B!OB*T&7JdvjPk#yigM zp42AY;p_iRn5JLvW>dh_v2HdkfUTPiVe4kI6JYCRL*A{M&CP(Vn+;*>X2Sz!teee` zk#F5>Dv@v9Y}gj-X2VXlZZ^E)&bryKF6(Bq5Av;>4S8E4&T-znLy>RYY?yD|YzSL7 z8^Znn!p%ne;c4`KVsr9i-E0V3Hygs%&4#dbvmt%!X2W(_Hyh?#Hygs%&4%r=ZZ^!f zZZ;0uvc$OA@X#;oW^*uL>t^#ZM%KF75VmeM?EnA!ZZ`ecdi_%0npI%O`qmKsKlQB{ z>`-$(=tSJtO7`QY0#zF$pWHhWT*@u)uXU&qgs*j|IgIU5hZ=&`p@uLwGPlD2#-WCw zb*Om{@c*Ji&CwvQ4mDL6@UL~KnFIvmP$Qr^)R4cy4mCT)WWK_o<|vX;hZ-TH4mFz~ zH+HCb3W+TFak3<59cq|u9cl>wD~B557>63pW;380IMh^O{u_sylh737P$Rj69cnnw z_}U1O*rDbPkflS-jxmufq~iNp>y=YT-$P{Tos9cq|}9cq|}9cq|}9cn1qf4M^qy?A1Wno3NK4IFCNUgJE#b1y|ga$`4}4IFBiZyjm`HV!p}jYAFVG!8WaszZ%{ zYr$DXK^$uSiKgz2LU5?rnPt_XhB-qVYOX-WzjCPI0b16fCV@|#aj4+$(!q%aNRau7`mZd`tC%SQ{xdD%HJRTl|K?rgtR$?Q7HdcZ%jER+a33xVEg0PL1 z;Ba%5j~!KVsr^aen-B`Ra;=nV#Ni=V91xmvMSj3lXi`{(rd)AAXv!5?i;a>X`zkc$ ziiA~Y%E_sGag@ZLKr{^Az;7L$S^f#2z#nApCXcuR4e~)TZW444R5uB43;-;~aGG#N zF3`)Dv(2?WFW$^oaLI3xKFw#?ryV$H8YJ>rRwLJSR~Ef@0EYo*Lz+KTZ33bqr)mPH zYno>eReeK1Ue{f<3Bmev0y7O;ir{@vWNH7vsCo=o&&nAc%p{+RC-I zMLJA*ODhZrIg??A^PMqmc+)i8;z3ZL9(b;q@^i5;@-NyEH0h^i!Y#y4%^UFw9*Lit z*WQYmp?+#!$5Rlp)KASDNm%{VyitVJPtDtiu==TaqY0~@nm6Vh!0M;wjeQZY`l)&2 zc<{XXsd=4OfOqv%^TvMyoKEpm^CnEd>!E&X-bBJ(>Zj(F{uR8bpPE-IAtE%sdUcnu z4}5wLd4nNXLy76caU|>{ zFU-ewr(H}4m&9s&R!TCc2d&bfgA}tDd{*I;NY;6l9A(x zJ}B&@Wb_oGQ#CF*oq^*Lc2aT%L57{&iT|x?OjuOo(%NZ)iI$ZX_9Mu!ld{?^3BG|T zSys0zL57`_6)3hz*hyLa*#xO22hX$GFj$A*h!R`!7C^k5GsOoc>?FLj5jmnIhy84e zgq?(!kvR!F30DaMwdC*yL15TPcq0)s>?GQnN4ATW94#iOT5_~4VaiVj;(yVSqwNT) zmK+_H!$^si934Tr8g>#bWA|y;NpvLhHS8ohn)w=b5}nI@4LgZ0+7YmZohYnfC(*?h zp(<+0(M=Os5yMWRn@L2&PNG|+B7~hp*KZ93(UPMZ1*Dc7-AeujwB+c{BV#ga2a&le zCUg6RBttDZS|enrB}aGfKr$M35?%Wy5?S)&WJyl7Ir#E+*FIsZCOJQos>FENCmRxZX>l7`y;$#82+*X_-AhqO7fs7<;(bSVb z3|jKh_)oOtOg(dqmdw{R+s;t-uh){Zqb~rCYRTELtyqjiOU{ntH%ztUY$vl-OU{nx z+)^z$JAtrj$=QjlO10$dB$lO?%!w{qa&|HUK*B&i;6XdcnV^myfHtUul8p)Kps-LT!A{mfGdz_$^O}7*Te;IToPj_Sbdd#oESe2 zPmO*o=u;?feU*Nk*m!3=O|oYxlFD2RQN0)v7!~1VZa{t*+=^de^#K3{{vdM?t*HBzF&l;ASWKU`7}m#DQR8f41UNdZn78MJ~) z>in!XDKkGCTsuEok6>j_lDi|H(>l)6|4`RoQCCrV^hupP-NPib#F53McH)c6b+fgX-LslF5B^5W-5%G!6v~0tf3?=%TNLxm zH9C106=jS0TCOh$tSJg_*Rc?Mgo+Zwa=n?E!zAeDE@g!=H{`kXO4fZcGk^Q6R{DBe z_s`y-{B)A^W?zSA`VA7wQhJr2S&9KC23_`@J8 z^Y3QZCjWalA|^nhZK^AJ`{5pXWKYO`iQ!r1m^&!eqq7q2wa77d0`P**!G?mwNFK;D z*ieudJ%Z>o6eLbxM({*}XAq>J;A-NV^C<|MI|0TBCdS7v>_kxS1lXM58(^ZOZYzR% zC%^#&^-h2l1ZgNJeV)~Z0q+lv{(Cs$e-B5bjvvnX@8O6m)KCyLoyxa+SG?!X|Mzgj z{~nI$B)jyWL>dbIdpIJZt}=~0flbe+$TShw^C>dTg!O!iObcN>pCZ#rSkI@(6nRA6 ze-B5r+x~K{of)`PB6+a47~ZpB^~eFP|Pb+)rU+)k)`IY0?d{eEJm(y|L<~Zv(6wWO;#& zRVOW-;PVLbd^x8|m;WXisv!Mt$2$nZPCiGby}ihE)dK)=5h8x&c*x%YD98_wrNfiI zilvK8%VB>X0kDVty)zTDwQN0d!o*GX#Dblf`CWG%s;+$%6z~V{U-@(Uy3ikux5JVI z3|7Le{D!B%hubYBj(J5fFG6YlxqX+$C3; z`^sCn7%f-!T>LXew+G<#dce?`;w7)Fwqe*oXP~}sLef|K^#*^KXp-x7WKi4pSo#{4e#n#_sBLeS zR*jpl6(>sZ4C0?p{G$zik5-Byyeh^&-{24H>LPkv+X8mZGL~NVk`}uwF13xIi_PrXnVtd;M z;zZKRHH0=3Io5v%t`Ibe$TbB!DxZsojh_p`-y#XHHEbrU*-86u5#AxTtvG?1o3ZYT zP2HVw-R)R#v1e(#32Lq0>E{uo*6N)>up}rA9wNSKt!0E0z2GBJ+as8$BT+bl zAhlM%_FDjh*O-0-KYrc*1gX0Eg;NPqb@l7}2vT(|d7gELBAS=Je}xAHwxt&u?FVGr ziORr8>Bsj145B~aVd*D?Gto=T|CDfT^cM3!Bis@N7}wIz33nu)#&0PCrtn{9@*Wm& zB{3EEbtB1iJ0i)@ywYlyBeNp;J_*#g9LnR8_wY%r`!4=F zKAA#Sl{UB@5Kd0!Nnp4H?VO$5gk{FKcO&md$r((Hl|+BChlz2LSe-nV)H)?`Q*sfX zOu+JuJ-p<2lAb8MtxJAJw8?G&ga@6(o=BCI4Fg*0J=S?qNDr*q(tfr#dI$|Ey^Np} zeG9*(m$T(Tv^n8b$0Iv~zPXL5fHcxFV?eol2A(nZ20WA8TAQ19D#jx-!|00A&0Xea zwq;LtDNND4bh^N$!7o6hY&uY~Yw#1C#OkvPfgPMIAh+{^Qv{@)I4m5G-}GGM9*=)H zr|by)m!%6uSkIgUF9(TAehe_|La#g@O*4bRiRdU3ZO)k-M8C$cMqPx% z=yXi}Xgc92V&q#igK#o>8(-UK=Cdf9iRR#~h-Q6={Fdk>2x!r4=66JY!{m?V5T2Un zO^VT6MuBxl*TMxL>Sq3;h$pEj9q~tp?9gPcPtg z(b^b(B>GVBIq{!z(wz7wp;a;nu9N+oY+lNCX5UAx$^PS!k^Kw7%lN8iU4p9wfzBey z8w7#QBFP(x5UvIJOls>l*;NdwNG&GlL=R$qq_!m-V5}d-|B0i}OR4P$hCiW%nmTMh zwlN82Q%8`l6Xns|)G{tcek2>dM>0Q%mXO-f%uhu;tSWUb^D|L9IyiOFcK}yLBhfty zS4TX)FLm*IsH)bf3{p3p!HQ@DO5IE%PV@&NFklqRa8;1H{yHF3kI5qQMgi$8lDd`r zVOf+rVnOE4XJRsI2a&leCUg7WNruiMsWn1|&LXM1Zy}lRS7>Kv>e_CMP!0KUYDg}K zzQOk2%j`@5Y}5ZUq%Ku{utgvdC4On7Hvq91c2y=XNaRGwU3ek>;=x5vsWxMn%gKf!N#MhBVB zBIQ}asVD)9ba_q(na(2RdBT;^qiB42CE?oWHI}V<2yjF63C63un)xl!*~0+Wu|XY? z*9y46H)K)tHu39;zXAuycOudB9v;+IED@V!d{-TUZ#a`BH~tUrj@WCaceVEd;la%qWy_Kj2CC7qrK6@OxvT#uYy9) z2i4cGUUPQ=3&>iSnIvl=m?gc^fDDxe4fsv)I=gK2GE2<`n8{}O4oAGsE}N6s*62o} zt8D{PReMHRX!B66@UsTpfdm3Q(>{xHh6x znJdx@r6bxDtCT$YODA7OZ+U8BaLVv%djP(b;TMcs#%*`H`!*lFJy58fZv< z)IdWN)`sLq4KyS_YM>$cQ3DN8SR0ZbB@Kz>LV=A~RaeBVrTpmEz|-uA=St?s5S|nD z;$_H>B|JBx%8(yN9=fAf33qZy>2=b4d^_JPE-1c}_(mBXj(-O&3}2p&*C;>nN`B#n z1I|w(=tS4d1w5I&1`&P1^HT_?qK&%&e}ix)ng(?1U3}A~Mi&!hI+ud3 z=m>H!gDqPceaQToto5MiA#yN_@FCG*%%A-l${v9+WYZHD^YNVf0A{C@0X&wunRYT? z^nQUhmj zCAJwT@i^<~mJ)A%u9yQQ=;yC>bPtqxo~@f8B|iR4OZ;8`V|T*TZcM~iG%-dKji~?cJ5}A&vkN|wnBTqk z@4(KSsy^q`sj5?_PMxlII{ z{9!a;R8?p#C(?&EJ+(%OuhKl(u?CqMUSEbhwr)i>>HIbLbi7$OaTqWV-b^HlF)e=qhs-{wDY-}<5{!$Zp`)oG& zMCWOu*ENxsz79oAcvBU%M*SG~`BWEasy8*2m%ag1&uc1Az}J1M&6;YTrt;D^f$AG? zsX{yn4}xo{wBmYAwQjA_3NO6_RPSo4Sz5vlpXw$}b-t$Z(szJr{$ES$b%jrLo2J^J zsl4<~P#yJlsf0iDsUFc(7i%gny%|(jYbsB|5Jr=#*N-&SMos0VyVe?gV*5%ZR22WI zDK6I(UV7_VjNy^AzJD-jgMRi$MLl2rU<`j2r79cr2UFRgPO(83A>RoP(l$uh2lQX+V)o!rM6xW?evT% z+HOrTu|Vg=d_V{omzSvRLuQF3{GRDq!v0#O)3i*gt)9@-+7fz6Si*)DigSltuhHUM z?$_rQUz|I%IMdZ6bcZgmU75Rkv^bqc{a9MhONHM9zgLW=`__MU)~nv7e)Yt%e@!#c ze#DiUeTVeRa!@(pq&GM8{)1wBoma(yY@n2Fmg=L43nNH_lZ8hhB(zECQNDX=}ewx z(hYu}dAszj~%Mn9Zgvsz+r+}4Siis7t!hq^dkL>#9@ zT&L)uN=tkZ$D3S~P!}b(e2h*irC$p)C;aNQx@yuE%#*fA8Zok|{|nnqVABOkLX2cNX}-9rR}voQS0-f|-Xw!cVesXbRLNJUAGF=~$UuCIO5G(B z)i_Rjy{#&o(G~6}$lJ8C(x0JCrxdt!Hgj4RI*sOY*;BuzIXd!1RSGv{@nd!!3%9#P z3j3`Z#S{CB&Dg7K)Aat*YtN}Z?C38gJx|3!L49u2?4A*3hH;Rbg8G`ed~$!0<4;N@ zI}M{b!FK-<<+$kuMNzEuH+?yNR3gWZl^h*Pj-MzwI+Yxcse(>7n%`u5-c8PZdY|(y zs`UbLzF@CnX<=!`4<6X{IWJJ0r?)ULV=myx!}xCD;?Z2dRUC$Q|G5H=KyYjKUs-2#~3(`#N$ak_gSGaZd5-Y-i$y|i>SwV zR*EBqNc&pOR0jQL~b0UVnK~phczT z!>nMPWEsE51gp2DmQO;2V6b8A;|d0!fx5r`umHUO$G@|iFBy@ng=>L$7whY5$Or0>+b{j z!8=YjkU(yS{lD9BN}=_R)2jhG_I3D{9jDyfrrrscKqYbI`}lEe3LQETw>dHizCO;e zf94T9OM=~WV#Av&asMe(KG4-Il1Ua@B$F)e!BueHItIRBrt%>$XtB-$Z6?KSWrK{+ zS%}7G(&X&&)U1hM=hJ0cF4w62ZgAxBR5LIOSFyw|u*5Z*0KU9@ z%&zxXqCB#;L31?q8^(PQt$##S;*6N$ z`*|$vKH3IBZ&#q&3dnWgfwux~<+Au<#9qDqe+0Sz?>hW?`~L{{-2caDu-@dig5VZZ zAW}7u;8cQnZny~Fj4DN{3ECR~9vZ1T9rbg*N(|Z5U^p)kmQ4+ovytesslj&cBrKa6 z63(fF<(7WZSw^@I*;G2m6K>*ic9=7Pd}L`m3Ol)wwFD^ckpOxdvhOe|`wnf{cNlx) zuULdS+;+TrYE@XFlL)POQ<8k zeTT8QISxOa3GO?LB}@vuG(ioCB_**UfmzgurOeOcXLW-64r6-XVS@V(V|w3Vg8L3* zd6T;b*C)8|Fji;IKw?9Jk-S)6a}$0xCb;h~Hqh)sVsnD~4r8s7*qR_^tW6R(B)IP| zHb@dX65Mwf8)CB6cP6;+Fg8?V+nwOP!`N{1bRg(`hj#3~j9t%)bKhYCc~P4@;?z#oKzf?F5hNsciI6PHcnxKWUya;f z;IGn%{g?#YcNni_j@~GxcbSP`HZE$#OcggLxy?h6pO(!@Y1y2Vmd#1&z~&@(0BLR6 zoaDA%2H4@|B)4q`gfJX#PI3n^+jh7)$sJ6MOgfB#xkCu&9d1r?hq9=G!_7(VFw$~! z5=Vq=PI8AIhRc~VF*6xvqCAX6Om^NJBT>N$16*n(lB$rQC_EwWlu9~pqwqwE$Qda- zk$w}^zub8a1tv0ST5woQ!)~YlwNqP(f+6*beRT$QZ+_eBJxGAHo zF*Fu9QCn)pO&R4)0#dZ{A)+AMlu0o&@Y(^NJD)u6P(kkRVWIhgW8G zB`dh_M$LMV6o8zrGMFvJdZE|Uxkloi!eoDqf1Zy&gZNVTDXQ@4s`{s>!l%_pw|&~@ zHHf?huv%?VRiD55)q2h6HGn#UIP6(fzZQJ5MjZC6s+nw+0V;XJS+&r0a|m@kyy+)r z)qI<{L&+t)>DOn~+#W}A7>f#Tdg!d$;He%?z}`Q3 zIDwBNgqvi-*N-FUC+F#Hgj>ddY3NIApAF=%pNc=0;00{qO9cEmZq$S?7x2>F0IwiO zuj7aK4eO^42#1~qrWM;xkPje4@(T!FfU+VrR1w>$gMEwI_2^>fiaxLlaUvVePUJ`3 z?+}Hx{3h&#H}QW1u%7rSt~c?salMJ3us87&_9lM9-o#J1Mf?m*{7ejr>xrL7xnpSQE z8>p=LU<*^QxDgp~BQoMfWRx2b;vVO+0VZ&i8&TH!MZn@ll(qd943ryDHi+5EjVK#T z^;B*|*$~3YjVK$+qLdp^HjK1%BRIa~tg^DKMt=OH6O7E-R=fai&s1rM(tC?e!={H5A0)n z>=%6OUi&yHKV^>7*ysDaSNqsc6|pZR@15o|y;NmpsUKA47e4k*!N#<`rheX{6~ulR zJj0tduIXL4nDZ7s-af*H3(4=tc&8~bwyr^}#5xW+UFM1Ut#-xjyrbz#NON`R5^gwG zwO5z4S9sHP=N5jZ$>=KZ)3Eyxu-jph814=>+ep_v?k?pS7CW>>3E)SJnGyEyW|}!XYsyn@<4`ZrZur={dzD9`<3L+c2MP zdaOyEhu3y4l<0?0qFzt3kfiyTzW;q2nw%fAD*>;r;V-hHF`Tm5G@QlwV!jFqNG0n)cUg8gAnCYMp*| zO+zoHYfL^T4;5J3AUD^W^>yqJt*uf`QLbC0X{KS0)|X#~#zgHDNTc@4urAWMzc~xw)Bc4Z)*bzp(!+g|{4qG2rH$UAHe;7k z^S`lPeAo_%UZfaRg23qoTanLgZe#Lnj~zE%okLq?5lq*Eq;#6&HSA zcfMyg%&tBO3|?7)EM)btxusc#`e$gp5&1O^I+c~}n4u{bBby(yYoSlsp&MqcBAu&A zo6AYrsd{CKanK=5p8PdFRfNxO`6i<~d`2fLMw{2N4Np^TcmooP@L)H`9yh!g2aRJ@ zCN^n4#ho_$d_EJssu)C_LPpdQS%n?T-eACZz_cZ^4O3>x?RvGd%9m+C8MaS}{Gal) zYT&d5z#rnRjB0&cgHL^1#vid%)vKuHcD0HM7gSx}jwkx;7`D`8S#wTiKll2EG{D`mp^>s5@EGbbRSRxy?iU&<=R z%9{(oO|4?AIvmvLtzxXc68}`I7;B)!GSw=^YL&!RS;bgwl2EG{Ymg+=D#jXO4n(19 z6=Mw*+0-h=8g8ydIS&~wR~D9zSz23JNm*G~+X$+ag>?<9t5z1)^|O%8mBj$$!8=AO z!H%TZVwRc9-jv)gdAY%ur8UN6zQio8u?ptO!a73WsJ#{ZVmpx|G0VsoSiHn6BO3(d zaw2k}fV+Sit(k>yi3Ky}hnOYf+7h#j)=Csmt^HH$Vv&9zb$$v96^juB8TEApKoP#e z2))jWvNqBSZ8_20t|gv??3~6BL%&g*`juqJF5V;{l16+8Wl7T2jgJ(Nu5NrZLA7*n zhuujTxO8wwFk3AhT*2njVG}N=iIX7L#{h_ErjdLP>BN@rA}7hmpA%c9fR_kv;{Z$Y zA*samf5=^%O5auy;AYXYc0xE`m6R;ksXgC8`ojrgn zn$rLc=ZjMTw~*&pXC916MSnIN&cZo_NCQ`r?IHNO0DoE+lKViD6jsTf6KoWb))DN( z`h{kKw$i>8BvG4hh|Gi@z(uqALCN9c*I5Sfp8}90V5CNwwGns&P8uSZbp#E^A>51g zX>oo+`g)dw<<9kF02GnOGC~VcoY|Y)?B@W6&4%O2>o=rnBxpF_BHV|t=^R1yCc+`$ zhF)|4Ol4l*0`jW(SYrNsrkh!w6P})G#4p-`W%99UU2c9I1#CGNIe3PyQX%D6lCuA7 z$!yV?iHT^_?*}M7?Ntp1< zMBod4>-o@?c_EW0YJ9BNMezBed?UAukHHqEqD{=j z(&u7z=j4k=7D zF?_wk6pAv5D$0%VcS(vm3=gNNA5)W+6tkO_v#F+N)_t$n>`u_-?t|DY`*?+b6Mkkl zsRGXkNH$AdU5Ga5AoDRCPTy-(h~LqOX4ia3Mh8(YL#{?wmo_56YfO>X3FLJ+c_n)A zx?S^<%j9)}MhWsdyvXY*w%B3hbz(zzx!%*f zCp#FWXrFB9H06`MtCjlQ7Dbp`4K3&q+16oe?RQ1&(}5g?GwHch(dh!)D?`YK1{(Wy z+jK-+J82gHO*?4>V|K(Q7tb*}2&}YYHUZh5V|E=;v|~otbIb^Pju~OkF(d3dW=!~w z856!^#)R*fG2uIAO!$r&6TV|M3ljQ{Stk;{V@82}$BYTzF}oNE6<&s8MpxQ*%+5kW zg_q%&Ee1E=Fn(Vv6$c#;rF&7lV<@H^!l7?) zJc`R>?Spyaz+Y(+ogfh(+2X2-@M3z|$V}W5CW9SYP{)Uja0nKV!t&pZWt) zjMO#AVRjmHY+qt$crDE<$aofTh^*|<40mVe!dUb<7MBo0j5QL+$n`~AnXP1lhmTF2 znL)+OHnMWU?K(4YCeV5BUivd?M0pz}_gPfKyp-8axcmlX>8jdEULV?v+~bc^c{i#b z%yP`l%T6GLf#r4nZcZ@uA+{18@2yUumS#cdu_~>8H<)a%UPtcU)#=qkg2_(QdJDv^ zI-E4M!s6S1hUSfI; z;zeG9MYC7u=a6zwHgw8f$yU>D}4=$}vS z-r$eI^tyt-zy@V9)C0O(X)U4{aY|g9{y+aq>U+T- z7ri%NiqGI)FsPLWB2yuDq|ZPR2!n+jsFlLtdz!%zp8xPoXe`;#N|W3&k-#C@%9U6b32ko}|{ep}Qw3 zjoIi|=uKefb8ItL_@PBq3%k07+w)>2ysHyAVqIPPIW>q%c~?-%6|B1*`praD%2R$R z$HNoL?`A2sU&=RF30rfTrb_XyP9$S50mkPNHxjx-Gj8=6UrNRzend0wRN_ap_#H;o zD+w>VI48Q)CSASO63Rc)dgj_?&Ivh%Awg)S&VB0V5RXFU+B^3^P zoQz&mNNmdGX-BITyU%B^!e^i`D3>rWy%u8=dDkGy(`?=M%v#Oq5TDa-a*`%`&*Yo{ zeNavGo~g!Ahngk4tJ96TN7#?=nlDXIQVsTbz2i&uuFp%xyqD}S>gG_8cg(e#n6nu_ zX4fRw6XYGASO)VurGj`@A;`nzwa={7ycR1~;Pqwl5{25Qc}-Wf@RIFp9xs81#eYak z^p@aWag?eS<97U*UH?gLQV)fJ#;#d5cb-SU5!AaEMfr=lR1^18v>>ibfSBG2u6pe& zyu2h-@QWONugm4$ngNvoa4c-K0OUK=RNpM=}9<5gWo``m6O zH)$D#L2e?>pTzsZeGayacMaS+*x9ei#hWy@Q9ie~d~UDl%1tM^m+0i+P_(?&S-+gT zwwu?1{%40P$)3dI%a7S*m3ytcU3i5zZCIQCE98Y9>8!g6@G1)#N8i0q`zVi+jm-)!<&T zQ?>Aknm1ZaT5+0JS=ERq>C5*>2dEUgT3XagjyLM>X3d64Q$9RW)oi8uLCv^wP&FIo zaaT>L2>hlTp|5rnF6VPy_^gy~Ov}=gU^Ylnb+u;D z|(=a7nv5bAB5QR->ONF;3RkDnI zG=v3B@VGD3tV#s-gkYa`-x|NwPIR?6Xm6}xar=~OH6<&%Hr~~fR2F9EJ#Al&J}&G2 z7BBsNs1j?4U&QGYf zkUK~?CA$(WyJ@K;#v?JrPvKOi&6Myga(VJ#CDOxMGP5g__Cz{MHQe;9G|Snl(2gwj z+1%}27>L(>|!=xQF6L3{ldaStU(#f;e8@7Q-2J6_@#cQh;M81v)D z?D`x~RZkDr3Z}Ym=s;YCg5@qC@i5iqkhX#|LNlAd)x5q%M);UrJB8O^T-U6cmZP_I zqTOiuG5e@5uX&NmGNB}`@ijDnW!yR(Q4Y0V_e7M${kr?6Dw)5m`}3^xAecT0T%G6b z9}gb+8Bo243rbHASNEK)xhN&n7sJocj|5r8v%oFx!3|x0BraOqgB!Ynpnl>fvKeqx zw$_I2J%D4}S{sf-7{J_G8+I=NXj3+Bt+muS;B%2@sdK;CRZ-qYvm?V?{KRm zvW*yb{zXO-w(yFq=kV(gC$0`@jg}8W!fnH9%5c92i((qqU6|gZmAp5S$Vb!b$Z#OD zvILFTF1S|F92wfNb5ek-2q$9K!pDy02`6K`NfE97Jn%CpbPMuA>h_d%5=x5Jj3)C! zwC*u7za9M%t$!LwMr`cKfP4Q0pcUhRs?h=!#E$Wp+h_yP^F|pjKLfCQAW00XgG7y+ zkrQEdA`xxsg@&rYnIX}BitoK>k!UmPYQ^NV(H7?0hP9lG`~Q(-g_yetWU-eaPppg; zQ5BDsv*N0e?^s*3fC<%{); zRjc}0caxxIHF+drbqr7{9=eUbhq}aivustDSV7n2QPMTs1N>wHVwlqFnd2cCKIf<( zjEH#{x|OqM!ZwX02nRD25%h(UYOmxKvWJmP!?!#{!5wMwN*@JH#hM}rkpAx=(c){n}Qshg8Nq(6eYsv9S%@M;+K6q(}&#_i<>@>3f zO?;d9o((BR(NyU+ap~HtMvD`dr&whsvR>uXGt3W$@d^f(Wjr|oji!v#*AW$`ar)8; zs>#aqG9-LHD05dhCQ5 zMB*{&v1tSihsUJHP9n@RkjW#&W71 zfG74@=G#sOxqXiL35Um|$1Z1n(%~`bu`53hIOFh`bOq;}YQkSX9qjW)+>Y&dlLhgZ z^w@1=g1h)cxLpb|Tsw9%Z(bw@!pOyL5s=5E$L^qfxcwle9&EnDXYmx9T>&=t_-yX{ zSF+(T>9L){hR3AG?yX0zVaqY;u^VqkqKxtwWn^bNJSIJMKeLlgfnx0@oOfQNG~Xrf zf^$g}@B@UK93GP%dyqISMme({1X#i4Hjeq^G3jatirZq3dlOd@JSN>f>I{^a;0fpU z1j*$I=l0Q54WpboU}KC3lV&5tW76%3{{domkUg1?Bq}DyO7(=vagr-crcU#j9P2T` zG3i^O40d}OIqC+X^9Hw4$PGg0&#Jfi;HmRAbyD3RboLQeHwc|~2&)@}&bx%w4MOKV z!YxTEt7FIsW`mOVk&!8hQAs|3;)EnIHfga;OA-^4eE!6VNTNMS{dJ;}n4TO={jjlH z1UCqiUn5%FY(Szj$r~q5Lhk%6O~y#0pFc^WkqjqgUW=dANj`t#&d;R!MA4$}=2o zlDHwsyKBxMN$g1S`4dO)+)DEK6KALhx;yzU(T1Ccp&b4ENjx?k*p;udOudQA*~Woz|2ZwWnz)_nr#a00&vlHyyFR=Iw?^3xN1YE=13kBQ-RP{_q`R9PO6MtDF zb~6ch+b~hfoZKxOEf$AHZ9W6IssTgBthxx}KUDQR`Yl}bRdl6QbrISuQq>Fj(W+DN z9nX(oufk+ie+#1zzoAYTt+KjVOxy*GWce-Q!O^)Cm&g5LyGnT$$yx5aKJ{ zD{ChZJRLHn5|k@kVA8igM=`$_^Y&mxlK9g|7 zxg675dLiMc^D5y*gk!bz@6wCO29~Uxd3^y(g<`O#>02hSgs-yXTT}@@Bv*kgSkv^) zd~~sH1r9yGg_MRpkD{gj{UXv0Wl1;Q0Ir5Jjy!InidoL7%)gDSF{_whXr~{zg#=QS z2US7uk>DZ1meEUfas9|=fK@daR=g{hUQJjm%2IX=eiQR}sz_ zZZdNo4>d?kCByRxDlIq_kThC_;pQ`6c%C@xAwcHB-jF{rgXk9txPjmo1^g2cE*7wv zgi9u-6&v=xtrJ!i5JM>GLh&Kf?pQ!--&SfFF|J54Ci*Z$)iUZhs%*%B}wsqKD|$lj(RS|jm==2xtDC&>$zMb zK&8OBD#~j)T!`fI++J=wRMcEG(ep+*FaHRCT2DiC+;cVOBPYh}cp_I9hZu@+y<$x7 zJ=a_5A6Fu|0`oEI>AmL~{)-85cB_VcinLtIRRx~ns*(ZAt(aL{?oAvy)-NAv2WXFl zd3h>-SbvOMc>p|r_;&a%Fc=JokDoB&(|ju9KLNQe-!gu9KLNQKY{S5dcJKZe>AHy(c#;6@)Mcg?(l6p`AM$= z?r_dyxsy2ScRGCAPJR+6?~M-Mwv(SkmtwcWWBnBTh{Lz-A&!0o2h@?=f~~0Ze?fcnt6mv)z{Ff z2!f(mvq~N>tO`6{ST`UI9QAl%T`Lb^k;e<`+SqRD@xr=6%vO&V)(vJus>ciKh7eYd z7uF4BQR?x+x?!Ykf{M|7lE(|{hEK$0yi*0=cy}5$^u_NdPkA*-uS)i>!&j5^N+~U; z744NKY&m>2Nv{msmu@+mJi~W+o$4pQcK!}uXqG1b7>cDr0KCg5V21}tw(*rE%O1!bO2K=cD_FVOh6Zd4~MulmM&d(*!w-NAhC`{tg`!sb&C5X7NbPVuDdf5UE{9 zkO7UT?C^GM2I%8?)Y1J8prHWdXfD$zdk<`4TlyfUjHW)el{GA*sgG@=aAhXJ>ji-w z727Td?AO>WLJ}pg z_G8n4hp1F|aRZe$ryZz`pVrz!{4X0|nI4NVcRB!=rBIR)1N#;M88NW$pnT|Fi5P&*ch>oA zb_Lkn8jy?kuM2usAkzVUS=Dk+aqNp`lyh=F}Svy&Dh2KH{k zd5aMP`@7^_uoyA0A0XUhF=AjpNSqeKm7<{*xn0-IhtK)xcB3mLrj?Hh=DV)0y!0foXKl^CdW$kgvoJ|D@>+d3IxT3kT7ZE zp!f;cO5nh0pN0!k%nlEuw^6I#Y~-BoZbCUdqQLa1N3r zR;17qIQ+=`BCf1XF$$8%$s0J=r5FWC1dl#Vz$NxSmgJWqmCkzm?cV5O;D&cMWT9Ta3{qu4l!QuuAWt z^Bn1C(M{Gsw3oSW;+o{n@^aHghEb3#qacYfCiAn5f+WT&SVDwH2wb)kwJ84r%PeE) zqkMya41JVeDBvzgR#8Ji+E@uYF_-+ ze868#4)`f>Q{&f5Sun3FKpRQzK7JdG7it-p1 zeg1Tsuw~KbPiI&bR<<+AsPHcE9h>e)^%KbFGx{||s3C+ai`WFi0H+#>8fs%zo0#F) zT;&SYBmg!1LMC5}68au1-cMl-lx$k-GA=Me8<|n7PFBm5KL)DEyg5dug2e+|YGjg1 z(RjpHrjn8;EuMarNf9|C3YbZ6MQdDcJqOjwWS&9(9nvG2EPLclHT;+@gL17(|Itg2 zL1<_)2y>r7PIws9Vq-RWD>_$rWGjoknw9cZuVyQYy_%JVR=t|7EcR-)ve>J@hwQ3X zvz5hO%~lqBHCtKi)oi8os`WcKDcLmjaE8op*$maR!y1Fu%Vx!&H9~wAESuw0m2C!Q zt}*lo!R3krv*@neC z)Oo?Sz?ScbsUuEQ1!`Q1cLdVXzGIADcbaZY(oc&^wq}m%~>&q|6T3$ob z7wZ-CS5xKUoWcaA{#&Ky6{?tehV=|@x?^o&6uJIJC2w0>;F}uF=T!2}wS{#|{*HXH zS}J_;D5PFirR-c=pp`LSVQ=8}Y~fGj`+J2t9&JPga%?J@v<_pl(mJM5Z;n6-yy?v~swD=oCBmCSy_om7DZ6j3@Z$x{ERT`y|FRW?opxCn> zK2?d_crUN6dqW>%(m068D<0+Y0-rwh|Dph{XZTU=-lbahi8ZR-uTsgUkR3@C=i;tK{ozAetkwy!w-vUm%l%b+2ro;P{wbgE4V5V7q7IM2rJ0`wKZ1A+riY z74_dItr$N;(;loyLAwOBszSZ^~8SFxd{X+XuE7mmxY+ATAX zIcgOfevxqVFnou(iVd}_2k712E^ej49vt?1nA1pTz>!4X3V$VZ@mC0P6&t!lK(*yY zK(1m#R}kbG4^QLQJ8YM5&%<_CGgoc0L5+>@@9Hh?pVT(%Q%pG1mU>LIFNfJVb^6G$Q{Rr z43aM6K<;=hatbcvK<-h@Z*dt1awiZTm1G>qJ(|^-=rRuEPGo+&%Q%obX#u!(xaYCl zNtfbkr^`5yJLz%28(jvt-AR)G?{*pBR`4S(<3R4D=OGUQ+*FaZsFhUTG#o}f5?feL zhf$BjR`!6ys7FFxCy$%Y0IwH>zYyFm2vm=RyiPtYQIE0{o&yV)QIE1|1Pzx_kFt{p zGa$s7IN4oxIDaN7-lBgPH9z>QSa%C+{-q zQFb}=lP;qkWmnDvoN@aTU*Md}s7Kk?Uq(^b%4L`BxPS#Q>QSa%C+{-qQKnxfUul=! zd>s%{jCz#a!m*!X)T8VU%18R|e9xy>?~zyZ`aSZXzw=qrGu%3Z;7W?&j`E}af<{O&Qc*rZav7;8SMQN8r){Dp36o|+-XmW= zaT;3C%M98>VKf63}HeQ6eex3mC%Cn_OBtQY(qu)nN)iY!HSB< zfo-^qYg8mvw=%9#QAs%AGOkgPBAj#?*QiJn&bW+gRAdO}UB)#kvXr{crL$NemZab^ zu2E6VnzXo#YgE)wpmvvcKPqa8zfQeCzM}qD$cjtIBKgLjIW!ouNdB4p4VNK{-0bvPcd$PeVES#PG`4DyT-5A&cadaS2%@x3a!2Ll((x1PzxVi{v$|x$QD!k-UCA z31Ct<*rGOhhz7C-qJhjck&xUoz1*~sW5~j0$Rat$WWLRiMRKfy8L~(oA+W=cMd}MI z(_zRWwLw6JEK(N=xC{prsco4H~mm!PHVCq)VWym5k zgmB(v$Rab8MHO6zEHcAL%Uf(zbcu#!h9_}3%#cO4;@<$qC1jDU`#ss`#UnO+pq`l`PC<$f7Ex{1S#Ns?vll zmm!O)49jBR6c=*X5X_2};k)KFV9Ys?@I~;~A+>OkL{|oqT%nxj%OS6Ug+NyjUHf6rG*p&I! zVpHZ@i%pqtEjDGowb+#T)?!oUTZ>JZZ!I=uzO~qt`PSzl_H>tVg8U$M{tTHf@`I@x z9WF;)eu(%xM)+}5F+cRP_^!K|i;hpxt;5mmdWqiaFU;&@JFc9K2FFLQ)Ul5FISQzk z_nCH5LM|uk<&}t?Z0Ru8p1oxadHzovLv^ z^5zp54G)t#M`~|9Hb-blt%S~%P*!`CnBt)B#tc7)1@W3XN z)nm```yIWfZ%>YaBzjM=w}jJoAGg9%hc8}%>-v@>!4G-#-Xhjd-W>A368;G<|E#0;D4T!6%UX<@zvbvXGWnl&^d4pU;G_4vqx87u zkL58CjMT&UHl6MR!t8n+`kQ{UnHLG-*w8iU>l%v5pRCEunThuW=&O&cNk7o1cy;%h zbfl)3+_@(GV0|&UV@>vc7VG|8IKR3kJNif@6K^4j%^_L7*w!p7hmfI7C+4srq?~tt z!<+uF2F8qFVkf%pMF4UFi;E>AszPd=j`5mgl8I#6M(kZ=8pmP!w2bz{e4Ehc(?A_; z828Up#(+T)et7KP-yQ5x5gxMC=HY;0owdNxVI6|B6u02l3*Zp$8Ngw$2Lm`NRP%Y} z7DF|q0TH!dJo*NWv+Ng-{#j})<|g{~w?M1*i%0hnR{O=H?+{k|#iQ>MF35|DqVEw_ z2TDZ^lL>X8RMeD&I#4Pal7u=?Dr!kW9ViuzNJ1Sb6^%+l9Vi9&ncL*lfl|@9xd#b# zpj0$rQeb6nqDe_8a}!O;p_|IwMD?;m-d7L}p7a^bn?D9Ob)ZzV&irpA)PYjbzVgx` zb)Zyqpe$n4fl|>{No0$dTi(@4pV6Trn=&`i;pSeHqn8~q zyxajE50@QLyoI_<*IrQJehYt$zh9oBZN!EKF_k ziw|P9+T<4>Or2Ak{Nh6ht4)6Kp)5*m@{7y6RJa16&dUlUKKvWFEGrPVA_rM*S%J89 z>j7uD0&#miCIw0$t)8&ya0TM_CLGFe1>zP6haIj!+y=sy!xf0z_)V~h$ZlG<&o7Z* z=5Ph#Hr=or7@0;;#Tz3h5oYU%v&`qRA}146@y5uiuaJuI z#>i^&H6-2`3B(&CpJl#^H%0>S#>nN&SMkQkm6$+vyivg_-Wd5hUmB3dPLs%vJ6RCp zjgdgSF{0y*Wp?Cd1_{d*_;tgsym zv=VkKXV@`vFGJ)y>=?Q6GeD`JJVpiCsjy?@erBt%V`MjB6?TjS!j6$Z*fH`TaawQ> z0et=qpzhGJmgu+}kt}DdF?tjq>n>-QFgihU877P#&3-dtR2IG;MksZxF*=dF$_7Oz zzv?qNR_Y{7j+0zrGSz_9P)rC36FiKikIQ4oG1~qxcqDt_YUMdB5$EOuPHc#k@4&CD zDPt9KMPiV#r0QzMAY+w;RSYtgQeDj$WGqcs#UNuD!YT$C%dQ8kVvw;M^HmHoR?Ql! z7-X!5(L@!4jMWlighAY75FWE5Cw#CwzlmzovgmL-WogWd3mxy9@_2%Qten zXo)g%H2pgSxj>8BtXlfFr1~SNzN@JQ`BZ#ki=z6YN0t34i+=GEjXTW8o#o@c=;5X- zU`@Aa@InC}|5*<|doy`IeVoQ^^>JVDai7+>IXV5|Y4!*<9B1AWLKXx+ zG*cf)O*g7uV)F5~7OFNm$>&O!Qq}Hp#dUgS4;$lgssZkE=08vIe?~O4S9L~D-XN<+XTen31H!Nb8N=>UiRTp(apa%DR`@4*`sEnf0Ie6Ehw&oOO}Ni%7n;2VQiT!bvGfs}WUd^~9&H$o z8pnA&d$jpG$Ts3%oC>&w{WLbtx3$75<4@Sa=lKsqm|b6`48nO*i42oUWSFdE=uG`qGw|YvEcIlCx{$Lz z)X*GuH8>xl5tm9iEXjnsZx$AleD!d~JD!PNE1Vlb)>bxlD6Xnk-Wd5QY!+rqdv$ z7?}n%M79-t!8Ouc&6PhL6BJc>f*P=wNbJ6Ol7z^)JY#?5#S6A4-#eR`KDRx8Ht1??W*e727qh9@EMdqsY z(LYB^%d@P1auL3EeTbSUZ4&K*Zh1;(mnw!+su*!3*&Wa=Du(N|M#5_ioOR=Mf@+QO zv{_WMimE^&S!4~pDuX(aWvW#5(q2D6zdS|D7L`Ypk)!5SS!2G77$V~S2 z)fnTXn;Q2k)p+b<3l4x5Pj~xEi$jKkyb;%p&%v#F#Fdm_7y~@~l6*GJz#@e|uneQM z)hLe5KpBS7=GUUsCz8CH03aWD>{&Xf)eUu(V2Cc^vJL|%?6^%cE^P5eNu6{DoJ z)++|~&{N*0;qlq(a|_iRw#b3uKt^7K7l zI-;t3YH^LH#kEB(_VhI<65F{x*d=}^Qal{;#@Q7zP_G78~maV(9s{lJRM;28!oNvl=e5xlAcTtV3xdIDp$Q!5$q)zqJUAW z3^pn!wp6eevDLsU3Z3osVpiws2{TvJuqscVaGaUf0m^DsQ+;ZB_IIt<-*v_Q?p128 z>Xo_j`cx)<>D6Ev%xLgCB{(6YPlNe^?nn0quc&VP>XB%KreMBDAy-O_ncwkLq<$1< zQhHc5MQQdm&KCvbL~GIdrsw$nK4MR^a!{#i9*hD4Dmb86eU=D&rY%>gMiwnvpa7{# ziA5`^N_Tr!Iwpd%Jjp(+GjRYN?>-ATo<_t0i2JsmiMMn_?8l)CsCZ9P790=%Y<(}P zd7T=ay_9;_>+aNs=l!%@biLU7V?^T`eMRay%l6S7sCCY>WjfiHtUSf-7i3eS6gU*g z8`2b@#n-n$d7@YSi&sj94(9IS+^SgXF>!G4N`QvrWq{Ak*J~+dpidLfYwdrx2CtP= zqOEjD4GJ<36pT51e^f~q_Aq)%fg>eZwqXn}ic=!Yeg~3gOh3RY*w0F- zbWH5Wm;Knhg6=~&?G53KH-xjnA(snIG4KtFQw;nA<+be3Gbo+7=+oLoXFE83sBv|` zX`|R-CA|@FZ>itK@#O2B)-HIuK?P{?y7?pd1pgbm*>fxQ>-=@sft;rURh|xXcm9G} zP!rSwoM@u7psuIC5Ln$RyI1cIRDY(GVcI*G?+tCaQuGD`mP_}o=M8GpSX6=_bDAYj z2?8cn4=*aufmESrUArq4S3cUQ6YE-Pr}`JK7S}*MEzZH7D$+Ly*r@+AhUR@WFsM%l zSbp@>r)p14seu8f0f(A;{h{=%u9(3N>Q%JqJ(iaBrJYyQM8DHz1}pd)8t6&6LM;q* zU!&Kpp3-R_p(!Xsi7opO`WF}y)aRnZ8W2W?%l{eW2~I)jpt4|L|Z!FbH6Hvzq3QpfH7;S0yo$+5dH;Kc!4FAk6>Dz{p$b&r?^+wNnH zYbj^Ad;9k6iv7k3v_l=N3>&#PMU)P}-ob7w89#+03o>X3B6jOv1i^x1)pND|AsSef z1t<^D;U!){sXu2Gm6WUgNU6Ds7Gn%C4I-v)t0kA?g*)RajI^KiRI$GQvjdsIh-01K zD?R7&UV7B&>6sRp2304$#g$GLToapYU<4Zo!1e2HZ@o!g1#KothN z%9iyOS1rE8rAC$<`j zFIGT}G|#3|HIguZy4yjU_rcTt`)fhbAbGY42FVLxzmHT-X$9h*?Q)AIisB`_G0J-| z0bl8372A`=QFiqI&ix_3KLVO}0Oi$6<0-H16`d@qa6sKOqe5xNcK2~hyZ3$d*6aGB z5e}60i3yY2SagR;8Ux=j9{pwqEvr6J6 zo?2gG)Sz4OQaKi%^88RMSwqr1s-esuDa=Kfm@ zwcp%`~&+EujZzDAbL&s^9tA`)1Uc$Z|8$|w;4n#l+tsD z1-C+QXN9ged4J@MG(96?#YlE>af)4nypI@&T`TQ?6)x`D+pkg3s?u9`p6+ljF6Q;W z-|anBg_FD=_$Y3pDb=;$RIe35vp!Hfni}P8q0lN6xH-a^|DaNhD&AWTsHRru0a_Z( z2)C5?6A)pEB{!5kOD68aCllD;GJ#Pyl;7XoS_L|(o3+xN)P0|X=TsK&>IGQnem>9? z_7Arzr6G|I4!f5cn6jdQ`N$jddfJ2HO?Z*Y-~GwmTLH_H^T%+Y-E`Aem6~qZ)a3=C zs)KYTi?y0!?{Ylyjz_@4*Lhnx4|E3&@%qwX`N2c1I1L0hFCW12zkeT<_K3?Kp#|N~ z*2!XLePr9;v$MESLhdYO)eVpwqzvqCs4DHkJj&KhiX)hc&8-F#+h1Q*8MS^_!Az^J z(gUNrx7ZU=Yl7D$+B)|}zvA&gy`J-SPUwq`UJn<8IDzRwGwi+x>42t}(e!}&e87Ej zzXCm#xnv1gqOjeTfY>vPeM-8_5=6DfPOkX*2e2WYcKmPJ#uL2BmsWb1$r{br^OP;R z6nM6Qb*fShl()|l##!lFb@8Tl$vjz8%rChS0s9cV;%g_ImiOsPt|9|UvES$u6s=qI z$!E?fy?Z#4qsX&u#T!8TlR=N2?v89AYEf#x4&=)GeVW5g_#d?`Ts?8%?G5sFYVh%e zKu_WI$KK4(xuME$-<}pCuO}aERXj7Nlb(^&Nj?t4Vsx^oJHEx!cBeS&1WMFB3P)Ik z3tZ7uSQB|yN|nerfqq4L8lLWpL`2iJ`ZaJt+UHA+rkZQ zRY??^7pqWjt4g`I9Ifz{qu%327!T}*N>5Pi@Anp}YzR8xKv4_TKvSrUEElTpyA4LX z7Ca-Q)}DAir$*IlgXuqPhs}ISizlU#OJVAYU5R~E-S-XF7q1ezx6+&adiQ!XczgDA z2X}vhqqKuPze6K`uy0w~QJ?I>zyLeI<7CB#R<1xXt`M*|oXqP_3f}#63>G=d|sgAfsji&}Dlm=r*RdKiS{s*kCvJBYZ zp!c2Q7>U^L63=VL5Bqdnu&GL>Wq3uN5oF6`N@pnV5l^lC^pOJX zwqFzVw`+5$u6CbzKF-$ZsfWc7MXAx>?<}mHB=6a3-B=7!d<>1{O{lgvp?=gs9~|vv z!NDAOR!JT`SA#j}`O9!#sPU=dP*TP;9n>w);n7V(bqYk-OIokQ2V~m?8ms7i!$6nl zYhYPNeXaJ~T+i#)jb98b^tA9r7rgY^0X(S>snBd2Z`ISYkAjWf{VB;(z3;iv{?fIe>PsqYrO8B=K%^p1HFb5A42ld64QJe3S;8KcEkU+&LxZHwk=(@ zAybLPyQ*V>6X7%R?RI(Ioh)Ck!N7OxnHzr`wJ<>Cd%1B|0( z=FeTRWa*02XD?Ycw*-4-5qf}?y_YIQHZ*>V!(#_srOJ&z4;?wrmAN+p}qP>zYJ9dkm zM!9$^1`9@gcWuT0t@iwFDC|REk<5OS-%`=5hDgQ_0~z)YXKb^7@Go}buB|p$hgV%4 zE^DK!K(_sZ`?hS|0$J@nTkJjPkr%dr zZF-A+^W-z_AJ}_vf*&hZh}tvSP)zuhOwId*vYSe^V%oG5#o&F=TuX-#te?2ki$8#`iM}CoY@aMgyU2!MG)h z#?PI%VDa4I@KmEVFg%MH-Uvj_aiE#CWCb`KdF+Yf7IElei1)~y&0OPgsm_o7S5#-* z+{G)F&0M&jDg~~nYF&&tNXYmd7QH=t>HWIkL)+%RqnkgdjMmmR|36g%im+(OV*c=N zuvf^%sWC8*bQ)#dltr9a-y23>lzPMHi#ZFHL1r)oynMm@#nN8v zv?a68oH=I>Yr!i>&0TRil^~d*U{3A}7mgT)6hhPr6>x=NKzpIr>{uk=#CPIQ@M4K5 zh3@ileKKG8LBl+6Z#Xyo$;+5%)+IpG2J~S|G-)C>NXM|>Dc7>Yh(mfZNjGxSwP!kHs+yl~3bCvqGUl%`` z;y!=g-d(%G*<*J3pL;st26oy*?Tn2z!({uk$xmK(&Wyq5?OkoB=dWL7&+pu|%6{Em z-??kcS(M>0a5>8^?0w@}d%jv8MD44i_SThq?bWKbPehfll8vlzR6Jy9GW*b|y=T*2 zd)4ajysJYI_#iK#e?kUdf%!4{Bmeld;``6t0ay1QYxQA?=s7BixrYZ;F?&|JH}*ogKQJof-7 zvkw^l_#pQH#NFHjChMLXE_RV`akCYv{ z>p6Rdz1}|6ZbSl>eTKbfm3``A2w{B~uAhqi)vE$E1ciCHSe*N&tb_0$K z-PN|~vghn=_VMAR)5Dp&nPazsq~QgC=RFr{spQ>6K1VXR-gam)o0PV|1B%W15XW}nTAzYvy2MN z>ow)+Tv5Pt)aDvizw*;hB4gXB=Xc`gno|*?KPY=@s9$(lZ3|Dhwh!cs_m*@?8PmKGmc$;|$qNqk zxSOW#lKm6xHLca(6tV5OT%gSV_vXyN?BBD>pRADnAuFWfEVO9m($hOYJ+BL&I?Y!sLW6DBoZhAU2BE8-|?N3i4 z_BQ6c=a4%xJ=y;Bd3)z$iV7W6h1lErP+R)4LG~*9r@y25A3WK{oMP`CJQOEIC_^tEyDli&h>lzf46L(JVI4KYSIriA+Z0yVUy?2pFCv!rd@k)4jr6cIe5GM z{PtB({$LfRS4gG4rl6Gu%a_Wt_YOrsQfBE*dqan&Lu0G#1&<(O4;yx5NyAd~k9(IJ^k zCPT9^TaqeJnxgm=rA2(GKvLu>OH*)1CLk&*VR_<45M1y{Kz%%)lA=CE{eOSUxpU`c zQc7vx-_MhQX6AnH@BYp?zw9URLPsji zZzEuqy~LMq4D?`bzPpj0fc6x3RrKp0w@PK?JWxDfPeU%VG>CQPFEl1x0^NUVN-#=8AIW^I?qtceEOxRe$XKmH%rI-T&pmu{c}Dz^ikG z5Z?Azj_Oi^oDtp9Sgf|QnkQ8M*Mqsa$Jyw;hX-oip;%Z3*N7g2ZsVOa!{f=CD9#G+ z>g?^CiQo<&1tT@5Ux#hV9%v%xm93FYVYCfe6@;}y8877@z#+-FrrxE4G(0{7=VH;v ze`a0<0=SFT)s)#&Dk`_x2Wq<4*^lqp)@VOlLyO&f{vA9O7q~s(AKQ?;w&>cTOV8hc zSwpN7oU-qUnmw4(yT5IHTgTPDd8gR#^LOl8fqxhKJG1^R_wU$6|2AB;;i}TB{1beO z^R8Zh^|Gs%Ub7DWExpE9bh5qVo+Ued=bU`cl6xxgZ^=ErqA9+mbV&d~xcNY(>pygx z{!Lh2R{Yqu#v1#qKXg6!_|Snt|Cq$A-sDRNF?V$}?(MSo_$MOR+;yGZ^KqYhp~9~A84j6=kl93Z?@Gq!i>JLoj#<|CG+)AO3l~tc@;%HJ!yYu zp?}=%>0)w?{a6<=%Fn;-J@oU--0E)+G%bCD+Ycd1w^jdL*0+=%<5kbH=y&ce|F{(bf*z*EA54E-kA1JxZRKS-f92X+x_kMzH=s40GC$S`GfxPi~9T**}MEJx8SS5 zzh;Ynti9IXz8^Mne;F3n!Y1DCALm=1x6Q7=)Ys-bS~zmM`{r0*S#EH~GD-nMGT(wz zebuMfvuo^Vg}n!31^ijIZpiNI<$*#?5eN|*w2@=GEAubiUDJKw*}fXwrSVA;|8*_x z8W2*f>%f0h#+vlfetTLm{uR-81xAAUKL;AGg(CQ@)8DpQ!(Kf2=doI{`0H(p#qV|G zaudm7ZQH39YkJ-x=FxM`ykp+HXzxIJ(B9@x!H69H;F5|62LAAHdLQ9N_y{+`rnej6 zKW`&E)lt-`!<5%EgS6?5zh6U?t5S`=udTS2^qC zbl*+(R#4iD?OyvpUl)E>a0KiUj({~Dy9n4D%-B)%<){S7{y$8l{qIJOas^h7YV*@Z zhOZp2s2qbBoU1keZ@ zgqJzWRNSzTRBo#UPM(+-kgQP=jDZPrAsLy3LpsKcg8VSdD5yprNa1Gg=oMmKBP<t#B;vs9|YtVb=$Im6LtN`EUIH?0nyxT$J-B`{w5R z=H>fJ@OLui_+0-_Mpv=eHW$!SEKE-D}j0%5qfhE`b zXt_<%AhPw)gef8;bGDNe>5j5`p9$ef+*jz@7xeXD`CvQNG2K0_!V2G`sYy#s2YycsIEM z|J{T}Me!X!y*TanoqHm_@&fwfgyXa3oq+LFo&D+clgf9^B>;;dy?FjzRvad&gDZXJ2~h(XL1d4)1Pebttpmy z-9#Xg>aOvREga;6ZJ(3IH)2YKPDuqAS2%b$1-^<4JhqTyKmo{RABVECMKf11lCuf{*SFugn7wL4i+IfTg4P;v-G$e&|Rvx|oO zod{_q3;ZW-sq~L4>`(Xg@1t2@#Mw!J-FvP)w=(O}Kc=9jcnD(d+TD9#D06FYA1vz) z??B9q!*+QAmFh!wahF|_^mo|1qW&EP{)r7FCB(gEM{U}P?MKv%IwipPY?Jyycn)yS?!G5foBFcOP4uoSEIC*-ep`z zwv>1O$QT`2SW<$XW26lx4%NXQ1?R_6KbCry=4I;P&5b{()^7fc*4jyC`ciE+-nq=D zmo}wO<0|mm4A`4lrfUNqs3|s8L%mI}{ZfB-J8UEMQ|;Zo{i&g?9E|u5+q18{ZO{Ip z_F!-nYM6tRrCh`A%G!iCglleAJoCjv?^*R<#%a28IM_ZcpF%9nO`$^ zC@q$TjmZ<-EYwZ8=3KT+`ANGX0vFBLxkumw^&Yez5pzf0n6Xc?bCJ!CfV~#zC?EM# z?Y(wBY!e(R@#E-0_;F)A*Aog~%D8d+M(|tLRa`xL8T{7c;qysy?8xOX(B+c?N<60iOy$ZVReF&Dczf^<8wKX-x14H5>^kBq#Bnxkj zf{Sn@8`J%h#77PpiGBmoYjoMX!RBmQB28@AE-9|i!`to72+jMVI)cB{t3G<4_Nw>g z<@wH^Z2z0RhxX9h*AuaauoGOnZ}#Lq#76qk+y%<$p8Bj0q%lB9gA)Cu&v*U=?nKuH z{Q0-n_-7T`vh|#Myb$T!)1FTE_fSuY9=XTqbsy@pcSQE(=mJfgXU1aFSNHEurz^5z z5f!t}jidlFHxr+rfW#apPLg_7ZfXcAfUs<_Jv*6-Br#Z-jJN*sQx#XwnNgfhm!OBo z8wu#&u`p(6cXFS^iG1fG7{mdG0hpWg?(8^2@-+&WOhTzdI3{j^vD6O0@j`@+{Lupc zS%`9sD;(ZUEXt{|r($`%-oqAs6_vQ#)kXLB@qNgLHbeCD(kDvW z&n}DK_pTGTU~2<*Gd7Z;!4$Y3DF+$Hjm&^Hfjm?enhb*j$bMFUE!}UYAc_M2A{lI}`I`qL?Bk$=pq{v8S5 zd8bBp4|XG1HN#hUYGhk4kF62xLqHB|!8q_n<>ds~?d!9z=L-|vB-NzBG#(kyN1%yW zgXDqX4@@YuUmaA1N$<9&weN$y+ZFJ-uY=&rjItWT*X8DoYmzhfqW`X$-*O zIZsCMp!68=`=*~_2zt9R1PB9mciYp^2N&n3w$39@*pBexygUj;wvQBw+&a&m&Fw7T zX=l<$|BAiXIrw{218j#g4S8674R6=>hBFIC^t$RlNq=wp9cSmU5jtxOWQ^a4&Kg%H zf&$&ho-4@!W(HS~tnC260}~#(=So2CnJWR}ou)N&CAg(ivT!FUBRRL21C@KO#5JR; zgI8Daa=68GSKJpzOzi)TJk5&)soVbPceUG|kmnebRM!9+@m4#TZa;tk(9jTCw%gtu zu={DN+5RDPa`sEy_LJ@Xul2u1Wa+Lh^gYR*0ff^lBX&1-hpn*JMeO9qTl-+BD~jxr z3V*{c|7lxh@RQedV-K<8Z%@;L7h#p^Pj%T9uqh|P!1Q(xAv{>g^ObjEhRJ6wM$X@E z>u+kS>k(F*9_}kv?zi9%6&iiBFHWPmde@BQ+*-oj;Jw}_x#+|Ec2`^Zr!)m`*y=y_ zLv8h^=h?H3AA$E{(A0R!uQy3Ej%dv09t;76yA&QIS0uu&2)t8xREBJ%sYLLNq=r)M zTm6#?vD4t5R3rrpn~J7#n3X;=Z@-T|L{K;~i}45ZsJ`e<+WzaUw|LjT$JdQD_c>b|+P>#(o zV)zy??*87D=Ap+Mu11G`ec1X`8BiVd&8yXgaCtJv*g+wK;$DTw7Q~D+VDYm@8X3Th zGz4+hikd+J;KN(D=^El-=~ZThdhUS=*m?#kK(YoZ(AXT~4qc;#6ij+L3UMJhMj^QC zmCqZDLXaJ@Ef@b%ZOd7CL%qERy3<_){J%Zz*>qQ5dsnYLxV3nwE8XjM5c=)ev(Bw4 zp`}uYLG-43ch_LC0XJcaillurrsCv{er#ufw%tF}WADYbSxJm$_8ok@7msv-Vlu`z zy3e4Gz_kG;Igd#|&_hHS2a`sPn zYI}R5nSEfcL%b2Ha3eswbY(=Ahj=zH<|_^_3IFwtWk^nY5*ID%*gNS zekh%sb&fxNqkqDdv-y;kfUWns?A6P$Xs&C}^dO2quw0VWOMA`oY@TVHvXbOCJ`4Kg z`8$LFYrV2ky~*EpyMMwilPs_2%OrZIlUKg+!18WaXENv{GPc0prup_T@W*cVpIG1$ zk;ypI*=tI3@*D4D+Wlmy>mpNNX5{2#T)`d`7cs+6ciAru(#np!ZY)C-b$Ku_l<})k zj0YL(tO{NlMwCSmL9_Yh%4~_ zbL>m}+Y0>WZRwRh^d@$m&pB3o=%KoY!|%dey<+a}^X-5hy%**ZsM`^z-|k(By=?Ea zr5=S3s6gar01Gy^+IynuttIL9^bgMRpH=9@kl>a~v%i4x-IuW6+MW2#}k0ylpL>}Rph9e|YGPk+(J=rtU%RC_;GW$*y&a*hDMdNj50sHoUsgl2MS;h~!W z?ZoMF&RI1rCwB*j5g8vguMAX+2F&Owm`+` zkOV^klkTv0-$qtyWXCz&#r+#IF{JD_jTdG2m*B0e#Y?;J`qR>U+I44Q#^!wX;=w!c?npk4Pnns2+v3}N z=bdC%9()LQ4%&ML@4)vE(w~O&4G$9IB(+3DDf$o6Kwxlj@pZi^;@Zin@+l`peg2NM z{&99gdU4VI!Oz*f-QB(wlLrvV%-?IjyL%f``U)one1((kfh1lUo{T*V(VmL(g~{5$ zLFDG$w6`%5?((fV$sX`W68_Wdf<7v?DM+py^E(sV)O}kf+0%Y3)7rE<;5It25B&Bb zk@BoQvW#x_H}kb?9ej-dj^Q| z0?b`G`)yjS?Z?Y*{I!Ul_Y=JzOB4Lt?X{);NvL374KfE5hehJA@0oyqf|EI){WZcQ z3qIdjC;20I59KtZY{J?1^+Mz~VP+g>&-lj`6n7<;;{V=mo@Kffis!S=LjyZ%J>Ai_ zF-K-_hWC%hYPa9Y+Lj0w_9D%rCKopprPO!;QvPhMbc;AfG6Zo3j={*!2#CEdAI@Azh7+w%M#-&)$h zwzxm_(jFLZBB)n_*Jdo9i_J}!Vk@GW!IIs{ftvQ--o@BasrSC66}@vSYP#762;qfd zpY=LAgn#7rX@zL}i=(0U&9#X}s3?>$qsF<6(`Ip~p$u5xl*e92k(G4k@IMly;Px#bbn$vW-G)tpw2m{G=s2 znB6bw+bWY|l&J6`*{MqCbA$ zl1Tw!N^QnRfBf8f==HnNzG`!Kzfy5(lwUtTt~=rSW=*1}_XqCtEuTCv)Qhajx+lHy zV&Ekw2fnkWAY=t{yxdpJkKq6{RbiZ^Myw$#1WvFGZ^fKf2i51Lm$t)MHCN=@|>p1!~hNLhius6U)VGPcXv-v-G343PSjsC4Pi$SvY&wNp} zBT$oOS<`;J9qAO`N6k`-V*|uf%$J{@98G_Yqn8?ND(9G2-9;Q4)FR@Jk1K);JLoH? z!s0ax^Pm4p-}F3x{);#xuINFyIt9D%L_m&qBet?}FmX6;f8YvxcGn(J28dBsin8j7 zzEXyKd71e%Gm=tf%85p!IJYo7?{#XzdjX@C7U={vE=iT!wbE5gTGW<21R7oABX0xZ@S z1If=aW27>MYL?Etwx!Y%fp!dMQ47*xQ3gi&&Z3qudTpR<=#Hd4yU$myk^<_JS6f&Q z+0MY#ngE=7fk%c=vxhGR99PW`l8}uY_U9Iki*%YHMPX72|M8R)szegm>><3`L+vLc zGl_;~>=+4TRDfdeR1@7gJ|%4$Ws}5wc445`&XTVohV$Pqr+x=)l2%?IvK214??SCY zKx}_U`(}{*0;JvCTt-m^n97CZ#q2@yl({hhHodl6@_cceRD->i-ebN4lz4-hSh7X* z2a>XAl5;L~R~YCrHHC-J{Iu2r;&>CKd6s_SrSvs<_~Ap%`NutIXQ)OQeh@@OJEs}o zYR@BKqbsPP%#LO!oFOhYbSm;{1}751(MqEa+Iy*(dF%)I6240&1&WCnWg`EDTR!uX z21qq=+=D2^V%B9;6%kP_jRe7h%#NcTVVW^jP@H3(!-3HjASu3zFb* zWZK8Ph^dU(FWSA5?Mx9(zCm*wrEJ@UTLQCRwV&Y3<|w!*GWr*lHF5XRA5^_>=EUi< zxfr8eQp`$%O0<;ZEb{U14@3@iMP*h>dr}}m1=LI5Ok8IK?Wcvwhhi0_3Wd))ofOuG zr}5>de2?amvTCvf#_kG4vT4tI6STA61nnX7aK+$mWR6;Hk7<=XIPH`%ZsWArUfWmZ zdMn>=z`>_Q&YQ+g@Ctgg*uP`{`()d#>)~Aatm*iB)ZEO&*l6pJBsoGzxkq#yHPT~& zhetP^!$D;Cpy6X5iY?(SG;um9BI%qk3~6wLl8@GvLxTm$)TMbZv`g}&*FI#9HG!^);>Fw zUgqd)y$Vy91izi22p$_26rqTR9)pdbhI0%yR-Z!_cpg8Z4fq}-sb|MWa#(_l*)Vfn zco^gLOzmNX@}H3R z;L9odfc!;KG?U6=%H;;hH{BUTuy|)|hgicR2B2Z{oqR1 zqFQ>{a4cHel-V4MZINjYXad<&Ksij%uz;qSsDv77i+potDXa0iW_X;P2w_Bqn=Y~} zhdFhkt!I@k3uEE}ie9Q8?lHJ`{)U+>c_eKyO*muXiA^hrk zqRUq@1(Oj^3}GGz;nF>O_I$U?S9%f_qTTUQKi$B@4Wl@1YPUUw$O`kj_w3n=MP&on z3>Gnj>-{^{Zdkc~)zZ~V)*xK+V4pp(7c0+Gd;0K_?V>4NJ@(*k`&4?~|DRWr*FV<( ziM%aji||HYU#hDSFUn$17rQ8V084jMU8#duFhmowzE81TYY1H5l^h18`-edpDmHf* z>0ST$L1JMxyqd@+j^eLJXZ55ZtHOjjFY!l!O1l^Lh~3T zlyUF4g<=SiX`XD~%%nDqTed~Z0A`9t5NGLy)3Bj|*$tZsbNFL2#(^Cp={jQ^m@8vm z#FS*5nj>9g3wvVBBJwiaqeG6fJvvZPo{S%)SyHp8MzRcblo1{qJ(F)Wi)se5gzQXL zJy)y7ZAxC>?kwYmt-D?wOm;nt11GjL?!yH3OE5o+Hq@^F@U|PauE9AKyEx#)Yf6YP zZNH4;2bWJi(772&#MBodAtQR5yyGRwRxqXTZs z+MI|sEytRN`f5@O)BRfruq3~Yzeg;|+)e$EMlB;P6n%Ci z6dEqj1+$GHv&L09UBeuP^qANhm(AoB&CTa68W~gfnPyB?KazLjX~wWL)IzlxvmT7` zeXT(iVtgLvA+R2cUO|)9POornzx-C(O~&57alK@%Dad+FU<9GL46)issQr=JNEOF| zh>8PC8Sxgey{89j`@6fbp9FRdXtW=%C?0q=b(4X5(tTY~1Y@yt>wOh?L4cbLruz8|oc8xO9kOz_P`K{T;pg&{7OB?K5X!p0yYS z>gvUUlXkp6glp`~kdpeI1by*Ymq7qW+`5mrzK1vI5o1%wz%7vFBJ}F|CGg=JI>r7P zn+vh1FW}NRXYB^=W-SdN(>v124fyHiZb4mya9JA*H7<))**atylm=P7RpEtYG6LJ-AY>g!fqAdy3 zB2{nk{2+dUqzNG{`WZ~@XsK-uyB=#x#4O6W6@oPl#(C5Sx^PP>ie#-IGQ2$;i(8H1 zrZy{7+f?O5L$uRvW zPlTJThNjlqHxTxwa8tN89-fUOAc7?&Mf|;HLsfM!9*RZV60<|iwcEoNfLWW>1j!We zA1XA`SXbL2>7l5|#*Wq&6gF62+u0P2G$yRJ_86+0GZ+jdW5G~sQ?ePQgosLl#X(dC zG99$)!%aBAlZrui$j1z}H6`O#u&p&tsRTofSlk&7Hn+xu5E6c;tYEw@+2GK#%W17^ zMFnD%jKx+h;rar4%8J&uu^>=a?ffGcY^$xGOH4u}HGI2@dgwh$#Y9y5bOE0HKmw=Yai*xc`3I{71#>x@#qtFXl<7J0 zHID-zv0#)$vj&UR*0t87!dVxy@-O1WL#TuKbD@t>RAPBceYnFSi9!kamg+2NRazPdBk zI$XtrbOKLHt5t>u5UXt>L)wZL!-%134=zy!-1Zit7>6A7(F+|pPC1#KITvF2x~j6~ zde{_@(QnzCVRKu3Z6aKs4O$V%tjQtBYJoDkJ~ zVn?t(o}lJuwv(XFs2UOepm~E5vWb+o#a4H?UR|+bkX|?#tq(Ru;|Z&_tu2UF7>)(W z6t<$J3hv(3B51{H(YO<}Rm?0CMYVn4@eFE)( z-p(l@C5Pn>H^he}v!MmY-G-wnvRtl^zSW5Qqa~7rs5f^;*4`IikUyLi6=7}7l+9|Q z0y+=TuogB8+7B7Az}H1*#iePok#+AXU>J?U^BPbasVjS$kisRG^?3rpIq68u|{3wDwX$czLj&nLLS-Qlx z(1KM7g`q&mGz<-Q`JrYABGDOaqqk(@@hG|*ttiYvNVBjaG!mi^hSkzUcG*y@!dnO7 z7-??Mkxe*}Y$LJ=a@2+%E!f%)uL9pJOvpu=2s{7)lv-VFvfc`}kOhTeAr15h&FBbY ziC|qAtpS}%TeJn;8gx2VU4Ea0!iw*x@Oitf6plQI!)L2b4`c)?&JdU`9kytUP7z#@mzrlyTx z2?}zJxc_NHHLA}Oq~GY|BdRQ-IMmk~;X382g5%{@X=+4NO(dycjMU5Bltlb!>+$fF zb4rHYG60##s!lWz6q$7v^}@Xu_tT^e(U$qt$l%Mhwo%_`!49Z!n#t@&)LLganKmeO zixmoZA_P^}>={B*!KT)BX@x7w$~NLUjyh#gA9Q{=d4+;D)HX+(I_VXbHpeIr zuZ!R?t+Sl&0vZCl+!_nQJ9oMjEqkVEkUog{%G8eB-3ar5Nh4MoqXb@CE9tv>G2;^- zy6;EZy#n4nySBxJ#lucir16BYX4GQg187gsQ12*0ZA+&G>qq_HDp)@{77D5^nocZ*4sJ3G2d=WjqXO96(njqjBUkp=*!Gn*NsB@X)Pd_8oOH>FC=_R-5#?V)miL!`*kp z-Akq`zqB^iLY;LZIl~YLx|@+I(e*s5WmWa2mC#E^Y(W__Iei8cC3BDEEFBEWNaizw zzDex7w3%T#g7F1qIM_fPqRCXbsU*`yQXh!E0KT%*!)VVRgpXAlZPHSOXyC^7I3{de zP26!^HnfyA!ZRoPNcxhgOf+6o>0}ScOIzLvol)&u*%8(5xvX--$}KC)P;zN4-lr~Y zjZr1j2m`}KRAPOShObWE)l?-cxFIbGY33RCh{qZv3epPdU4vf!m{VvlX@v1QWu~TA zA>U0@uxJcp<#27Y`V*y>I{pOr+R!=l9?5tejs8K;o@*S&oIC+|o-j=o*>Ua(Yg_7L zt&lgHR;pKV)wH7x(jYzJd{po~@4h6RP^PFu2Awen&$nVHrq*=P)7 zz|Nq0JbG#ixjFgcTts*Kg1t{b` zS!g!c(r4vzjA(?6DnhF!Wr7#k5;AE*!WadzglPl-$zqreVNs72lyMjhpqaq25}bz1 zhz3PG>o=@lUJ2I_9ex|Dt@^z#uWaR(>Kw0lQ;!A*uQdiQn2X|VBe;*=FhZTGnnrC* zrn=($W7rLj^)is!~x80_`s$gDUUN_BryfWDoj%{@k(Hu5u)si6%i^bMruZlGz-HoknUhX7c zr=f5}hBLy>7Kv7>ibY1gctbSYRBttokn`s1<~AhA_2S5bvU^FmsWRH)7BY(>T)(_F z9t{b-(WK>Q@~j%eNF3vC%1xQ)E&v0D;i7bMfEp>%&eXq6@2xM#m8|^mcd{18n$tq<^$3-F{BN%r}%@PZ`3L56J;<~dU4#&nA zdW>LIdz4~I5y(etmVTj;g=3NmhVQkpjBc#Xp$i!aZVJbfO>Yn^M8&+}fB`vgX04*p zf&{5~1RauKbzF21=?2xx1ks*?kbAT)sCj^km~5(z!3XIG?y$@i{0QhJJqT9J5jW;V?brt*(~y7XudIq~JcW>yzrRxZScF58oMsLU=BoShY&u zsHIsaVXY1)R(GsHxe)^4&`6=H%W+(K*wj6ZBg8F^2tzPouLW@s)FuQ(6EbLu?uY7{<8Ddv zEx6j*`Q}Q_s(dXmWwQC##% z6^$jip*ls&sg#sgqe|_DpPBt(BknFJgwqs`x4}UoZ!Z|V5>9n9xhWz+_j9D2j8hG= zRynmu%~xV>(oG~%L5!<1H42ZiP4$37!NeVdY&h6R09D)}Q%@`$(|I{FSKNX#wWy8G z-MBhTc9~S#fl-@SI1xi∨4BG_A%o1qA50DY)&=NFw2mD=Ui_J2uBskak5gGczDOIGbxZC#v|oc_=RPBXg1 z;4tGA7iE`vqN39Z`tq)>1(YC@`SDC5tbswqoJ7 zrcPBSlTB469(19`g0*U($WSyJF_O@w8ujT)=9>j=V#wGDk%j2DyTTdIR)6>Hw$}DA zO~b;IiIY~NIB_)>R0Sk|X_jgzhj&wy)m%LSSw~7q`WqQ!LPEw+V>j91Ngm_=(nq|5Q2njQimtt?F6|d zQE2Lbn`^It<>%H)J&SY%NQ(uo{TmE5`%BQ$LO&+YFM*` zsn2z+qvkNnmb$zfllc+UkgG(p>Mm*s(!!)}R`)o}2+#vg2PM@i>TjCF4hyEbg-o@B zu#H4xPC}}!QA|;&c4CrHmLp_55mWib7Q0huruYq}0SsTF6{E)H#w|&0(b+oVHW--Z zL_uW5Mz9UTBBv`dvg5Fq`w{A5spK4G%_X;$89#|{XBp(|W|q-LnN5SpNMbG-!AsL_ zsRJuUD1-IU_;xGN46TI;C!exOG&9@tie70^XKG|b?n7N?5H{K33g`K0no)#1f<+b) zHa8fTnYu?epJFe|7*0y4A>PcRa6^>om^@4+N0iBE924MlS4(hnKcaQ98KY+^Gg+(7v^S*hxbSCi%7fLbet;$i`bq{GU-?zE~gL&o718jH(f zfa0PxJ6Lcrx8RUjxWgRwbP4UPcV4Bj7*^1590z?Cm4WRQ84Z?(c>nwx&S|0+k!g}O zrhLNm8`)xw&^9RoLW41N(9{}-NYMdjSF03_o`w-I70mTOv?LTv+RCtO9*HB&8xip= zKFzB|Eb6^$JLIcVzC>u$6^N~e{-F(%17S*}UYArtn8#0ABXZH{z9a0o3#8CK8ewgH zC+8T8lr$t3Zi%B)rua4r)lMY%?xb%Lmk|ei<3zA^JByPX{~T>V9W<-DeBH{b z>QXGNs;XIEmP=7eNHXlkh#(>&hzLwub1>4Jpq{&|xn9J`5uYGUvN+Bf+^rBTqKO5a zaSvaGo5Qf!Eg?836n5jxk{?SE?Ih-v!CjYY!H?tV+3d>I!gAqMhqZm1vQeeDwAj=O zNeubp2c0^DSul@jBbR0NM&$ zxld)w1;2;eE;I!L$sM?aJaNc{M28ccSlvxXm1DnR+6E7Tf^eoH6IjO(wO#yNaRnX5;Av1tyYVQ7GjaMT$l zt+rEqv&mE!5^M6-BDqLq=rVZ~2c@`@Kcx2s~sIBU`~}U(b5tNAly)prh5qfhJF# zN@b;qbK`ZA4YDFq2#$R#41dWl!-z~>0$OWG4n6#ajTBPF0<`d|SU4=tQFxmfxWe1z zaYme}iPat6G|WTmlV&0zo}J=bZt9!^G;?Z;p0Z%Vhwl!X>oK|F{zRrKc+{Zflc^?) z!#|kgWj~5Ga1#X9#KLm2gw+tFjp8_A`XLR1AHqUSa;*rZ;57e`DZIB_T*DJ3e#^WZ z_k^q@++OKqsfAUyl2kB#k=64`#GgDD&kYcJI%$_sT|8I^XkMf|?x3Jtg+Q+Rd7~wuISN(n8NmY_JeCI}OPMTCY!73Lda zq4IhiqhNjjHWVXXO1v$Gfh%3mvL^F@;f_fynXq^6l#%}*UQNsI%6VeRxijn;wLFF= zH3*Lk%`IW-6p})IGPRw_nORHe2;z{+diZPbX)6<_2<7q0Rt!oZC|P+$tM;&HjjK6C zBSM;5kvx$J<|_-~lT0>EiB`aV##%eGi)3z+6wFF2GM?mhIe8FeLx1NWsJ(U7n-ASO zQN2_WIzta%^pE@EIfWgwDVGj_hRIP6T~y|zAvM6N$C|=bV7Ra;Ya@Mk>j>0R)gYsN zT5Pv^=+aTA-ZD&~Te8Gf9FEP-a>#PC8d9G{xKPXE$dkh`an6__l1gyaHIOUfkW2CS zA&=HNB*yP?Esw-Y4HyP;*kV`)%HzyU*6(?9$75HjWo-hyrlt-rDVVhd-Up~4ROL}4 zreJ0{x!XcGxm7_QR*5Jhy5RHZD3Oy3XwxvkWb`*v7-xCwFls1~mLa1=4tuU%^9X6= zCVokWX4;pdX<t!%-c63XmSo3^l9o^)g=ZglaR}=THDyxqL)w#8=d(%2ZHmCwzdC1g)mk0b!H{tS5bhyrXv&?cLYIfl1 zeHtSeaS~k%F=alI)Z5(5(S*H>%HxgzY3ZLfByA2};w&rXy_uz5-kYXzs^71-lLed@_!FiwE+)~Rc-bW-TmD@B+Ng*Ei8O?3H z@H^|u>D3%mqIhNWt^%gBnjPE-(lmm&<=i5+=7ETVng=p;20>VuR`OxY#S`bcQZocK z2_tl!!Rf^*=dGOKY`8k#QZpQuSF}G_WJqHz4NFrp+{?>su&Idk=w>gCVWF5KLKDVr zYpbO9iAqD;H#BUjcW%qNbi|1flae_SS|5ej71q5lU@u$cPenjBNG`OPG_&5{WSYw6WU@)g*fpdesMECzyY=CA7K(Y; zB(8Rar7P`J=vQFvl&%Iak2q<)C0$hUnDnV9&;n=66R9~WMH99<38Qm+I(y?<7b#jo z3QYGf7lZd7*;8uvq?l>gdP9wtQ5h1pTM{Ox@Op<;61N$8Fh?PBsDw$vt(B-4N3fb9 zb8T|UPKA*Y@!(|1A$}pEOO=?h!}zEs9oNHTUSA02@fNKn z^W+9GHCkqcwUc^7(~M?&E+!?EhzYW&-7+(TjJ>5!4Pj_{GX(b0s1>R|1JVFdMFSF+ z3cNs$c4ZTZDj1sVdn)b>s2qtov&`HPHqMPGC|n~MN?L3%)}GOn7%$udI6{tfpu}l3 zXA&_bH9C!V79Agu@JjxSd?S^7)M+5?xrwXBc&I^$4d_|myz-A4ZD`m zrf`FKT*3&*fU+`c$+^-j3a}ePZXQQ&Fg=OgXy_$gUicd)<3|fxoHS9-&g;>`v#*ac zb6SBfX}S2LS2X#fr-PQfJ;QH#xyaaiHH1>9B+0kboTNw7M2t3|MJb~FlPeP>`Smc8a6Ao*kZ+_z=jIuIwj|2J&$~B$e;t!kR>SK$K3U zFxlo7+42D`L>TI0rr54(&>%8TYoW3!r~C#0w8l^y<&^icjYTvqe+Ux zvYt)CE76R^a*B$^n*55dCc`4u-{^jfhBwgbPFw^OT;ID_s+H*HN6e$Bn-QgXOKuoB zB17~ZNv1Ag9kSoZa6RJAVmU;XqsWw}26{)77a8fZM(DdEFYnw)ZxAN< z9!-V^o0#g5_4OuZY$zq&K3N6{nWQavo~|qU2~Ct-Z^WJtoH5M6OQHEMGI+?0xx&4f zglA_GfzCjRTtLk2yEozxZw_N9EHLm&Xg!*v#-=l@@UA$b9{he5^2jVBZM4iPj`1Xs z@vD|RQBMsdfu@fI$XJh4kJT37Mj-?ykyU!=V`!Nk%@U#55_!vcRke{1R|}DALJTYfn{#dCYBJ%lrycu4H`jVNms;b zaH_7=PZ8Hr(nI*TthX>p~3l|i@)W?^%(uCPYP#lE$TysVHM z{kV>H<>IJFu)P*L5TUl}E%Z(ibh1z)B#enemz=Ri5IM#xFp{1l3K@@6dyF=BNCnj<7mC6cg@rX=!gCJ}P| z%K?NzR6leA%dSLI&>^*kf(h;;B~eNZo-=% z*guFkmA432S!zdXF_1GJUAv!Og?%av#|A7bqKFzTC5(pgt`Odik6wx(!^+brh}h2nfw(JS&o-^zuwS}5caYHjOO7`jXEbMaGI*_U!j z@!dqoMLpC*o*?%Og~h-mj3GrRT;1vxhc;tg_~T|L1+n7WqitA&Lh{wj#j(I9+F`CF z3ARj|(E-J9bR_M%Cb0BIt$62;>O% z7dh3^gt^|90<2Fq*CAdjId$K5Qg9b~xJWepdYri0n8mm{=7@eHiQ&>{qH#l80!|56 zM>Ff9UP#wS`CJuiZFVO}Ry)*~eTS^SVIzg$-I#=LHY?4Y6dvkFMQz7>TeM-@b_@>X z86yc;5RrpY%3X+&o9;%^EzUdFnv->R1~ole9*WIDVkM;CQ4|a9>&j#lYg1b26;^i7 zXrnMw-z=c4%v5o65J^aGvP&#?j-X!;(RwoSiMS*pEq3JOgFe)K#eav@_ixv$cgc-dMZPdXxMch(C5|E4+-S<}EO&zs8M^HrSWOa-9 zkh4EbJ^RScB?<=vihcqwX3@qIy8RJd0YzWt0^nqz#(+6He3(o}*3Og2+7W|3%!Ot+W|kwp?5V;Y8w1=!Hxw z37LaX_M29gT@u`I>H6Ths?}9OLK$?GR;$D0XVr?}D(uy@vP$ZsK}P0C23saj_Blbk z^uh%rHk?(Dd@^EX^12wJ8TIYbrVE5fW!p%4^dprbLEB&8<%5)vCRCYJHJ|k z;6d-v$m3D%IjGKQ_|7S?99#u;6pd3Pw@wppZ0Edju4FGVny90`m_`{+wxp7nHPf5y zuH3XqD^Rkjx|gNN2TggWp_2dacNqr*46j}%^E$|7(sVSn}Iq;>Jb zE(R8!IBV)?k)8YOCD-84S;|DC9B6}NhYQXlY3II<$7ys!?;$!n(dd*u{3-I2GY=x* z;;iY~kmRKp$bII%!G9#N*uz zvLYOAqdmKsDZl(4CLfFgof)c);qdkiP4!qNXgOdNI$MM`uoDqK>)Sw~LejQ(8G2%l0uu9PgYwA1T+sdwaoOH4165;hFFL~{gK)f%oH|eDH9s`` zbQO?e?wN-kB2_r)9(TO z7BusB%?NbQjzFJzGWRdPm1ix)DGA<>ABRm;=fwS1A}2n|x+Nz*+Ik=-9?ubl6C)AbK&{c@BTc^&60+?PJHe!5+>i2FY7LRQ-135q`pk^dqDAe5B?O7N z0{({)@X;tZXOo&cZ5u}JjESNhny2oH&DgQf1Oa4m) zw$4%dCod9Urs4|~e@$_d?po#ZdF6vk{xmB71rNRpcrH2IJOaLt`AoEy-GCqXOyj?n z^##RuDn3K;Zz+D4;y9+3KLd(CqWEORf35fnil3={J44nEyoU zg*`$D3&o$C6}R>ZZd&qZ6)#ZyET#Xd;+HEvP4P=7i5wo#{Nr3;{yf3-CtHsyu4-t# zpnR@ZK73p-o_JO99>tBN8--JZ@?g&&QQTO%DT=?KxT(i;75|fm|GN~Qc$1XZ)K{hA z1&SL!?@@f2;$*4m)28_49{OF1?^Jw>kXs*9yvIZT8Q{6}>Wjds-amJxFxa7dzO6XC zcK)nafj-atPqv=)$oV&lKdm^#%b!0h{zDHv9T!Ua{H%xme8rzrT%>1N%Yjoq&(r*@ zQ2rMK&sDB>EB#+nLU^gtw~rNvc%SN<?-cxGrC+Lek>bVN$aNAci1p^s}aUsnA4^9494$y(n~ z{M!ozPb&StD;{1XK%3_0dBrcfQ1Dr>`}BEP@gFS_d;sl=J_i+VTPgTE1-5*sAgafY zEB;=^^MU8mhk_CCq7m>_Bj7b7;L#EA#0dDcBj8lZT>1Y9=<}>e)~G*;9JILnm5csX z(8IePHXiI{KEua@UsihWxU!$|;p5YvFrVS$$5(+*LcM%xo#fN>k7IGf@rh`Uw;Z3{ zzD@y7^yghBB{Kf}EX92ue7^E22ne5Z&Ey=as(EQ{LYy{o;@iwkZAI6#wup0gOL6 z5soX#XK0JycPRZd;3vYbSfhRdF8MQC=`X95>su6G#kgL$zP2!*ldT@LZ%{J+gq6=( zTCSu%^WG8o+@SOqwhDtbrT;g@m(&Sny2v>%{DOuNZ-Uo$|ThIbkqY z`CO&=cP2;%Z&Q5l2z>5W`f-gyXvRU`R{UEuu*JvN?ST>ayfOlAVSvN!?uWuZDqq%( z5E|+E<&&hm%M_oi^mmpCVB|kf@oPUJcv$H-0_XNJR`{$@you@c!u546@B-Jh`FWf2 zZ+={m59y8jnZKdRd_Su63zrFI^l&ExSb+B8jcfgY`AoGQ({=>&#h?FDK4)tGa0dFaPa5dHa=N+E=r@#hTSRPWbo zy&HMXR{ER9ivUanaE{{lsy)11`K(qvPvv%v;&qJch3hM!^gHhqaI4ur9V*_7=PoZia-Ao;q!>{e?|GUdF;Foaq67PA^f#$o3@?eW8kzc5PL>5W>h9_By6I`KyW%u)OS z!^f9R|6Qg3iW(9%2iBnCFKa(;8V2bIq+6fc-7e14$#Yl=VqtN=?CABO=N$+J)k zIz{C+Me(j{g)ph~GZjDO0|LxK|4N@FiZ8fHuFI9rM#aDVe!;8c%L)OX2tC|l{0had z0DdCwSUTTPpm@9TIdPRRZc+ThjO&H#>t3awuL*ui?|oD8u&2HMO7ZXLxa{jn|C-|C zr%SqK9O_5o&DDOVGCsj7{+uv)TKN6`B6<* z@g0i4cbCwkTKRK>;@^BluK%v|H?qGye4g$TO8@$1A=JmLUd1c!6+Y|b%ld)h=EV5B z75_2gdg1!|FW_XKUr>3TtM~q-d=^CnxL@%TCX3t_divATfm6G_aHkL&`Oi`MHf?uC zugaDF6z#vhq5Lmb{9msU!1xs%iZ^Thu2A}qGOib{uX~k#=xPDy>b-9Qr+U9j?ei$b zzpwPO10v@?YrXtR@tOZAgb)jV{-F3+Rh-W#{&(enzsLTcaFV23r*>G`Tc-jixuvzd z1eFPfh_=zE|-B>Hxk&@w*w<3)k0^N`FVa zfHU>p3yNPiD8MM6eE&}IpMF=a)x27M3>Da3jT1lTJmoVHILYTJ?O!%2K2Px#KN7%{ zt6K5TTrT*RmA+B&|M|24A5i>i#rLWH+@ko+jO&H#>prEQ^MZgzKc7_GcdE$qVlD3g za4Od$sy_kc^&gB+wJuk?v{CWbmCux30e+zP*)ZiKhab~KEk5WD_*0_zb~V^#>R4Z- z_-A$rU9aY+T=B2`yWqxetX2F^I_{gL`ql=V^55an|6NKy>ifc{Lg_!n^i!<@wTH&u z-lO!3E*AQC%9quz_#-<7Xi@xm#c!?=z|`;W755iNf{tA>{5^JT!YLV9DQo_k&iDkY zMfGR7-YiwT@hJi76yL0P@C5-3eM<4iZV~*eO8+6nPyL+$+KjE+6d$MUC8YHG6~9>v zr0$OO?~325eoKSW|3vXKngkfH_(8?@|4M+5D?a+v+;W)0_yp^bp9x`~(ie|Fze4Gc zf42~h(R$xF0)1HNpHfABkMi$O{L34K!ED7psQCUBf-hA3R>kk$DuB_SUd21L{Te@H zA_PKu`+~*~O~25m^r!6?K691-E5M0px~itu3FvUCyfqq6Gvz%?@rP2vV43nMVO%d;F|1E0p1ex%>GEaWr}$srCxB^3UswDIt#H#GpHcii)!QA)#}7xv^g#;o z*K17gM&$S8Gjh|P%lHIqlIrbw`si}SzrIX>xZ-t+4|?oILh<8w3gI-RzfSRce=mUP zM{ZJl`jdiJD*dM!*9+Izb@1!RKHTN;Zy!}YRT>~MhxxQv9{cp~ntr^W=zUYMLfKe0x&MsPFIRiDNcsO> z@ryk1d>fCGJr4!*n3C4d(dP`sS82QWlE79W<9gxxDpmSIE$>BoZ2Fo~+x{ki(c7;v{mIr(J@R~B>DTIf)=cH| zisB6q3Gf}smNjmM$mgzQg2TP!*9*Z#Ut@e36H)Di(qds(gc<>i7eRr<|}|K%zH z3KVYu&i`{6t7nQ|6#=!EB;5V7bDM&ia+(QLTLQq?TUYIvhe@BU+%Xvu1sBDdw^5C z^nOqL`M?PD-%$RqdHm-ejX?ivr5~)3L`{ADMe)nNA^2w`yVmLFi2PqTVLIQ?Zorxi zJXgQDmhlPJ15XPdb^EOMDBgXa;HW14#1+RL7W}zWzO3sMpQ-J4m*O`m{?Q)@pk~gx zOYw`eL0qZyUsXI$9gy!R{uFSM^SLVLv5LQ-^zXb!fOjeWKTMDDsrp5iD?Szmkn}1U z5`k$qX1zo4?|SN`2sr7pH9_R5VzQPg{U_D0K3(~5P<-|s0+{?aDWAtY?c%*kKS%An zu~#2deB%|uXP@%FP4TnGO8y_vdcVsiKl5bke)T7n-1@xI-_sz-UcJ$;`1ERFVDkUG z;-BmgLJUv%^A#9mlG|OY<@%3`zoPWNR{t5@hkRxV{RcGAg-ibIh9M$8MFnzg#xIkU z9>@IgXQF&rC5nIRs{%Zy<=vq8R4vy{O21w4Ki3N&wPsm66~9{joMNTF4LH{?IX3t_ z!hbF6UZ&Rz*Vn_!=XA}dio^Pz;-_6L#KvD8RQ#sj2yXg|KPvvXcI+lTV9(O_tNGFD zu}%X{a(nzK;bZK1vErxp3vTSg8pZ!p$HmZK{#>H?SG0b|D;@z(a=6i>pY2Lt{v{za z`M*)|hc6Qx#o^Cwia*^V6%|$dONzh$ZUL$l{}08t?G!-8YQ3uX*VSKw`tfHJ6o%xm z@XK;-{HU`Oze?-UM2DgHlNF0BTu$?(}I3_hxSu2+0Uqm)aRd0C%S z{6U>?zESDF2%PNILbX?_w${UppKLwtk@J(v=WA-`Vcz-kABz7*1!nZ>b;U1SCv?v$ z{dgz<*#Ymo_Q}AhejoLW$Ik^$@?7;{}=v4t; z9V_2)#V`J)Tx+*#?NYp8t>FDCpgoFz%QN5It@yj93H{R(wAh`yjbz_y95X+ zzFzUk7fXKLtL3d#JXtBg?MmOF_|M-fz&VQFsCai;05k450G#sqwDwcB(tlm)Pk%&! z_bdK0#jCCpV6ozVRD6#5x2C_Cf`&%r{qHA*uv6)0GOib{uZw_FetzZA^K#`=r;ODN zwJuS7>Epr#m;7l{{Bt_bYviy?@vk+A+|-;|A65KUmk9nv<#Q)+%FpE<{l8!7^VbRe z9ZLV0;*UNffSMcYCyXnR>+8Rj{tw%Qk7KW9OS;dh90K~x3BV`0o;N?|F#S|(na7{p z!1NQW8%l+8s!zTzSNwfHm+Nw6)T#KyK>?DAe^Bw6qa~jK`LaH#`2Xnmdb85s$GBd& zzP_#WzwQ0d7!y zv*Pz?Jn96+6O8MH>+9o6KlyS2jh=r&@xc28|DHb61cxD4eSK5upHstGsq`-?{t;~` zW`6Uxj4P4r%g6jDSbx|cpegTE#qT^I_;dQq1&X)s5@5XIPhh-4dj5#MH@Z>rC7>sK zr|Li4HvX(pJ`JkiWvW+O760itQIMF@Z)aRDTwhl!{l)8r{$ACqk0@TYM~IKpXFj3$ zueDvDr1;&6=btMK+7BZX)z9sUzpi+h`iHv}pD;(|tp2Cbs~Ny2DUJKB;k+INr|{@Au#@ zE1!WzVPO2OKPmpC8YGjS$p{qWlEXQSLk>F6evjs7p5ov3^b2bh|HV5*4!YdU3M&5N z3c+txJ_+Ddt{1d_pRD+9rq>JC*TTmq ze-(Va(jQd((fb6@*RCx8Jjth}@ds1C#{(xj|BBl4Y0BqJ#`VJWHAm^c*?@tOL}m5N_IL+DRYJ9e$&Pd}MW|1sbs&mNC|dymq;tR3lO<^QnaH>$ssRQ&sj zU;PUKJ}JptgNlF7qgQ`Wd_embqixL&xvN`TY&Vxsy9C+odM z%ICm%$w*4^Wr{!hm;lQa-^{pPxW1ymX}-Wajz|&?x&6e`jy|IN3wH_=WB2YyO!1S|kvHSY_bGm>4k%52KB71_faA~gs)wIayhZh}PWkUw z{F+sgL1Ul4p?Ix!_%KKOc~0>=9+B$@wOoHze3t5)@gF8E6!{#i75bBv{#3=gRlt|Z zZL3i64gV>?LB&@p{so;+yk8yJZNRC%mg##6hJS+>}K-&Y(8$~VrF+tw?JcRnq^QpF#bCi$%O`2YS3MLu1c@oSWSzTyeB zKc&iNrsD5byN$ICvEQCg%N54ztFhl2+HYuM;z@;TBpkIse;G`V;6cs9; zKV2(??Mh#+_!A!czg6*SE$AMlZ&18W^EpfL>lD9Q`yEs(e{NO$=U*fN{NWeZ8#ozrRAjPwBnCk3fGW>U}!w_H^|_j6FY}^NHx6!VkKsrJI?JGNZt;Z+uzO`Q4l1Bs01bAbwH}9A)U_ryt=qVKT@?=L!1EcX zjQH~DQGhq$KvJ;cZQF54snZ^ivM;~6!X}ZtpMN5O&8@L9VvrANh{=|}oZ-gSL|ao5 zJNIKhQzB^=k~)w?g2@)_DA)oC&7VKFco+lP?~m@3@WENMS)DmG1o>fBA#A;m-@)Lj z&Fjmm%dvrauyEdjxpRjhB>pU#c?-PA0`F4`ONuh7V9)oqAP)V)SxZQ89Zrg&^G0RU zemYal!j6zZ-3K?B2zR)yadb$%1!6w32HzIt8k-lIYuW};k28R2W)AKeX&WtbcRKwaNhh2ORR<_G?rj}G`^j#=jzb{Tni4>9Bgrq1B0Zg z1T*PC@ro8&25)MO$60@YUT9U9V~6GH(sdhyRW<9&tkoT*ZP99E0U5;!LO2ek1-tc1 z-Wh1D#Rk)Qf&&4WTf750pQwOsLOJ`?NaijqnS;7*4kd$OIyE!c(rVFmA}#hpRz6Z2uIwP*4Jb2NWMvj!e-UqoP`TK^*3jsS2N~ZNbOe>b#}!? z>RwI@9V$8q!<9XAV5K?b2)C#Lak53TbKDe>ORI8GDME%rPoh+WPvfIh^nAoB=PWqa z(`4+*GY48B1rI_^IjazJ=VJ#?4>HHobmq?YHm11?&@PF!>zpD@OpfQlMHbUJ3%o59 zh$opj3l_{_rfjakfs6@h107$>XSNUk)p3r3X`~&BVUxY7&7D&Wt=7Hk!)7P>VOz^* zohra*PRO?MAk3WWfZbqai~Fq2{q$UaU%=)eOR%Q~QfcUhGO^{(sK2iYB5?&@zo z4nj6r7M`tgZiNu(4Wt5j$PLe#5fBcxcFkovet{HS0^)m6v7TfwjZd=E30V^_zn$ z*C>ZID>hld)s-8TmsSQhtXfsIvN~8@y1a5_FvoELY+Z4n68gRBD7F))EXjV&u&^O) zKO3PcBBiPWfX?2Es5c=;Uxw(=FCrwv=A5C7b2XxM5NkZygwwE?1Y6lMNjaPe^ozKS zlh){V5GN|t;ashFlAR{UTIh*kUMs<;>9|e`%p7mzKIn;#Sd(LejcZ}iZu?wTi$J+)szWzVNBgYqSW_FT$KJVdoIArEIy(q_(jf@}r-LS&P~hg;j$jIhI5pJ4 zu?vTnEn8h#zPv10Qdm+r&x&LerO0)1ll%B3+Mhl9p^-M|C0=gz(tXFD`8<9I~a^5gAlD5?^*^~LYkhLo@r}-THUkkLQ+&$z3wiis$aRP zdS-efkO)As964AANJvBw0dinV4oJyu$tgs(qb0DlfMEH)bIy1Fs(WphrsutS_0Ih{ z|L5HM-dQx5i2J0H;d3TrXSx*?twwwm{P{pdHr{{&^>9c*ahlb>LQxA9{BT=mWlNwq z&L_*u8rFU0`kH1Dc7$(R@5aj&xx*?Mm@9#@Kwp6?ujnAL=ROe3m!{`eQbRJF$Dd4x z#XVMjdh?5#IjixUqhLopfYJWbM{r}*_R~jq7bHbgBrAT2^==cHKno{*5sx zetpF}SKDB5uQ6hQ1qQW+sOVP)6C~S9mE*HLCRWX`wniCs)5$R+l@Tf*y?_cU5yG|+x^8neb=P=W4{(2N^TvezW%SZZ z?aRqQ5vrSE*)ZgIGn~{doY$y?7;m?tBq!17Ih{Ard(j*raV8>(%?g} zr0G{yyI!Fpa>CQ(*f5{njujc zpyS2V@53E?D9qH2`Y9cX>W%q6DkwH;4V3^(W(YwwYRt_Fu6h;gsHBZ-uLrp<_S@nV z(pQ$w@D8IgQ&|)5Rj>g9x~q+r*v*StVrFZEjmXr5lIVsd>_w~AI8Nht(KoU!M6AY2 z>d_lS2doL<^^|F|i7FVHR5oP7GMHYuv*uJ%3!=h?RH!5fXec#<{yvp^o8o!0G|T0~ z@nz5S$CHycirhu`dt`QoTV)X+s^uu;)3oA7qp0>!6|R712*@g|jR{z(+`^AB--MN% zggr@QB9FQ7QuSVK0d@@~TWXvYwJh1U6a`%f6vtyNJdOYnwYy6oB&D6Iv~>1Pkzfma zK)<`mOV#3GsFMs*=TZaQhs)zB1(ZC4X5Cz@t1^p_a}{Vt^(j<7dxoJs8?h8{9{+33 z|0s0EI%q|1A}gaWC0&FbT{Wiiui_0a34R0}^q`+F-RWP$aQ0IJK81Uz5&FmzrS`DS4F2=%U9Ux0q{B`}1Hlks}8?NzR= zwrfTYeQs*yFZ6Sc_)XW#VwhwhP-um=maf?3tZ_%ShMBw%x|nLpXFvmqpsP@>vQ)wW zbepMAT^Cmz^_zV;tXG!R15QT3tCQI(=5Y3?k>WnOhdnIovKkuymXIi^2=-WwP;!i+ zoDfQ#U}6=Nk|4voha0h2LgAZ_WA|&S32SEmscC%jno=^#!yI*#;g`T=K}>E@mK1da zNeO+aP4jlZ>Xs?Z;$)XG5zcuynU0$&)-GOzhZ1~~TK6_*=2;j^FB;|)RZ+GjGFPoS z0qHo|e4{n2TDm}4QV%2MPAU%&niJ}CYEGv)HPJh55p;uVy0N`Y8%A8X*bP~6&r*GYS@RlY`U>D=%@S>h`o`A$Tk!v`^_JXVtu(r8iMK2tS+?2}qE9$^T;Y-72 zB#Ml6>mW^z+!X~v!`9wrc!yc`5JHB9fqkNY5@{NSyw(H{c0Fe#ii+TtNCYFC!ev3N zPI`-5B*v(Nf8mr(P?UUH_&upml_-{&-d*q8@RIe@HN=#TJ7LnNW>!I_MmZBU+3?Tv zmn{u#$^s{e=#oM#R+e}PWj~%TK@C(-tb4_TBh_&*yy&?&S<02eN@(`6vR0M*o?(Q^ ziFO=l7$g&9xpAD7jU$Pn9c+zmcVLW5cG(J*NQ#12$?`y;hNE;Nv;-n7uC&%ugBILM z(}?Z3=u5?sOX|A9=7NP;P$pxJt>#XSmqJ%{*c{1Og}5La7Q*cme> z$?_xUfHFtv;&I^?GBDz7v+aAp+K*YtIatTAtvZsEyu(>jgj!I^z9+XV}BZk$v z&(RSI@}mB4NZ{^x!yr+TC%Zt>8p}bQd%15ct~1^-LNtZs=%KZ_GV#b3t6D|&%QgK< z6ok}mNg$*U>H6(^K8Ug*YkFle={hat$?}kOBDZFBFzW2&vIw9(afA|pm9Vu^4x~FWbN=9* zTqkxXn|@v}8J%mTj(V;^VjyPB>$K=-bh>~$cl1r1sqbzBsw8Op5kt=Bl#?GOewATgiOJ*Q|9GUiH);?$#l^XTd8-Dv*_u!ohp(FIJ5 z)WSBCafp~U3);r&%mJ7G4u*NZ$Fk8TrPV^uVE)J){QSK&p+3Vs4qrDWH=EF2(P7u`V51dTnV@`!DFPWh|Xf zc}^>J&19fz*oOtBF(RTbq%sgd^u@YJCVQ=BX`r%EppvDdwq^D6$TnC=M_gB@zdU=& zxt>uD+>32hvjuWOOp;RxIpU}*bJfnqF7;LvKIUem2fwl*i$APq&mh_;mfWzj@$`^} zpLo^Vvk*D-Bo&gzk`t=3X+)DtYdCDSZo_EV^Wip{P(vD#O))c<%A0Nm6ejJPkh~6h zFV3+h^emHwYANTmO)&-2LqV9HChe~mBMUvNp_;4~i;*@znf}t_bSqF20dW^`rX2%l2(l!FhF{ zQ3sD9Rd1|H0Xn5Ug`UYGAsW0MNM2(F@-+6ySk!b3uTv~8T$1~2XtqF$ z7WIQ$(eZhy{Ny5~YK~r~0qA`ZO#zmM^4*an8NNEDN{ zcU%`lPA5~D4gYVRy43@gGVEd}qwA6mnee`qe&V7UtJxkjFguQ6V2!EN0EgK02<;!X zu84PYQa2`;7#hLcrk4+^tL6`onZma=Ul?ZmA&5M;LEM9AC)5M)#>b)1)QXsogf?Ai z)TJ*3#kFh;_NKbRYPR(v@AtMGE&T0Xf>~jbtYw&WH%HsGreneyOsFn{GG$G|DX%z> zykg6m2V>OuZW?lHQnw?{op>OEoQbc2K?P)+V7VOU%)@>;A5Sdg+CPsBLGN;exiRB= zFuaUxFUQFRP|2{-MX0cvC-d>CiK5U>q%cI) zT0dCq_GH4VW^qfAI`ZvJp}n?L8M^Ms8i*PDl?P>Ie(p6W{29te`#2q)iSgK%k*9$pBUB;SFiH$wzD>uw0 zA&mVn68e+M6KSq$-Hj3%+FZIu`+}!ifJ0_k)BUxw#_jS~$tq$+W0yL~6bJ!RCb>VJ zoi|Ig#@K0Rfbe2?2zUV#anciK+WUF58J5h_5YX~2=1b+>J2_u485S&5Z!MSTygOXL z#JSdv9&Jp#ku9IBu|`vS0a?b13hoFb!N0V($uF^7!v?l_y1fp&NLF1MLkeeY70-oz z8*lbzf|(SI76#pJ%y!NfTZ{BrgiM^$W&+BMH=D*!6!OJ38rW^D96j%grc{A`GXaZk zw^IzN4(rWTWZssH18(%y894Nb|Csj|;;(JST^D(^hU96xlB1>WE7JhnY!*2%pu;tW zCLj7CqC26$g!X>FG4hTlTy3sdqErt^gnKG)i^N7FPQF^Og$pyX1u3Dy_|I}j-Jy9z znXKIjSIg_Zoty7oEax+9_5z{O27`8iG#q;lIblueFD-8qfxo~{^7LZ#5$M`rLy2#P9800HM zo0=pARy}q~a=GE9abwuIuzK~Dh<0ZCYq14A1JWkv@HoH9;nK?X^Ak&e7tTHdFHaC& zEX*m{Kew$xPcAm@Sy?hPZ5?qcSC+hRHEW+&rYS_o5kkoa3mVj9 zQ-&LC-i3OZ&8r*??5IzhVG4-I^fji7$4fTDtY!-iH~iNTyo-9XZ0W$+2Afj%XM~A; zT`iP>XxuMtb*ek*DJVY}nQ06Uf>{raq$!eX-o8wLuLA}3a^}hf`wl4K6g)thbeJMI zlH#~)UbZ^|u&S$o?M7AjOBiY+7|jBkM>5_~tir`QP{0Ld$}{!Ywx*H{~ku(dNbc7tQF?`_y-SIlwG_wJQ?gBtoO zUQK>lE9S4CkKOReLj_K_8g_+)8ZLD~FvdrZ`jof7xV$OJ8PhJjW{mwIb1PE)e~=+iPq}>l(rYrZK)6V(4+3dOzwT zk`iTdwzJM|5Uai;c*MPJ)C}$_L$$(Ac4%lT$sA~s5|sq;vS-f0=V_gDL8W1GmpD4@ z3jUIYt6A#%{`#q{_QE1yfhAVEutk36a--Wtaqt~CYLz~39!zrF!>j~Gvax}54|ulE zc26-aWlxcqA}i!OfZ1&F3TUe;@7SY}b;@MU)pI{YpG@85|^DzWW<*jyG;8{O; zWph_o!XQ@AZQR?0 ze>L_30cCc{7+#)6ewd<$L!+nI`wUrtKqh(~AOa@v+$H#eRsFBzFcg^$2h_-wBwo1W=wxByPfl4 z)9>8g-T%x69*TcEJ-^s7UHh5YwAp37gCk|q z?M(3OFZ?fD>yNR#FkWHV0?$sz*BRG>_0#e3s(-F;v}!sBmUJ56S3Ir#|GxA`fZ!AK z@fwZpvvH#1A2%)f)Asq|Cvf_~0{&^h>v$vIYG-;rU6*g+q=erDypDgW8{^o*-^KO+ zdGEbJ<9|C&bkz8NE8suWw8!`D@ELf)|5KdkxC{Wkj)QX-{2$<)pD*AKuLMi*pNt3U zb^IoOEIuv%_}Z5Dit+#Ocl>4@|1n@SevMPdXZZcs1^n6XI)IMf4tS2AL(%x-a`zTa zh*P!qp;!DD9UsK_)xY31|E~x9u7h<4AMq0%-zIVKA^b=2*TVlDt`R33A3y)`vHJM? z{x$vI(*K+IrG)Ru(EP;lh6e6e@jf5_==k^eTEgGB;lJys@%q&~eqH}o1AjB%b^K|( zzgY0*{$B~ih(Fb@==e5(c&GY*%C8*$9U;~l&+}J1 z|JA_fx4}4IynZL3L6>yqC-30Ew$%TZKkz5^!w^DO zbKPgR;<`UH6CA!2jpZ9V5H9 z%TaCj^=H?>fBLV2)BoZ9;a?5-7Jr}qSBD>uu7(GgeLjCp|9|_cE3O~KeL4uP{O*|2 z6+a%l=J20==-)q%17GPQzLWl@ei85Zo&NtfzUuG?crQ%(Y5OO8T?PN||KjlR+TGMd G3;!EW-?BXb literal 0 HcmV?d00001 diff --git a/src/segwayrmp/lib/libctrl_arm64-v8a.so b/src/segwayrmp/lib/libctrl_arm64-v8a.so new file mode 100755 index 0000000000000000000000000000000000000000..dd6df5958ad25678b845fa38a7bd392a7393667d GIT binary patch literal 437648 zcmeFadwf*Y^*+335-pptzwXKITkDf-NN8*9j;v9|p-?MGk^Ysv4PeuBtB#h$=a2?F2fbRnLBj7bS8*%;$ z=kLIUait>zGN0gnvw^CQud~6^;YHe3oIc=tIM26mzmD%m&I=&h4DK^rXW=@I^L~i5M{sVyIS%}1cEI9~?025EHc!TDpHRp6%K zJRK(;_v1W-^JtbM?n>OJGMVjacRLd7pEWRLhvhbO~&~Y?#GZE zjv`<>PQkSe-22SWV}3Jm7T=THRh)h?xbFjB4m=y@Ma)kE-;Dcz;CvhBeKyH5+%LnK z&$x$m*~`gD+lRDWOuT^m?KoS(7jvF++|yCXSA$~zT?M|B(>gg1rQVJERk&8gMAZwp zzXY=X%iI;5uN1PkGxsX4XW(3fa|HMRWTvtliA=?r2YeRJbRuw!ha4T(@->OChW)?m zzeoT7@Hl$1m7tsxz@3tSPeh%{nz`%*X*A!o zM~=Noa2>;3MuId+6#>kV1m90jz)5P81djU##t#dAqqslZ?XQveONYP`2mXNrOSqoF zLwxngMBEoTu!Y~XH{#lf`%4(F#PunhH{pDVxo_e6EZ@sZy#R0E{!M|e75C0tySDf{ zC(s&$j#hIS_P?JbNVyE08!_b{oHmH-l|t@(+_&Le#@t9;@4|UHroWc0z@{{URfl=Jd05C?JIf-@KLm*U!w^CO)0IFfI+;_9(vg6kCy?pKUo$Mu`S zz81dU%jtLX^*rWlfoqs6V(v7?7YjW<0XK^A+qh4`{qrn$1g_JC?8(eKFPE}RIj(o$ z{2Byy(z5 zA?_QkFs|v~mvh?BaJ?SfJDlFYe5R294d0jHI)l?QaLr?WC+;uA{WCaU!F@f;yajw3 z?tj5}Jn&C(?gDPdH6Q0H+~3dXfNBc;2ggI;F30r(k@g1ezm4-dI6uWX3F(En+9MnH zHH<6xy3Ho?^>HDe1#S}XEzJE@q=k`oFYwj4MsU)xANU%aGjVI$ zKf+nc_#p1(5dofqa~#eiaef_%^KtrcPsfXV{Vnci;Vff35!cIbevgFsIEt^`eD%Vf z$+-Uo&U0~pHm-l?{MWI}SX}>vGX>{2aL&VNkI(sL6!O|*F7B&wUW7A;by3;{Lgt6y zOTazBnI57agBtQbzIvpBYR(MaKus_c-|7$WD5Ce`xe%8gVrml}vgH`VBFi`Jat3d=>>& z9Cj}A1+r5eJCBFcjQnlfk*%II3`|sRLx(BX+W8O+pmNu91KRn;9t1mW=L1IGKJR&{ zMn2_`DVfG4I&MaFk)EyO@HjmBzv!p@T#=6q(aZd8r;z^RRQ?8|e-!h7PbWP?k3S?a=sCepv2>mi%#p@4P$2+mFAzCsR)!aG7orJx)iK~p@*K=v)Mc^9!DSNPc-srKQ;<%%zl}lx0wP34jZ#-F%ckp@{$ct zF_w;B!1akQpkRa}U;h{5TQc!OkE1e-{P?iZWBuea)Tj2tEyhkSXT1^rM*0uXz>Z_7 zxv13`Jc*Bd%jgL*zi5QfQ~V>N$J#@4DG$rY%P&BZp6nkOJ&$nWJ?Iz2cm3HA&CH*5 z2I)Ueb+Lb@F#j0>AIa~bz>mY)c`CO{Z>!O7=M;0#!F~+dWxe%7*7FBsCq4NO8+n>% z&~YrvCB9*|A>K2zdY$Wk3vFiOuCS>AUh@k5Ul+#hQ`G->vEPliI$ z)A>I}PZ4Kb$npdI@$!x6uq6K^O_FeoHy8D1_ye_XnA^qHTQJkex6@#W!`h#lYWN_> zlb}w;UJcjh6t2%L%+JMSiOSttZS+(y|HO%g|Ck179C^%dL_Lr_`P?szw_t4K_`Ki~ zBWU~4ueiS~*lzSZ%X;47__@as54R*!xkHaq_N&Mqlh(i@$HE`T{w&&{!Lft+u1Ut< zI@#ag-ul?ge!kV==ksA6Jy+*O^F$k2{yyy|48&yt?lT0ox91FF|65R-=((mr3E6-0 zrucg9fkLup>s|5oyutA#g*VJPx!}TK{Bs7!`N)6~%x3w~HvTi8$NXa$N64NrH?TeC zqK<__l07Mo@%jYz+w3kQn8osAw4bn2arr66ebQfZx)J2?q+YV)`=>^@hV$GHf2MN1 z_n3N^#{5){8}EH$^lWAR4{1ifpC^!B<|lXzzlY;?8ryjX>k0G5VZ_Q$H1ZX+Xuy%r z{AC<}x;Wl4t#%)2n$>9?AgnDUeKRm+z zfUvBO9Il@OFBxq8`CmHDvyiy_lE=H`Qe)4@=A!;QjQj^Yo_2Ek!aRNSfY<$kUasNT zr~iw+)zb{W^p8gI4%Yt?$DbXJ@$N{jw`V^!f;P@)a{a7bZ}?Q!L(^UI|Ngs;|7UTz zi`kwu+PuZV-A}FKIPYC!6jZRDi5x#C(aS3w+05Up{Yq1D|5?rc+0OG%bSr%v$$sAX zE2DtkqtStGiuxI&_Hi86B>pp=?c75zopAK%|Kc4P`_+~eMo%&GAHi>_o|n!s@-H&) z((&Xt)x-5^{iJA^{^;X4S(Rk;?_fRW0aASyIL6aAv57*wSthOzZ?G><#kD-EB`DlcV!9>e}@>t`JvJkfYMX&8Ib zPB-ZBH9J*BV-l(*DLkTn-MSKa1PZACov9jwv?w;GcE4bMyd*3bPK=IP@EuFq_)Pe1clXBa*HO-7G>uHW#ysQrKuY-jnmc|Ppn zd9v*nZ{YFix%RQ2w6J_O9E|wnpBVl2d6(#R8Lf8w)A02EjSe6CLniyfNJFc8cwJx2 zaj$^+-53x_|0_*Kj~y>6wEvG*(`iEshaES6$A0qS8-~A)%Wc#3JX-Z|oL|d)e!9^= z@IxctrM01*M-xBv$o3fdy}TZrWU{H>X@46k|Lzf{y&{hJf0)bN@*|^wheP!~o{QFx z{f_wmYi-YHRrRhZ!}{TDey$DY7(ESa!Vx^L==|6awq1VA_14Vw_9Dwa%l?`6gwd16 z{I@gA^KNASvF&omV|f3@_;N2}f5>KkC}KU^5pNMXh8&Yn5Vf!V7zn8mmbhq`__mkr z4DK@J?qK=n+263Ep_w4_Wjy|7)fj$&`3Tp~beeeJ*kCT|o)muGG$U{8;Z831;$Ip* z%<^H58wHOTzL)t-Z4U!+S;+k^ZP1W=IqmawQ|==V7(G?YC-J;u!x_e5vzULGg=W>q!Te)A4XZcgm?i6PfuYXgS@8SAv=Y4~VnLiO`lYB9+ zD~p-Gh38i(JfCl1ekadcvPYQbwa<04p0AEp3to-qKRuG_XXtT&<5i7g-ahjzQ=en# zBNQCA9;O~;_;vk8SF^dO5X<{H&fB{hIvtkuAo~9ju3zQN(BR2MB)V zpUgD8Ct~Dnzqo+ciQ_qt6tMg*{k)h*y=e&B-*4r4<2nwgX)Ira8!C4U*Mpz=P264w zc>ZbIYv(ZY;a{`;8>)<*x3QjP_N&)FF@$ZeCR8t#JN{2b-qzdQJRXI4eVS>KRVv4; zF&wX~{nJi2diMUo2wFcZ=6E%pASeum-qhK+t(pC=3xC(q&M zI`Ed!pKmT|KG#n&uOrqmf1}6fe{zG-Z{<(t`MkOp69XJ36?KDtMD??S9S4u2j|+ye z=M0WB1N_3v!-~9Emyw=SN1Qx@`}JcS2U=MFU988?{mc5>gkj446UVEpkBov&*5hG+ zd;Mf%c^31#xgYhvYz(YnezUGm2IBIW?vH}t+gaSdl6gO;iup%RHud}>$NvnS=V0h~fZ)X}lh39F{vi>)DJYCEC$+mv-SBj1ohb`Cx0u{}d+b%5)k=S!2A$};QNpL=!}$qf_W_ednhD-YjpJM8Qf2I^cg{0?hoM})UVg_cv`@EF4pmxfw(+6*~s@e)=f8a zyt<7)Z2g!!Oq0jR_upw8;YHSU*D%jDo9iKu>!FC{-$!<`Gsy47{LD9_pA!EfeL#=n zG3Jj$1ropEDpRhlpE~ycF};SbVfj7jBtP`1gq>8M$2sD|=iI+`@CVY?50B*itLB@G zey%36)N&oixGU4f3E{fZ;M?H8-iK*ZnXShxPn&JXvS0w3XWM^7>G?>YS8$qd7v++pmr z>(hXaW1LxBwj~?+;#Up1)nrpmT%TijT(I`PVE6ZUo*ZUfSF@fJo58qdpVv2d7V*O*vH;}w9&KnQ&XVrFXu5op6A2aY|lFO{{y!g{nr1#z_>~MF_XWeu>C!G zn0YvTze4_b@qI=QH=CNo`-eML86Mq4AIEe5ebHt37Um~&KT76)w4V95(vAKqo~Pw8 ze+u{0XSttRJ>@)~AK?15*T1djQ&4ZDrv+?S!8Z(kk@+N!tC6=10r%6#9m9gGZ{x{(+)w@gF#MBT?uG0R&hLM2NBvN_7dz(vuW&tQ)*1_~ zo?9nVxkHa9P!FWXbH9n(w%%rQ9C(k%(*>OMIF5%Y-A4ZcJP#fF;E>er_wl~LbgrO! zmY=lO$UVvY-`Sr#_Zy0X&9nbYY!1G@FTz`i?ss}H>ckX2UgKWmZ zWBv*Vkp4Vw5c|A$@ccINp%L7|^80lEWgsr^d5oTYyuZ}KX%it&_7ph$-;Kwlat~Z) z?CE0pds$EN58|IUP5USIdq0ck1A0EdnZ@N+UC)Bx+h6efVeQ4Ho^3r`$b6XoxD&^E zmOsez)d9zQ+kXvH4|i}o4sbheWj%8_u1?u(?0<#%5{{qidEJ`F{6e(5_BXCK3?KS% z4Kpr3hklT#|30qc24@zR9FA9B$2|5@ZkOV}7~w6(T=o1!(_S9lZ&}K^rt-MC;paxM znfabGjQj@P{~TccetzDbTvN|hegxc={9$ji(SvH#$6_95gDjuVeCO##ew}0gYUMC- zYz2?|Po8b`2U*V^T|apLc#q+2zuV9Hm+m$^nnNF3c^urw`&YJoZ-xNb@8^DM{i^9? z!+*@nD^U}T_3lk8$DirKU=~46+FJL<#nH} z=Win2!!q)cHOA=4d(W`;c^9((jA8$2=S=tO`j;Ba{cqSG)_!2@-^e20#+B-AAJ0os zoId>Af7e}N+UpVK5Ayt{YL6jWnEx%$f5y`vv*WPq&52xY{}HBKYyTfvf7Y)IAJn<< zAC8AXZg<;GWr&~Wa1zLN4!Sexczp^@B``Ul(L&mPFd0fuoaoIlaC+LqTV#qT9=xZOAYf$NR=M^pH@K4N*}Mrw`j?<^!PfA$#pp1X}a zpgvB4f0CV5j(O?Bx;`*3R=B>(6fv6E`+aGUbMUYRa{7>~8kAJ?!|_ z-|pskzSl8NTfyEj5l|4v8!cj$Q$zGvosF`eZ< z{>+Det6{V5t6=<*}X$ zo`C`Y{L`e$3D4STIcg{T}pFKP}+*o^~C54g1f4!+(-IrriFmrofF_ zJAT_l_g@C$GKcp!?2ndM|NJf2^CRCkdJ5Qn+HR%iTF>uW;U4;EN;iD+eMT^w`5e?I z*+1x*|9{5g!p40@-eWF`K8q#&_i;S5?VgHyO5`Ww+5QIZU-?|_J7bKVE&npaBg{X? z-i4XznAxaY`OPyyvlml2wMHW=J>YYETgA| z^>kxCHa5ZEKVCS@^Io4~o@;NG(Q_Z``60)v3di{JU9QjRe=vd@S^jmla|7FHgRH4zDfS(;qRkt{a>j27yf>V=S!(9znlFhpVtw#9x8eM`G{lw z+0FIe$sI9`^*qM?J@sK@r!Ds$_&@pcZEqUEVwU&AAIQ#p$GSd6w+jo2%X#c?>mB~K ze3EC55aZx2CkIDbS<}7Z&&y zF3D|ftXWvv5RWcvs3>g?RH$W;$qm#sH}$|uZi+`rOl;FTI2P>up} zYb&C8sn`Ye%ZeINf-bi?x3tb$fLl>~;mW$^>e|4PK=aB5wJgwFQeI!XvZUJDR|1pC z`jYa}x^q?RaiSXX0%(oqL@D!#&xN+!`o=(1p4iznH9CW|MCg&ULy6F6A9exS-$T%QZm{G_SP5>auxt{lzL;i(b-FqHDc`6qG@Megx4RsKRJc ztWEg2mf4C>u_Rj>bY0O{-5g*?fdA+MZOf3`N9%ERL&Jj7)959Z!D6pD6 zlAqLgal^{yCRN`MsH>=MR87r|_&;500(Gi3P+Q*6s@<}wmU@4AX(M~2q6eiMy7_+c3YbT4S{&P}fx7ScJZbz*mdDnOlVbRow*t z2~?2N2kKy+Ws9oImp2Vz7gyBR7NB~HuS}RUXJt*G@o;HZCCqktpk_gJT_UCPYFA#; z+BhT==-K7vQ5uivc=F0Xqjq_CNMUu|GSmf_xhoO$tnA#zTCfExo2pcUsnU|#mCb>c zk{Yytie<_R1R6+6XO5R#S?7=~YOG$i40Sk<`b%vC^v|hnXl^xS);4gF^%w-KO-tY) zHTA0t>KnBFDBpNRDZIxPS6*LNQL>sCZN1j41#+tb<;!(hx``=!nSNB$ZB~f@&?GRc8IY7pX)Zz&$P$5w(HKEIkQPfil&~2g& zMx$~)e4sX~VIPJkjJp^fo2u$pleBMTbxj5J5>-@H-DGMBwbIypSzVcKZxpEuvAxXt z8pg}Q0CY#YpG}B1BO**QLMt_z)-a^Kib|W7>tq^N%$R>}R{piHgo0B6M$Y<**%cKk zf!s7Lhx{0(jTz??6F_W@J|YGt{UmIV9&f-cs4uOs_c|S+qIps2s_JE>&DHgFF0UcTa3j<9n zYcL^+5_2d*=GIpPDClt>jO*nX4x+}>n8Hbgf!g|20r(_z&7-irvZ)3=nZ|)~ihThp zv#7qgvy1BfHELc*yDqyM^%}(m#iSn92X=5y1I$B9N zx?Ehl7-pG_B zXm1)md8pd*m5q&hJ};liaG0BrW_UdHFQYm7*oj1Bz37LjsjqJ+sb0aAAd~UTHG!rE z%s_^hVbkITWTPf1LnaSbhLlNI#wCH~OIq^LhL^Kf>KwJUNx6YdW0x)Gc9U#5WLH~9 zh|0w?je+tKl3UfH1uR^x5hi>k7)YpGP8W<33DlJ%#Bt#Zbgnq6P*YV1nbH12 zw!2XQ0rVJhU#!-&mtr1Sj};%^qrn@OAtpzO+EuhbR~nMbnPRiqJ|;6bI4eqxQd(|m zKv$pXmqeG-!WRbGUeFk5sA=UUu<7LGfjZg?;9w10g%FPbfH7UquCxxV8g-A!JgGEo z*H}_h(oECoIIfX7Qf=16C6$Xl9-6MLD5F^pEWk8} z9Ed}Y9k-)XAXzUpm?p4KX{GE7!_am0m`P(^Aw?@!*3`tx(m(Z zhi);-);8$fA&MZ{A?b$th+YOqXG=v`MPdrI5Ti)7nVu?5VcuaE?V6Z_322nS*pq9< zm^rKJV!Io(08vQ8Qm=k!0;zTGl$ZuU7PE0eB4$R-dv8il49wD&=F$f1HLZsAdL7$R z+!{q@>FU5&MU(9k)d*nNhOIggw^)kmTU4mNQm;bnt!*%IfsCt&Ex+vcps6lQ&9Hl< z=gGSI9CK&p#Dtlc0-AI!hK~_IsoZVtz!uNWX>3HJ(maNFT52ybYkr!=Fgu&Z?xFM* zi1Z6}peMOpnmcf;z%0e)^_617tWs}kl%PpU>Szp$g-6{LqCDIwp3tGlM4~|RTrEl3d+k7nfZVD921qP`-MM)`q}pkd`+^^>JcmC#rHaZ33#w${O0`sMPyf zsum4_nLs5iD6!cS3qZVO}Dm>rJz*fSS#9+ego(gXz_Oo+(W5lb5t z%qT_hzz7tJoiMMuPA#FOc%X(>YZdh?5qVZ()m7T4N}KB|u>nYn9~)9=O9ERbdRNZL zS-b>+uCaVxMRbqSRBUtynRG=)CajM!f;SMcdMBI)k%=Ov?9Fe@x<2(uaD}ryM9#-D8#lO?a zEhgOLuuA7O*M-fXu)_$jZU0WK48n_i@oOxKCGg2Tj+bWP|1%@#zt>8;nirXsyBgXud0r_mNm!%Pm_*BB5? z0tG?TvV~}wfPO<|LYI+=l6D+t8hu-C)j~~FQf8O@5Dhlb8bBH2w3=6>aTNB56J>L9 zCa06-pk<$vDoj?pE(lF!E6mzOYaxm$DBDSK3k{{K^%!L;%jVZDrZ=p)0frJleAbRN?ubEcO4oa4z{Y5s5CeR_QAKJ{8r-hP}!^|JMTNsuRKv!Y&oXa!5s3-Wg z-ejHXWUi%Q(-YLWm4%U7g)PqVxjF=(n^PUyL@tc#es=67p3M^Pf0ji7HuhUJA_;Ra zdee?wLw;PilugzZT8ovY;~NvJu1S2*U@O|Di6pHirp5Ru%`&JQA;*=NAcZJeJoBWl zOi%h^8Y$UmMZ|O{r8HKYIFU25>ciw7Uc&K!rbucd^I1T3bj+lAJ9c86brpS~MLE$& z?fWf)l1MT=RS<>vmMHdOZ(dz_VW84xD8%c((x!lg##hOSIX}7x zKb~dSMo!m-*%!N_Od~~emI8buVe`hG(K^k%3T&he$!Aj&*N;u5ryBCGreG^#-q{VS zUnf%#8&+ayqsA97q>0V!48COEiPn;4@mY>F%v6a;pnij{VAHilB00W4n2+ils%?Mb z9+6NcmtL#Jm0`YqGht0Nmt)_jv>AH~<=9PWu5O}TE^}XR?wiZOYY8eHz2D?7sBdi6 z-|=8w-(0_(-V)c*<~oKhk~2d5=}{a({ZSCqL1NI?x(J&p*xhhQVH;8vVGjnouhePa zWcdr16xAkpe2 z1n{~>8;2bh+K?-u7e;!^zFaT4RcTEF_V-aOstF%6Q6_A@RO{F0rOnvNrnl>ARV9BK zRY^NE<|C*%`YnmM&#P|IpHJ$2YK$1VSXFCw1n}t8^K0o_2F>7Bf960#26nR)CD_$$ zRvbDv4o!PKGQX$^f;iFVan^z|bic5&gVtU0Q+N3nqWQd|hd;ukixurE2S|o!F-?C_9n_S#$ zrIfV72x0a&l$?wAV+rWI`jvR6G*sLaB>B9R4K>y1uXu&0KO-Fa*7qaHVxlo%kw9Dy%{r)HPFq-cB3Pt4d0#n<%`>sGZtWKXrzxwHv0o z>mcY`jBf_vz6;^S^yy%X#Uw<(nTs(6*t}m{Q-KXuAx0#$#gmwPHz3aAgFAfx8B?G! z1;iM|k`#zyWG+7Ab6BHCMS2|GoTZ1#QmbX3We&D1@nBlCDW#!dx8Dz-=*aL+;NCfh_R=Xl=m_h{VLD+Oc%+Twuk>{4puIBT18DY&Zgcqep+A<-vJ(=q~)FSF&n52LK1j zzd9s6DK7m?$lAZ}GWp%n^sYAQ1Nir=_z$9rU(`_bIQUfNH}c;XTX~D^-yK_iAm98Q zS_=Ojh~+y=4WH`Zdznvj@cqnt9DM54Mo*@L?_}QoyD+xg-bc;fp=I*FGh+F)HlruY z!F!m`cJP_ZdmVfh^Z5=woB09IZJ^w=kO{OMry=oh^8NlF|LeB9qjekW!R{$x6O zqzL}RC<{Lqyhre9g2$ieM-PwS@h6edqnG`he(p{3nL_@osI*d9f=73Z9@&DwD9S43 z75r?$=LwKLGT5FZxOux8%|0N3jRtV zzh3b4n9oa;;Od1plg#&lda}g7*skO~L02{sX}m2;Tmt3?&x}p8w=p=kg2w zNYtr4ssw+u;2Q)#Uhpk~KThyL!Q0;~pfc7Ao_|V87u_!SX+qCN!CxTwu;4Ee{8quw z6MU!OFBSX_!ShehX?wZ^UoPZ(1ixJHy@KbT8q#|92;TlS2PH%Vf3487Pw;C5-!FLn zX-TbrK=45!uWpX{KmSyQmiLH$B>5B}f49(+D){>apCXY>%+uQw6_O@M(hY6g>Y_l~%Pw@TUv; zF42y0ypZRg4AFXe1W*4)xjlLXKSS_4gnr5I5%L!b`H0~8r*U)<`vgzF)n|`>!7mj2 zfZ!Jievhz6@@jpo-z^dHDT2RD@Tr35sk}BRBJ@i>O~{uEJs!c=3qDiu^l!-6BTMkj zg3lKGD#3dNZ+|bw8t*u4y*9!eX!S@I~>jlq0ov3rQ3%*XsZxs9@!G{H3DC%LW;P(i7x&-eQdhEYb zM)mW&kRK58uHYL4f2rVG1TWW>LBTH+^6Le^Nbv1~Uo7~Ig8zo# z!-6jq{8qs)5qziMiv+(z@K*@FOYm0-zDMv&1>Y<9ZwY>n;I9^ZMDQho-zRv#;QIw% zCinrtmkVCq67&BG!KVm5Aox_lR|`H(@Ye|5BlzWl&lG%(;Ijl@C-`i^*9+b&_y)n} z3x0**3k2UN_+r5~3EnUGX2Dkpey!je1pjTpw+Q|^!3PC@z2MgiJ}CHh!QUYGje@^X z@L|EP6Z}@euNQo$;BOK94#9s<@LhtxUGP1E|GwaR1>Y|CJ%YbO@Dah^DfoSY|AFB9 z1%J2T2Lykw;MJ`$|G!W0DT2RW@Tr1-K=5gT4-4KS_zuBm3VyTTvjqR3;Ijq)W5Ig` zzg6)0g5NIq0>M8l_+r8TkKp}+|Eb`s1m7w62EqSA@GXM>rQm~t-y!(*g5N3lcELX> z_>F>pO7LO9cL{#0;GY(Jr{KE$X;0px*w&05e{|~|Y1;0=5Rf2z4@C|~0U+^u0?-zVf@cRY7Uhp3Y zzFqJi3x1>EKM{Ob@Sh5PtKbI&-zoUd1;0b^2L<0H_%8+DBltst?-e{=Sw@dNg6E&y z)@c#J^FMi{`F(vf{(PaoU+_7C9}xV7f>*c4{Qv8MPZ9h~ z!KVs-mf+I_pDTEe;PV8ZDfqd9&l3E6!DkD8f#AJ@Unux|!7mnkf#3@SUo7}S!TSZj zMDSIDzfABAf-e?)i{Sa6fY9w26#O@Z{CdGJ6@0tkza{vMg1=huVZrl1NuvI@XG|>EBGqG?-6{p;3I;+M)3Ot&p)xOpQ~T+D}?-j;2Q<6 zz8~}dCc&o&o`3RL>rWMYtB_9<{PlwO2)<45nS#Gj@L7WYj^MKef0N+7g1=et`GQ|B z_yWOySMbGxzeVtV!QU$QD#70-_y)n>F8CI~^G~N6{}=onLVmsAe<1jF!QUnLje_4O z_^{v~5d2obhXvm$_zuDE5d3DrcL{!r;ClrBpx}E2|6{@L5&TxcM+Co3@cRV6UGV*a z|Eb^y1m7um)gJTzp9?-k@Q(>TRq&4sK27lQy`)F*JA{0u;CBi>OYlz$K3nil3EnIC zrv;xc_-?@$2>uzt7YqJ3g7*vlcY?1H{0o9_5d2GmZxMX2;DdsHS@7!xzgzI_g8!r7 zHwyk0!G{I^s^GT@evjZg1^*Yp?-2a!g6|UiUj^SI_`eIjSMU+R?-BePf{zHkPw@K$ zzgO`6f`3c!1A>2B@G2DZ|9=QRMezFspDOr&3O-Hn?+D%__;&@LDfoX0K1=W)3O-x# z9}C_q_)i3%FZj;{Um*Acf-e^QLBab4|E1uo1b;~I4T8tVtI?xH@X3M?3Vwv(*9(56 z;M)a%gy1&{{z$=x1wTsgTLnK_@STDmBlsPHKU(lzf*&jR9>E_c_+G)EAox9k|C-<< zg6Dt2TG#15!Jj1L`vrfh;0FZn5xlx1=Ktw}PZ4~E;8O)ZQSfPkpCovX;OXCnvPY)i z&lG%?;Q5~*)>*Ozf0mH<3Vw><^99fU^rF^NAoyuQzF6?*3EnUG>4L8k{P}`!5Ip@G z+V*G>e74|&g6DsFT4z}=_?be!UGTF6zftgB!G{GuTku;2?-P8d;Q60|(e~^R{2U?Q zC3ybSTg&$dex8u;75sd`?-Be0!AAtYSn&Gjl4B@a=+c75u?9yS5!nQlTv))P{p=p5EG( zRH8p8?FWzbVdt^a@&;4e(nB8igjXkclKx~*oi+n$9VSiV3xT@@o(bG1un*Xsp>=8b zxxg6$&j2V;6mUwfiDN{5cn$KZh@}`?i08S*gY{;ekE{*z}Eo#1g--v6Sxt$ zP2g3)9Rgnq+%52Rz7ONz-7Shvts2}0%r((4X{t(I^Z&a8-d#dUIpAC@U_6*0$&H* zCvY3EdrGYQn}9O}z6IDP@a@250^b4LCh%Rr9RlA2+%53^z1{_E%4uf`vmR-cApa~|83w5f!_i43H$+YnZWyj+XVg;xI^I2fx89%61Y!b_gs{p z6)S%vaE8F6fPDfV4O}MhSl~8+j|c7$_(b4tflmeQ6F39deQvD$(}6Pto($|0cq(w2 zz|(-+1fBuhA@GI3-2%@9?i1Jt?4A}Ye=cx_!1IB90xtqC6Sxq#P2kIcI|RN8xLe?> zf%^n519qPmE58yrL*Q$GeFE13mkHbm+$QiU;0}SW1@0F3I^aHm+koBEW98ojoFVWn zz&?R*2QCx%4&XL{?*i@+_#WVHf$s&_$R<+0zV4eCh+6H z9RfcA+%51^z`-)17`^Q4zMqZ+mHPKxJ=;vz-DFN~Ex7dS)U`M^Gb7Xg4Y*I>K4AB(Sov=QX9)Zb zuutF*fXf8l58Nj3r@$Qoe-7L&@Rz`SQQUc~+l%s*Ex+^Fk-!-Oj{^1yd^B*Gz+-{i z1U??PL*NsEy9GWKxKH2=V7Dt){^`IO0#63^2|N|JOyFt2Z352#?hyDw;BJ9u0{02* z19rP(<=U>S zxJ=+i;5LC*0e1*|EpWHM*8%ql+y?AUj+K8CaE8FQ0Q&^K9k@*3JAm5+z6-cR;Cq0( z1->7+Pv8z<_lQ{e4*_QgydBsl@K1ot1b!5_P2k6YI|P0LxLe?-fcpgQ26m5(mH!-Y zhQQAQ`viUoxJ=;Pz-zh(I78scz&?Se0+$Iq4Y*C<8NeL^UkKbS@J!%7fqlU4QL*yp0%r(3AJ`}G zBH%KC3xV4Nz8tti;H!YU1-=@%PvA0O_vl#pmB1MSUjytDxDL2X;6~s!fmZ={2z)JY zx4_o{_X*qv>>d*<|0duJfo}o!34A+nnZS1dw+Va~aEHM60Cx*~KX9MG9l-9RV&y*s zoFVXbV4uK00WK5xQQ$U#9|!Ib_zB={fu92I6Sy1LeRQn+=YTT=ejeCoFutv7S9!UE zUZoy8_TZrt?7nm<_N3E2$A{8SRw2lAD!Nzdg<09^!)*$`ONo5x8+?Pakw7PEunhNJ3#B#Myo-5@6_qf zxID+}Qs-+sAM*_ckw@F};_ShvKRaqt>_8`h`McJ*o9-dJ-o1ZZ@xc70{ z>rB}x_vH>!yG4>z&Oefpwx5oBs*Akis7&|vz9iRn7nPTkvi-&{P5ro#N7vKqzQHeH z??0^#e%P>i=<~nD`BZA&;3nw){THmK#n?i8g?(<^hsUYG%{Q{WY203WxJ*y(;AzmY z7q&iw>j#5}?oNk3w145jHM6(DZ$jk5)~B?c$kPiO^*!`_0)HhRwC{i7WE*k^zhmu1 zzBYT0e21W8*nF^imypdv8MZtH-@gxblCRzXU$s1N)CWoCPNxj~Fe(GPNahx&40w`B zWS91f;G_^;RoA2t`On+1>kaslwqdVt(1pBOE`qjGs$Y3d({it~oYw^oeaE#HzKC>} z_p~^<-BJ#9MEbN`FkY@l%Hg@9a*=qsr=%R7Eh^_dJ+9oxq+AX3r8?{2;b{EYHETr9 zu8T(G=;sTb9{L3S5>84EDWyUa)~ap#-Yf2d=6+YXyH)4$pAl+Dy~DQ$&qQAjKj0m7 zFHpvw;29yR&j|X;!{i@IeW={3C_HOU4(?ZMa^W8G<47J?h3iq!MR}-P>R)dpjobe5 zfQg@B*jkIeKzh0;??pxr;(1h00O_X8aoca_GX3x?>c?Sv&duJzOnSx#&=x3@bd`R7 zsEGKP#ItSbLjTjqub(x1M(BS`e;SLwKOC>iN9-%5XM(-HkwJWB7A)L|`p< znV*Y%^f?Ye#p&ZBT1y=~VTHMr{|SL?2KlX5!P9#>>? zDEy2&bUd{yuKQ5tu0uy`+jS@f=aJiXEpfF*WrJrSwz@*2A*)ndVV5i17{0)@bJrm^ zWRq|v;~cSV*99o&P1U;V1y`(`F!CZMZoXjl&M#0ObpLylwF&xc-|9fx$)?R$kndPN zX{}fHC8egoPZU1iq&S?k{e9R$`HgQ*2~qxasK;Yaw?p#!&yLIcH<`EVY@K%{@{;e& zf?X6x&G`K%J$~DHfG#UIHFP@p55)=ZIiZQVt`+yIb3=C{zfOys8`@y+z0*P=dmo+_ zy4~J;&I{dY?<41h*4umk^w4+gePnv5&EAL44_$BX{WC&q?Y-xMP%GVE-=+H-{ub5v zapZ!~7vOb$VBDQVc3%%$Sq^{eXyp9aq4V+l_^e~Ru{}FBKc?c9{BOuIp62I}eqq1VoN?0C|IG&^T`1Lge%gm(lr{&d_^o@t~TWwwFSeGlB%$#2hs&aMsZ4f26t zPUy?es66k^>0}>t)AJBMxaJw{KdB?zb{{Iwdg0(2rJpN&j2iqc=8EBSQg`k;D|ILJ z2bXHwt>+oAp^eH1mxO!#>f~-?L%~iOPpM2-I7j!V0@GhU^rOG{F}HFdeo(&o%!gqk z@oL{`m@m`3N#)R$+VNW`BbtYvqbn!$81iZT-V3#!Y}OMQ8PkLDHwSgPVm5QO%(Gc` zHrI;_V*=T72J>CXst8}tji<6JQFaSGKRx?d1-d?|&ud%XJ1sMBCfL@isvqV#!1d+^j{cS1ADX{)Ct-#hwSk|?g7lVttMA8gxpI&13#y;>K=gd6XxNIwIK#EUP>|9UIX; zMLMkkevE#s$X_Ar_G2vJJk;himsv{v4cr8eJIAJxzW6#d-%`oCa3dbXx3`IBWY>wX zc`Bu&?59x&G~R?yU_aPm+8k+S{&a#Db3gCSFs^Q|cR-i1BX{tPB-dnjOS-|x1DQdR zp|vB`Nge$8>l}BLQiZmkV2)B`>@so5`h%@6SDM%O;{oXOssa7XCu8X$ygN}( zleJAGkF}n?A3MbFp3rfR(p~*n-&23umpix@^S+7jB{$-%>*!!%4f}Ld=5-^J%QBme z2^N++WjuLWPdUq!jt&-H<&@EcB<1E#FakZHrY2{QRknG{pjGpy$g z$joxeJYvdv6EfYTXH>9ohEryPDJu!jO)@Und^TkK6vHD&hr%~v{fN1q8*{x3%=O%u z>t$fB=f+$wJtcRWD`kB@3H)|VR zj?^7Q9q9Sh#Y1%052Kr68pV69YpY%->i!)O@i}U{=NO}3eSL`jE1+Lt41XE@sQ=SL zcmI+4Cv;O>qdt3BeZisna#`Q6p|2fnd=Ad-RQH&dY&xuMGl$rg1zqprq-S(xa=RDN zxD&KCg#hp;_Cz4a=7cJfD;tvA1W zi2mO}erEPx_X%TLuS!FIc%^-Jx(e?fG``%c#^(*XuGzTz6N`%>^Xzwb ze+W$D@C%>(7j}D+hm?IU%KjWWsJ$@>r#ek+w;C}d?`_s@^fx=d^uneOz{k%6%orI# zIaipt)T@vO{V6AYoP07mKi-73hu*i_jD1Y__t&*fjO!E^A|pb-L3?e&{8HPCJrdd< z+>AZf4vg3Dpd8}e;OXkxXs&8~?qGC34?3HngLI!xx=(`cle`#P)nwR?u~c2E*AP^m z8X4L~{-I;i$j}=o>z}B9jl&~Dn=sdZ3)no%v+?m1>n&|#GWPwh_vX+%R%7_p2onc; z71A)*%RvmCOgdeD8=sB{?M-q|j_(H}woiqH)l{PzP!WisHoA}nNESIWQbYcD# zCpRAZDm*rU- zM=@vHggx30jF-D6x^i|cRy%3^tX^ry`YPP`KI%s6>(_I-96blax=9^6WS;-Y+`$&x zry*nekFIyL56wZtDapF0L=G?v|9#+hD)=eqoG<*1{EEvE&#&`!}f^zZubI_d{hwrz9NBgGV5@33P! z>6S2s(9dixrNnp;3cS}#AESo0gn7!&gGso;9-__4y z=YbsG5feA9Q8^vhTk=9z_>gWhZOhMXzkv?dv$IWG;(p6X-kqD*cyl@sLknT+$@D(# zX7{!ZGX`L6p3HVm4!uor34O+8=T}JknbF&?uop@7I123;K7@FjtiG`c<&!+Ek8GVh z2>CEc$Ya`{@F-V`RjK_T;ctmwd!8K zQn%7rwFzS#jaOxN-Lbp-wJrPI-+p?3_i26m-D`dK`VL%mr-EKD@zLC2mD(4|N#IsG%>4(lP=v2_z1)Uz)>V{4a>vVg6xZBtCKikUd9ocO>oMG8#z{}=kp4Xrwuj-z&V385gZ#cL z=J$ChYa&iJ%Gv;5dy4kWFy@T4aR~D1NdGSNSAI9_x8pA9^5}J(?vogKcSbPBz;oY< zKG2#19owN#k2UaNs*ee`xjtNo{j|uT2jKg*->nyji$ zT7o_>TD44ALS<4tqs*Pru|0ups^UZ~YweS=3Cn;yl_B)E$~^Mf-LT6uE?DSYt4LapVHzB=C*n7Bo z4MR3jz5X3~oqc7vdeyPR=}#>tc08SAVn;K4fa>o*ZId^Vk9_A2JmZu6jIvGMK>E$% z8UJmYm_B-`Y!B++6c@H6cvfedcqt~rXA`!!LpR3PR_Z5au3~&IVI4J?I=X@D=&b*; zjy7{0%|jhEaUC5e{B{%4XNo%NBEJoePo?MJc+sh!3H>V!S*IV^`dONwe%^QZEb2$= z`geL0)s2WnoqF8yntE};Hx+!~Ej*vr&+EwWtghBRvwrM#b?LFES9wztt{?B;pEza> zDKpQMna*YQ9Ii}ndMK>m58=dR-teE6nQzLR&1F7(xH2PLrsvp%&si}{nbCGJm}lr@4d|?_Zp; zPRb`N!;a~W_K^9UvCsc+%5lnv|4aF<|585kZ{!m`x9KyND%A0C^_wuCX_HHBZ1Czi zahIL5CTthaF!qrzADVz~8&z9j1lPy}Z>#kS+b@Ith+&w6gfXX8YsW01wT!t>9!KLC z%{{^wFo*Z)^j$><);gOn@V0I_&)Z6V=L(NAd#qh&g~mW1e6CmFJ~n6Jb(wufl49PG zOu%(L{FuHKh~SzA|E4`b-mFNcOMLoR7*W6{!_6R0?vETZ}Ca$ zAod&Zv&Su`qP@n2m%zVH68H*UQ}ye8n4Q>vIad1=F!lv@Zo>C9y8URa?Q!jhwxwBr z={~X!WA#M5>!h*z5AYK$6I*-tx`G*IE)p3RBHOSxdN6(uJ$d`L;LB#+X7+dJUeV!s z#H+8~?|TofiN3ej&#aR9nNPqoo*5cELW|zoT{Im?J#Hqq zw=pK$wOd$>yUsq)1zB(0n%RuE_d&07E~D2%Ò%>TpsD=_tU1J~c=;p)#j(X_KV zE@A!c{n!6l{k_TcmyP->OHhArApPwBu>K;$)Zc>tFYB+!)ZZqqzt`{_iT#i3FPOOg zHYBP)-7lhh2WHH2_+JvQ!S=y_>01!;KRNGnA^optQ|o^b;eQEZ6Xq9sFUc|9(mM5X zyiaucp`Q1}`60(I^jo~MIf!>Q2k}1SV31=L#VYLKwQd^cJs25b`ncxSfJ49ZN^Ujc z+4UG3%W++U>oQzdBOY+`BUaaZP!=J3Jn>qZ_d+9nVj3p_$s{ z9|_`uXA;M+<3f0!37ZkaV6QWVO`-Pr2gL^y!*qO5S9%c_dKJf48TXxi+mClh-nhPP z_UEE;4|50J4>NJiWBkg6*h}{3k^Q@3_S5@JnqNfMp?-c2bwa}R*?|uze=NS)xP~#s zd~bm{gv-2F(teiEH|(4$&NndM!Puks_%VlZhm9RB{|TmEyV63N@jXWi`JmVnqd8S% zmdbhKBJ&=I_EkNet`j3kp2;+hqh8w;&sEZu8f7t!Tak;*d!rzHIWo(eWAi4+7u7@g zXxy>$Hmgs?_DS2tzJ$Ja)4l}0gG$tHI)7|G#^kl@Jpb3I4~e}V+t#KpQyXgvSR5r@g_Q8fB_C-z!^&GBj+Rrj^S^I(B z-{3v#Hq_xG^lmh^M{0Zp>8qjB#^tby%O=gN7xlf~-@yJJt$jSahM_zZkMDwB*t{L{ zndtijnioVS$h~Kt7wEM~S1awMc+k&j4~u-D3+2+ies*e$u2Vzbqx#T3FadQ*ei1CB z`3=cY*(acEj#ce?zbweHir>?GjpkA&R<(;cSf@+rzrE>H3EtDZ@;>Dm8lQGuuW~4E zETweZCwiAdGPJ+BAJS!#-J-9? z_BVAKQXKIkhCAYjU5gHBbCUNCk?%UJynmQDW&4O(o0>L{obbSj)Q)=10Kc%$YsQr5 z-e#w(i=TU#F=ZK^JSrV`rFL)?nnLI!u2;E z_F4H&NWV1X|i zc6JS8=luV`PL-_2({ulM@DRe>SI1X1@Kp_bRRdquz*jZ!RSkSq17Fp^S2gfe4SZDt zU)8`@HSkpp{NGpu_U}0GZx(Ja`&3WI{XNSr2Y=`p`rWW({GF03^wC-P`y}k=?E00; zdHo-}cb+Cn^q81#~D^xen8cmE&u-UiIBs=WK&duBoc z36cy^0tw8SB$}9@K~Tc*HD?m6RCooFRD6n+6Say3ixHm}#-!#1w4kAdQ>dcF;7K%`aGjoYmR#>^GF4qZ#|E@t~L~}Dx6a~=4|lT1RhU;{|(f!^#IDLP0dwl?x|~G zw2nKt)*SVu-N&=!V~;cc20jEI(etJIqYeA4Zo6>PD$Y5~EpQ%Cb*kX;=Yb#8BhT@TbdIM6)13(mZK&*2;l(_s zt#x!WHy1~<|AxGTvlpT}dW7>vtfOgu`*HF^-Zb)bo}sPI`UOvB%Ldzb96HO=GmC>A z;syCrX0SfQbDwGMIkm$*g&VkE+0ETg%-av@F0c`4j%>n+{N-!?tS?&XNVr-Zkk7@M}xFC_~Z7O zOCD=KV9BHHFI)0R`~IAroU!Dg_UWwO?aQ4G)3%TPv<1y|Kff%RAF1`*8j#YDXJ~jb zL&H-U8lKJ2@LalPab*-O)*A4j=5E#QaHd^5dnfqMXX-{f({|&JI+?Xy##3jZ%Zn?I zat>5y^B!uSsg49uxsKcYE1-MWe3&)ezNVwEm5;71F0He|DSr<0A^sV}ZP z);O(r zQt=M<<+${1#XH(U`u5@-?IB$&-q8`#cNOoL64G}U?}(HZF42<8KE={ub^e{a+P0T6 zZOg`syx-vbf!*O)dvJ8k75KR1t8PtoC%)#vj1N$qhpD4J;1^4EUg@N5_HrKmOQqVv&O7wN^9?sRMFS4JmWetOrAl_f8B=d;r9T_1|p@%vY6v>qGr z|CZ2?PG`YB4rc>jx^`YOrk#sI zJMR4bOT)L~Ysa+nj?m76my(`kW7;_>w6o|XY^QX@n0A(gcJK)=nS4sG8`I8A+6nd$ zabcKZm`&URHpV7OM{?I+-X`Ku7u%8F-;NDlhkaa+?tUJ%Kw!>+lcvJEi+C^KEf|+%KUc*H-yh*H-P=%3~gnsB~QA3CitVTaA50 zhG+5k%8#1cD4gKwIid0`+ISZESy^bmueofXy>>$7Yn1&-C=2fLuQ}X{Cpx(06D$8f z*?$jZqu$C_Dch>QQ6KYw^aq)KjprV_|IN`5(SOHJu_u>(JK4K+&H)zRW{2_EBh-_u zHw8VY^;Wi|?d8X4pME6Z5%N91*cT-ns=!JtZeWiRd!g<_-ih`^9UiUgMrZ9?F{)e& zeAC%`8+}qYI9b^vGG%K~WkaTHA8p7Uv=7tDGG1!HjVtRy*+&|1)u&t8#qKP<;ZTb! z@5z)6aPvHN=YL z;Xt}W<2$uqYA1H@Aa-vjc5iNX>h>z_p61();g8kt&^-V-=B)vZ)SIuH{J8bo#l3q^U%ha zdwaQCSN9SbANQ#wx=SIX6(cKMCZD;3G++195cdjp2R3%C$A8cIaL=2w&9d)jR4*>t zeL(2Yw90#_^OtFz;Hz5Had!w^sXK)JkUE>jsUupW+Dy%jsJ}WRcKx&E$sc9EGfvXp zOK94+Qo)aBztKP2-cb8q-?#Ec{N?Sm8=*H@KN5WNEPZ4CCxuzsud)G{t;!bhjfaAN zS~i+qSvOAEuRFL0re%}qmG_KOcE-bQ9F~?X%&43-PT6muE8v@fJEL;?IAx6oh5aiX z@IZY>C%9kFzvwuC=Wb8C;xo#+zJvSvp5vRp;}==Ktnw`H2aeHEC+mHi@!?*=!@*~C zxCzhV0hL#g|5?hXbS4K_JaiNA)4XVAWgg|O0OuT?rJ0pijG?nJmOTx)8pl@I=Q+T? z(T+ato7TzSQ6YY8hwo{-#aWf#!VmH0x@>+jtMVNACGtO)&5t@O&yZgx|C(%mxwG;l z`L6xWium11m)fE4SpGw~hW!OwO5-Fum$Vg_nhy-)*|7JJKG41|rJaescY$O6yOUp^ z;G$2BxYOl7;rZX3U-fcr&VQKlc{&~bx^EHt+!b9XpG%+1eSLS)W;RcE$Y$T87I(_g_uIGc9Ajsx9*C|Syt1P!%@e-w zcXXwB+LON!nAy52cVSbxGgJ8mJ86sw=0f|e(qnwh$4}1qF(CF`IQy&SRB%@6MUt*h7M&$!@GI|^IOBenk;7?iI z=VS7WX8XI;LM+#@{Zz^i@%to0nfuqQEa&;8GwAWiRPj{5VZyj}Ts)H5IXsT`c$}NT zBgMJ+@?6=al+}Gi%&+ZM8)xAU^gI}zB>qlAwYzhQ*-Dd+=3&hN)@I}+9e@w3?y5W8 zH=0VXpk4h=19YJue{JQ8Bj2NpU%SY|PEXd_z@OiTRcOw(S*XPMc%mu$}p341cQ@OXu2Qa7H@PXdPJHN@fn+C4M z7VZ9C6TFW|H=63I-P0|6wS%BkUZ8{A-3! zhcv%9Q#j-&&lK%$w>RhScH=HM z&R^Z*?}*zRJ-OljKIVo8&_CH%M`4b}WILh4m~wPn zmxmKK!4V&t?`6o<|H9<;lZoiKY4ZBDiR$l|yncP6`d`Y|AD55e&VbC>%N!qW%fo5O z$EGtvx%#(HUcWd|{o3U9Tb)tDUNo1nBa+R%J5n4pp-v}baIo0P)jua+e_UQRozL{~ zmxFO$9!5((Hl5AN@v%NRADYj06zOcjOX$&nrX2!mYMqyb9JNG`P|@_oBUJi=bG+E z%)xj*-~J@L$lc?Z)6I|Wg>E+8qmrwC+2r-hP4}7P=$Mn|MKd4etCNZ9&zrn{ZKC>x z$?MlAs=sjZ`px&y3`u&C<`^@BgF15H1AO|;@97e+LU1ZPW z<#0WDa$0K>)jxIe`t^zGpFVm0h~MI9f&Z1(7p$@RS2o2r>AQ5TFj4)tOuPT3fFx`vWwxON-Cfb(hjC>TeSv*o;Pi|;Sb0|gbr8y|H@rboy zdsHGfXK`f|@>o+Y$qs0z>n`?${Dynq_bqqo9(u#I)K$4zbb#AQ=%e8r>awOHo>{qa zp|X{7`?`6$9Q;k8Org8-Hk`{ekU>r zbQ_O<)8O%);;H2s;4$q49xFCaQd}2Q z)I-Qz`CinMd=EK1-|qH&0JCc` z`-OszvRC(MaF8r6Ll#yR8SD(-*~|J9|GgZ(%b)Rkx>evB?zJVAg|sIa7phFN?=3G) zdEeR0Bkq&D5BTEIf*(4*r#$+F;n8bb@u>9Llty zbg_q{y-2k{Tj9ux>{ql60_$wbyo3KkTa{%$<3Yac-v&OETJV9qF?=W;Rhj1NZt;AW zJsuyT*QfX|_xSh0hcEoA@xk^OI9qysWjT0?r!lZv`nKX5QdkQ!u&U@5JZ-=#zoD|w z!}<^OrzI?YvpDc|mWL&MQ~OtQhDottk@Tya{&oJbr}JGr&7WjrzH$TBZ^2!9*vA^z z7{8N=pPu#Q*3#x6_@5f!=Hj*n+{ZKJe+f>-R^>A^{m7RWO`_wS&~y}alzv*gC%!!* zz{t|V9?`&;djgF4jW|6nc)H4w_R);|J-Dz&w`b_*oa;I*>Ni=|kFF%#5qPJ3S+nmg zE>Gd#>f!gH&$&&Wxr_N{X>-NMlzBs1x2b6!3vSV;9^`y97)`V+$UTa(xKR4sr z?{$3)uIwK@+T;2ykL!x@apfMkV=GH2zjG|Ed^;}1^^clxEgjSv*K=vB8P~s+U1Lj4 zxN`5=ah2&F*8z{~K@;Jc9A6pb`=?srn(+xodR(<8JahqjYmj%LGkW_Gh0X$B0gD&J}?*=RB zt$dks`vA*mqa69WqC!-;ML3+#on*kMPjz>a9R^Jr+lr=tfF_LxO(S+obKsxv^c(J&kt13j(WoWmbKs`eX%=FS@(~SwfKtukDQ3k4xH`oB-Q)BBJXgg zH2YcatFu-=%zV*9y^Y_$^YB(315S0nhX&l%)X_!ge>${xg#WJg>d17IxxYHN$Lvei zlm2Q@HuA9QDxY`vojEP^OLpbUk63xt)A}20vct>DgAdVOAHSv6&HmAtaa|~*xG}(y z&PpbV_3F&KMfwIF!@b2Gy{mop^sM<;Vn*>&x~!+ZHTLs*9T{Rg0UZOJZ{7-Du47Iz z(jM0DuNHAlUJ)aqEybtiMbE`LI@~X`HeGYzyIx%w;9|i{d68dL=N5Wmg zrql3PG{c{fQ1%>b&%W!N2j#1jO@JqQR??S>?qH8$Z*c<7(ur@;hMrL!Jy^;fCGAr> zoBdKt$GKlXM*k~XFJ{{l&g|X-sIZ43BIZxG95|Ib~YFlqWgp|@?~#Rgk0VJ zqf5d0KRln+{@3O6ga`gcHmCi}Lub)8wqbZ6C!cQMahAt}a#hlam!aW7J;URy7I*;L z@W96IgXdX1)_%|7(f)mp55M7iPQWdRD~eYfKf^xh^v?T{q2s_28ql#+?@yNOlvipu z8#F$PHf(OFm-4pf2;7;Q_GznMm`OVJVb@q+iA>9$)$1&H7ZPX+~@b&xIcE!mnE79>I%F z_2Vt;)E11X^Kt5Y)5|@tmkmBP^RUOm-&@|9j*i1S(~Z60T{kup!@sOi^WUH`rXd9QXWRHay;aI>E^q+-{^Rl+Na$uJrzIOg%6vWZ%=)#@`k(cafe5+ zrMxQK37yuPieL5hklPy4CfDGHQyApOCr8=`l)}jM83&;gq9vot=7&VDe1+GszmuID zgq|`6VBg#l`7QMwr{GsY-;sse3{!oX^0F{L1I$)+C+x?P22Ph#e<0J3Eq&ja_^#SVd)d#9S8Ky1z`Se??zTDTBPRo~-po6rFy)VQ{Wy>;NCSM!GK839u8vIl|E#+A?2A8F;fqzYF(g z_ympFRW?4t`Grs?*rehN;oQ8hGW5||8=M;Kg?0}M{sy@D`uTm$A(mFVijUco@A_Bz z)S+9L8@Q49a1pf7zx|uyfd$2p9(L(d(w{SDvWe4VG{5aRvO_SosM_qCDilD=6wZE-3-&eDf-zdAm* z7u%4`3drh2a2nkb^^DRt*YS6zpR5!6wDF(@59+=js#9*5be;8E!MRs4DD~8b*VTu2 zq;XPD9k|0=h)I2$!;JmZW;bmr9v$6CyY$(0A3K0^NH^N0KL_TlI^~8*Q?}8r@Biw@ zHMI-e;f-V4ZTIa)-~i9OjSRZqH6(SnewI; zd$f*b=^3P1?=cw1V_%G)e&3DD2X)7S#edM@(?(;Fc`5F_HyV@kiH}Gth7oU1m3~pr z;-mASQG05e;?OGkp;(pjPn3~`ttFE82K1;4`!2w9=}_Bj&YFX-(nZcJJnVI8*gvfv z^xlZhsa~1bZ0KBYUFPv-PlZn#-et`_p6l_ZT$Oaf9s%KfxoD!E;eBokyu~|gE!tJ< zv9@GmdViqSWBz8;>1a&8;!9h*<9ku|5Mn}XGvYkO0J>*%={t1&(9`n+|NNeRO6Ggk zf8F0B<@}1BIb`fJ#F%I3R{RHe;Ujiw>|;8Be@RyAci{QGaO%Geo^t2LAajs|L#M!x z5Yw}7#HWoniFk90=MCkmq>-cX<|gqb#Pp|(&zm;RMXGJ{xt=!dYY~sdvu^S1G~WjJ zqi=mp=W^fCK%y*)!uA#(`+3J?LggSBVk3ZOjxe z=~lmrkKCL1&(7syql!;f0k2WVkDu|qRbrR{e9%^WwD}%l*w1tKndS^+YZ@O{Nz0!W zuvI<5XCz)o-2+|zCHJe(Kvx$>v#f8S%qzf=eq*pIAHn-Oc$ZH2__eb!$K=lr$`5Le z4Bl*2j6fS|zo@xYk5ffoW} z_DcX`ULHpCJb+@7A0Si7Br5IffwpyJ))4jX#|As%;-U(&+7Yp@rg`q-pPFeZn`Z9cSHby_6Sef5l zqHIquv0I4IbFuQBVLaKG+meqMkS&6@WLe0JDQiI|H1B$#!{HqA(1*^YL4W+XRrMLa z8XVDOb9mI@4E&(Z>$>mUkffa&619fDTjQN$G7eB5Aq)`-wn@w z9ko>zd>?n8oBpnOScAye#@WO}XJLPyZnM9$+}@aAf8DZm@(ef5@mg7EWRAIqezK>q zA(|U;*XPN|-C_;L1EVF#v+8*WZ#Aax40BfP$gmlX=u&)IZ*SjzOX@qq+29850q1~c znD0~@0Y^Op4xyZEGUOlCWY?)J$Tuj=_)`M4O{QF^Czoafa%8M8>1BX=Q# zD&t6{r;vtDV)Wqi8hD3s*=O)s!LN?%m*zG3CEkU5@Jm~S2k-y0iBIWVP#0rT+16C} zFb^A=>(j*J((^ifj_gXhCL3ftosLPL)L58$F=gvrO?HOf3?u)noq0HCWNfVyJp8z{ zac*7nh1?bB^atD@lRxL3F_vP|*LgYZ4s$B;G-#Hc`#C1X&MoX^(ZKOENbd_CD@y{Z4TIXu4GSs|X$>CP|NI-T-)uiN*gdAq}rrOI<=AUAIZ z{5Z_p@eLp5=Iz$N1N0c4rt@~{`-gjLJ;Et|AnFP5sB?zp9f6MVZCLGx{;HK8w2)Wu z3sI>tZ~R;NHpM&^mqiwr$;PfReh2$%=vOnp)4A*n%%1?Wp+k+jtzyL#r$Pg#A2i`4 z`3t8DUMNl(nDQS1r& z0~5e4*SCW&(i(R+ekrrg?d-_KGR}@HR%zH#xBO~zYy(}r#48tL>tQZK@q6<+cZfUX zms6TacVnaRuBb=0+8keovL*Qu)oUu3_Idao>zlA${K<3p*?#5&`stthWmCtbeN3>q zOrN%l-=1F@_2a|)WvA8EQRR)`!kx$4SMvNC{}#Uk=bPxc=n8%>jMdDip2NMb;9=>@ zIeVjfr{sglkE1wE_W>{NXuPl0`?T18w^g_f?;5>YJW+Z+=>U(rB7}#{`xn8(@^|R2 zvPS-!@ALWi{g^psD??g-zAAY162rA+EcAMyy|2f{SA72x^-SjE^`hI-KWOe$92|H$@F06GDElq^W)`2$Oqn+3xT7TPs&rdVa~_IwYVo+Ce=&i z@k#Vj-(t<1OPmwb?@^sRxB=9!@!6OjFFW_w`1l7(DA_-8&F=Hp!53HPM(i7 z8Zo0^FHjdefVWKRaJTUCoVaE}yZcJ@JX=ryqt+%jeyFZ|sNi<=vV9^}>Fr>S<-W4?nvf zN@X=pjPVNrj^qRl?ySdY=)S&z2Xn7In%C~dmRjwH%FlT>d~*VSvph-TPk3?zya+l! zx-!4+#(03ZAN<~Kd|B7cT&TTMk8#Av=#bXg;-1k{&>O~}qNBbvO*`Gu_`b#&pH=L=K{X$@$X}8 zBE?tp4d~D4o4^kpF%`*=*zistDg&(s$R=w~MU#2-c`9F>8tbf9u-`LdW*fhlY4pku`6g>^HF|v6h~iPk9g>O7UhLukV+f@w*V(0^ayGpEkUU&jRy8 z&wI*MNdwF9wzckn_k}HZ--P!cWbvK^&#=~gvDbO#W^G@r{LG&9ZXGC%6|*{~`9)wO z1AcRdzEo++n!U1?b}_$O|Nkoa`mJevu=M(u;$vfOrgORMLq1<~1@z_21NIk~2edk* z?ORgpH+}KtihP$$-{oV3R|&=_@iq0CUnCxmrzdC9=9v@M{|2#%;K#rZI0!~T?NdLY zemu|N6!AnyPq94>!sA}zQ`*#Tv22CL0q8UR=G#r!sN-RX85{d`sy+s^7$Wd+G;(~y zE)wmN2>j&SXW(Z7&vj3{e!nT~Nf>D2<+jZT_F23^J`0C+C8NQlaBxmtcxT=h7p1#%E@_t-x>VC5-JU#zjd_DdC zeDJZeu=M}(8PSIJ)uw~IOGf%8`70ewLw3?h;i7dIWJI0KRo>_GE}aZ9)O_|rRgvQY zbboDO=ONv^^KFTq{CCnH^yKy~fLq{gH~vfCq?3z@k1c;!Urz_H7(=ZZKu=6JX!n(= zZn%3J_Jp$$S^H9a`8(>y+$P<4&wqh#obi8%ZajX^e;?hbB3J3hLBz|>NBr07!KbmC ztiS!gSr6Xx-%tVJ(i>>FJurwv=hp+ML(>qV^-G9(w{6 zgU9$*y~i{7-IZMY5$qzfwi^0Q?LQ0t@j?8u(uzNR=+nd>iN+cal1I$(ee@!019mn_ zb3FCFoBm)vZ|B0>M*QER{|+&(VxX?r;h_F|u1^b}gM3=}Xx~N`?Sapi zn($dGxgEqeol{hd82an;eJn(Nm9%{e{k1PwZ0fJyB3N@7&oXW;`S|Gfm8bEn@Z%1M zDt9%6b|UU<%*ImM_iEqNA4|rxtNA2i^r);J^S53)tl8^Pvi0N>%BR&r!h1B)t!S={QL;~^*k_H z!|wsfgKtkEkFaOBWq{ zZ|_C_`a8(=&Tr;@%KtCdy#2qFHk_5~H;8NVag+Nk6`Owv{R3m-w0~fpFYOqF0;qz?rb`Qc0-+EYEw<;A{VW&eVWW#oHRwvYWd)_;xH-$KJg{q62te;dv_ zX8O9b-JYJUXR^oH?`dk@-+ZNb1rM#S(EcQi=gtJr(|D?%4}IBbzAq!cO4`1KzRZ_v z?#ucGo3iQH^AzfyGI3oSdn%sLnBK#Uj`w5wP+z!&v8T$&|7pynwuqmsuhYB6c)iH` zZ2G#;Uy&DwnB`>jN%c>5YXSxOJ}WQ!k7KVldw#SpUi^vQ25)+uUR*4_U{967;akMF z2$=eDcQ$?+rHZ;62^+)5EONp3x~90uK6y zObU!ytKeXDz*XOcht?RfJh%@X5w5~d@VX7p*yG9iUItIa->vY}{+lZJiT;42=CegZ zqubly7U|<996%dI5X{#;Y@Ye8FoH)UPw|QHP)6lb(tr z<=eC_X8F9k?+rfr@>Z{zPs8nwPX-H^;!~#ns>YhcIDT%m(>_pz8|`}PI_y;=!VGFxQ2LYJ(+rbFGaL{E3{>8_d?_t)_KR+q{dQP=nJlG zoOh9qX6-^YejW1LdNpvb#dmE1Ps)5eW1FTQ$a@&QeCVvG=VAJlN2WUYXJLhPr(xN+ z?s@<&_iEU47@vqtT^brV+v(C%r9%<=!x~w-M=ZZ?^G#^f_c33r>rGjp%fXRX)f<(u(!2ch56lT4qH-htBa)z*(` zEg|-O$EVGIW%e?lkHhWgBsdC|Y^jb<$--R-9{R36;05}xRYAA$cO$_^W&Qj_{!2Un zk1(ze{K)K$ZL!YU<=4)jL%hT1Ot_}{e)uujn(91sIfF;%-ma;t{l=V1Ms}0*xmxqp zTvoJCdH2q*%f?(kn3ak4`Lyvp*y2&(Xk$U_@fz$>^FLL1Ap5+VcW~*{xI#KpB~P~O z@N3=wah`SLE3$9O)8~x*gHM0i!OHlQhR+FWJ;GCZ)ErB^KC~bDcAi>~iHLDF8pG#C{~gY|8-4g*^{MJJwg1if zO~!!M|0$3DInny7(i$T$C#rR&A=araUO#}Cp0OCXt?SktDDB(6arTv9JK9@d_ovo0 z?qkiz*0)=fNq|#8-xG~Lo4%u?ww`2r9@Lh`7MhD~DyO!p2e>g{89!?0Wm%sFk5eqp zhK4D3_p!##Z?`Hw*O`H(eBThw)f^YUAGBnE`ory0mWbXz$0mlr=Ve~*S-JvFxiv1) z=jVgpjQ)HjH(m_$vkf~I{<6*J&&sQo;YVa^-O?YPQK@D;EpYw^UD>_T`oo5;sBTw@ zxQ1s(nLW1p?Y!4>pAGL`*X%x8DcV&A69z=Pd_Z@Bm~ zR*hI8GY?JtGC=&oo=NL-kW)kFq+c5IF}7hpijA{4GjHXL-^4G{BlBUzH&ymYYK;?H z*ZG{0Dey~UqcMI`F$(LW16{zPTxvVauPVJ3`M{S>jgx5C#tGa12_K06SNV6PHtPGj zmBb+G>!wD7p|1-t}pL*V@Nt`IwFsf%ViszqqmDa&Ko*10Ngbm_201IeKpz4_cgH`SQ(tr_b5z z@n8XY$$!=G8KG{(nF`Y}^)=jwV*5o&-;7^X*^<{EiAA91I=k?CTCbUgns?WCHi*lml5af`HO(-i{lKnxO z{T|^THMP?+HUVBQvFQqE4*R`CTf^oWwr;*4gU|e|OtmKix(%ms*4X5?HSYoc8~e?? zPrY307-5aAw>)kK8qS_0PTU6+T61Y~bqsulP@2X6MZC5!WfEf@fJ?b_;jq zEp$Gl3Lcy#HQuW4;Ec^+h?$O~&EPvO!jB{i%7gFZ8TcHt7uR&FkZ;50X{4{@SE(c4 zhF@LvFVuBBp4|4*v$P&|899k=!TcYo9}BTYzW))uNhlxXakI5C!69G&<|FjJ(COi@ zDhKZ(tNXx?fqW0@IA&y8D9e&`tr4k8^i(*HQW`AzK0^7tKRp5{x>BTw`w<`R9jZ(n2NKvx!y zud|jqD%*@#kaODK?}cw$C_Z9y7SlEPx8T$Efe*o_t;D~n{3hC$-zyXQEg=uPwti$h z|7QK8_iqnADLI#O5bRG25_WXTZz{+hbP>nKi8l?={W-QXp{U| zzOU>&SoCg;xF6o1H=^EQ_}IGca(s8@91{79<;$6C5xuO-^;CU-`n9HZN=}BIzK_rJ zhhu%LWQV-dF|?1jM)n7XF|=#%19T1`$E{oZeL1XWY^Bc`*g^~}KA`gteJvj&93dKI z3#X#rl87^Qg33mR)rdUIIEZ7&pS9p`*U&HTI{alCn8rFKELgPME8((YR$Pn|j z+P5QGJD`1OnzsHtk&kHJw}TJpC8oJ4@I-OrY2~po1#+;xxX|++@V7l3ehg7!opFG) z*$dybcKBG!F<)ccR&5c7>s&9omW%Du^&99#-s#;aG4pV@na+g%ya8MO4>_cBiWsQ74N}S$31h!^TJESBc59c*yoX^@8z;DnG%e{7!h3@_2|JA9|s90ORW! zJVtfaRb#uZs7HP}g4Q}?N1a=d&DL297)7V*$lAsg_#>Y-en;q69es+lc0##f(sds* z&p^LaHb%edOVO|FSsUPMPPg9W=6-c&hKF;8+I+(6lHml-b!?%|{(Q~Nso$y-&l}uj zPHzi7w)g&MH+1Fi08qc6F)?%LTcwBi5$Q`&eW2H!dPWCKAH1#y|8*9+Dm_r$FYe6y z9~@lztsVZ#CnOHu$UXQG@$wX>>+D}M7|urli#aQ^$8%(lyxZ7c`IM875^ZYN_BVs; za@w|XO>jaCll4oUrjhOPWx$+=EeMyz0T;!IvN8EfwMjoM-(dbyxG>jY`IO7~OX{Tl z5HRScz+r2`l!e2SMW@DHTsjuWB+|b1N^u^FnB)dVBkxGe`xeY z!I$P@`Fru7TcXCE57w-72byFztaW!_MtAYfKC)rSlJ~XXAKyhe()VF|^c{wSl_PEs z<*J!-U#Fb)!2#YJ`f0Cs!=apbKf4c`>*`edRsTJKCW|9N-Gcl5Ahq9({Rdn;|5kjD@FX?SA9|CE^rgy8~yO){g3rM+ROMLeGhh(>wkzbeP874 zt5yHQSW-H6>SX;7uub=nllEt-j`qBS810Sdvh=0PpLZJ*qjou;20zn&VK(LEQ-<+7 z@xA{0-Tuk=R^M1Fb5F)=_RjpCo-uq<{AYRSfONVMe>SbB;Ae!p+Ad3XntaJR>5XJA z{X*Vl`83^a^nsO}r7n(`eE5wp#Up*RBm24o`;x5QNnQJ%xZe;H><{xTjYq-PVEegD z=~95LyOgYMZE;1hWCMQ3_Uk?TH;YHpKlsIUS(uE?3?}pBqG_l1ZJG-`&eu!Ny;9~O z>cg*9KjNF}b!dKF^ip2GL9g%K#KgLHd^tKE=HX3N(tVYs&N=$#>velrjE_geheF^X zFb~l;Vjy^6V_A*0RZp_Cr=Pp%Le}SV-1Jqvmt66K_FZ!1H$D2i@2+~7`eu5kr}R#9|r|aAG ztSeoI{_73~(;a-R^lOi73S1wQ4f51nSFE{7(l!^Ur(zK5Tl`?}jy~ZT*BoE0jOzQ? zVyl~Ah5VHxZHE)Xiw4?uWmk^;8hx=ed9~E$$HrvhwfTGW0p4{U zB!5nx%@6Q=!;sUvE&u4An`l?x&-BmGm&K(cD<#D<#U*3z1$+t^PF^9N^fsNHXJA}# z-9~hEqw9;;I($}rLiotVw(oKE)2I^@JrH(A3CpX;B8N=(U~ERUN6 zZo7wTXYuhpf-QN5c?hiq`SvVE8759p40H}W9Iws8CTUZ0FuK6?^Ao_aySK7)Ch$;m zD82aDn|{SUYU+2(o*b>j0l`=0`-_Z>J5g{qPMG8N3j`et>kP6-^F7E+I--3F;ym1nH2cFV2eZpP1|;c~^@z}EOV@H;A`_h8_AXj{65 zFP$d68mBDnjQlvPHK8ASq<56P1>T1H%TgQVcPvY?(WGIc;-TWdsj>^~dQ919=@@%{ z9$(<>+3`HxkB0xXxZK-hy*+1Ro%7+p@`f#rcV%TOFK|!ROLosin0FaPZo=De(Yy=e z278yDFz!r{m7bU5XQT(`a(A}YDdqob%Hz2dUl4wq{V2Z4{xpYj1Zly4EzdH)Wv{%Y z%443Uj(ypD4s#(s?fgos`5eaj(wi~!Il2=lqc?$<(cRjcN8F0O>3nr|K4+M`&~}0K zF@00Ht}Ekp?}wg%r^a;3A2W}maaHIe@EbLB4tjTg1sw`~YvRj9;vsS3S|1m6lq{yd zGCF+hUXhP9>1>fbC2`@Xik?xap@%_d{}4SCj*Yp7FQvbMVE8Qu&*eEC+&zuo1y`PA z%{~vE6&V?NkT{S$jrpvt;^8*ti_JFLw-?p-@!fpmQD(D>_nwOQ?O^Tw4}FB}=ncMX zpZ87Hmdz=+-&S9{1iM%JnR$ltJnqQ=2k!14On`5`Gk3Ahk=G$#;0Lz80QGz zV~_=UHx0e{Y4CwrIhI~ya$M`>`0YEK95)5o0E7CSvF0A+7jIuV^4G49zA}1hg>Y6s zy1N7T{3c67HmlRL(Nz}iH+s4#S0$aS_I_S^ALzPqe7fX+!=3^5e>d7XElpcnHMMnv zZ;NtO(xG3}T}5eIH;ms_;M-Twhp?Z*^lxk0)?ji#LxlyUNYGHZ)l#^=Qa;3r!=L;ZEIJ$Um%Y_Wzd*3jiL zuzoa-O?EHGCa+ELA8h^&1hdI&JuQ^0lIBj2u{L?___VaL$p!FnZ*1}>w@+@9JK#~X zoVtMD>_4six_Owy1N*et#9@)OHpc9+Nr|na;llt&WQ~3DuG;M8}55Ls6MY$?z zWMXaQeE6l~w-tQ&@6%?^hhLJm<@Ua0qMU> z@Zk@Ab#mXZ4clw>4Rhd0?ze50raWoLdZXvVM)*KFS=vI@8^`BEJGz+4dVLC?eLZQq zA?x+NEy`6%CyQFhdj0rq1zCTaHgmGRFl~!*XPUNlP1YCsb}3gS&A8BXEGO#=CusL2 zl=ZOUmI-A2-o23ZYg@?rv)(5t#?xFtu8q2j|A_Hy?dC1CVY)(`H@5|>PXKGr`g>c> zc@hhz>sKc;e$)6OjBOJ6Qi}-q7^-w6L>*w7nkMQuKKnc=a^UYNKaxvPacOg47VLX1 z_IG;PHO`dW8{_H##0V;DOxLQ8zEclFd zCB|f?*T_QiD%~5Rx#7F!UXbH~_T8_4Yu={ovUnYLfLgt^)UolYY)1Z=HOhPWra7li zz+1JknWy$)Xl(U<+UsKMlu*XjHmIj{FWIrRf2o%Th6ZU$bIF_bEC#xP7(X@%WX%Px>A9!Tf{IPds0jjj^9QeLvd3qZtS3V8B5% z90m-%-;L~O3wsYR^7fvkqZ1fWT;9EiI_QTxf2n;E@?p%KXUpo$d&qC24*q}DU#D$3 zpC0U8wvnwX`>?zhxj#PG+c5Lr>>aTAW%*LA&x+PyZ{xKu`ws2fv#DOzPQyMcTf>v? z;QygzU4*U%KkfqsH%!`u&b(qu8JE z^FXItW%0JjF10^#XhGXZa%WVD%jMm&Md|4i&_2}L0gY|^R&<-psz3c7 zC`a3rn_UI}WYLO|&nZ>}mt?MMvxuKFyr?7Dq8GdO{JpEE^1mhB^<4b)-L%s-le-zn z6JH(xj`}C*k=9k3VLX|ELHkd~>F=5qx54lH9#i_M?4IJaj;7u6cTu6d`%uyAV`jk$ z-)Hi@jql>MaJqtW0|y~*c&qn!d0(#bdbj-&JiDFW%lO@~zN)4=z&Toa&vQ0)LOAPRw`~?0%F@w>!!Nv-^;^>%)$s>AwI#yT}()#I-2X0#@6|n zuVej>Z=3!3gI9U}7SN%9)3;4lE#TJ2!u_6y+px#bcZ}t$&O53N@v|=3WciFQ%<}mx z&*#&`=MB-*b_aEq){^H>=?!D}^F@!-n*{^7Ckn>%6TqmCg;Dh|=p;-o(dliKwhn9u zoc9Ux-9_Fs@@OOWdF{wtG{%%Seo{t$OzZc@023P5)wEvFl9r>#(6Z6vaZri}zbB2{ zWaol$ExJ7+%xL)-n1AA7j+I&7hKvU6rj0R<_21B<{fkP!I@>PqsSeh>T*_nHJ#|dG zt;cg&JqTy|WGjo&%hXrU=0_bo;*|hr$oxNc|5Q}e?-!MKUqTtTR=Ly1MUF-*GtZUz zFl8F=tgHI^v^i3UqI+bw(aD#ss>j6Kj3bC4pX#P=H+u-Q#%u4i=im8VoM^D9exlG* zk&SJ~#?*&3@EjYPm8BE(dH*7x%k$6l^#1a<@Y>`J%~z3b_^@DWjl2CM8}YA(Pf3It z?KzlkZX+9S1zHnm70(27DliAI(WHFE?$SGMex`W*JKsmi|2H?*zoAWim+V7y zc2PcA8V?rKzb%Ug;Q_x@w25`Rs8V3hTi5NZ%gOipyxwyP$9Vp%x>vfZ_{{UHdO~@X z^@o1nk>OZ8w(@PtsXy311N)&V11i2%|$+u{yx$D-Y#y;$4=@8 z;e%wh*7xPt2>!$HxzLD@wxUzfl=ALZO3!YHM%qXthgGbVj(mnZ!?Ap<&Jc~%Jw3y~ ztI0lQ%l?oRWn=Dcxd8Z9K5^wAXfA)d_HQ-Hzc-Yxx$<}W@`|kuPW@OHr_uJ)$iZ~g zx1~0j6Eym&`@w(SXW(CCGw%p+qvH&3^(T_UTIQGZ{V~aOOEi)^+)=qo>8+%<0*`aA zZL%4q@tN%!H%X3W~{q*$nS=>m^FT-`tRg?blA(1(Lr~I z6805jS618p{cVy3>A!J!Wcr1?zx~{oD95-(YcP#*lPhC%!~cX>(C)$kZ!4eiVd$#o z{Rx$$;2k_$wGf^u)@VC5Qrxy9Dx7G#r~T{m!ACMH%FeT8ij6V{`!apdW8-tmaemY0 zoi>R^aE+u-!W$Y-ki99MqMZ2CtvgQ1U#x(V(ogOO9Ml@7_`m=q<=?~D97xR8{*{mOtgbAMB)61pFHOPi zxopYPZ+SbYVH*?H$?&-5>#QB8&J5vsi{~@={P8&Wq;kP;v}&8V_DZrfu4t}fy<%z7 zJH;pX%H9q06Y5*FhOK!?%fnx&pVeGtk-To5NmE&T2Yi^GAP?<*K=)>GPRo4wCs^-T zHHvP%t!>?FwDxfc{W|fee8&lr5$_vsZS?ut&ng{=(Qnhs5Cd>;R2#P0eR|(>@#*n% zEonlp1@Ax)_h#TGn|;4sI!gH~t4YkG_14GQYqM_N>3h`;Sb2j7`Ws)}nLhZYT9@jw3EK z`mkq^jr95hlF?P@^(7sZLzTXo^wmyY=GT=Dex0=Wb)M$ed75A6ne*%L>=W?H==Og7 zyYNtUkoD^y^LgdeHjb}+pFES7{5o)o;AA!hP3VD}Yx8}W<}7E!!>nKT{aKhJ!XLW6 zestx&jkyx;b*R2cchKl;Xv}>y@yPXE@yO>F#3MH>im~U8O0>9qf}Zi=?%8&Pd$zyc zJv)wZ&nd_2Ijyo!V;g(dXW?gyi6Tqve{(-zO5 z9C=Yx>k+>=2b+5@hj(~z>2IBWMbQ^lA>(tuC7-Ffe8U&f-;{Tkq`TyGkf$eSGwj)h z{+oPiy}5W#W9I7W+j##@{9bomaf#X1t|-#HmEBWiW4=-O zlsn_fm%o^S!#nLUKFF7SR%KW2TVeid#GZ=VFPUchCF>pK&g5Ly@DAX4KEA-yF|d+3 zrj>D})KT14?1;9NI{J9V+Y<6M?xcSm5gnTZn>yl$bg0OFzGpp7%3FsGso&99$<{P@ zYOY1^jq!%&efIV9K0aQgU(C+?l=g-1=w}pUrr#4|J|`#ZgTP-pELrnS@_Ia7yK}NG zhj(zB*-Ex*gKt5$KastXXR;M+$(H9tvb{z;p^V8EJYJ}5FH?Q&@%G{knNxO zwuJL5;PqJEhS=v87l&hyb{E72*yV+s(O4giT)#0I`TQl($PJgG7jw%eRJ+P23@j+0 zuys-SgzJ`;Pq=DW- z4IR91+!#?~UdbWQS8RH(EB?}V@L1o9KL0J~)Eci-Dj#fSk(agduFK&yb{(VJ{7ys+ z*Z!Sx))`uU8=eZ^rrLh}!I;=MTR%Jgtx3++o2CnjDpXaeRIpi}sFnvn!vE=O#4$6BTe%O1m zLOgc+ok8XTAE{S#rXkF+c`#y!E8Um`Q^B1{&GhIEoVZ@Tu;k>jutB` zTDs>khH6cZm5G5J=sDHV<8Y@P@OwH(4|#V_LeDT`=t=2GGW4A4>0vK^QGA1*1ryP8 z%p~*xyCpreGlm}WKKWA6^Zg7x=XiR`4SIe~8{^7n%_Q^yyCpreGlm}W)SpkJZ+j)5 znSFyn_u4<|=}8*&e03svJ}?PAz-~zo?Tn#^yu)80J=ya=1$>R}q8^>=e23usn0M6` z*aLnk-u3~9Zc--U^yC#u+YUHu|3btj7KP45w7kUH>; zZwpVt-x9<7etf#_GU3b^?XQzR&X&=hoPg7x1l#rXiDzepvN7u;AuZUncZP6Kp5Z>X zHSS@Jcl5w$urovJ!v~fJhnwp}?VI~9Dm^DZ+Y7A$uaiXMfu2U-OxC7+q{;*1+{^KA zla-GsuRRa%hqn}@&X^DR+C5644D0?qX?hy-U(9`lHGwprd9jeT_#sor-l->CYwc%$H80ry9tQ@9@h?g4Mg?~2NYGu^@(hn00Q)!b0x*FTBJ%{L80gXZrN=D&KekNVUt zho~Q4AQ_Vfolg%VC$*vZLe&!w$WLv2PRQrC%miQcBBhyI3+2xT&tJ4h_B&>(e=hGE z+oE&r_k=yn_cWDxC-0@U=oB~R4|DMOIljJI;JP8E89Sx~$q96TM~_IGRC zqq+YoaiG4<1BRYKw}P(7XNdky&>vv$MBlof(>T!0g+=Ar70WAYjyoDT7}%;O-m7j| zzSY0C^9?w}A}dCyv#T3i3)Hdi*jKJR?`e5pTY1`2`G)?cYh1e`Pj|$;kkOr)$4tOM z>zCN!D#gV+&=oy{PG)1xBP2`3$Hqf=r}P~BWHiUccCuOJF_sSahWF2jk4@#x#+AqY zB`RMBmzwFPmy`eIaHbsl*~Tr$HSXKMQ#M z>0!x&Xph~QzC0R~p4)i>>9F+tOKvY&H1i`?PI{8+b|_QxcM^{CZC{N~LfJ>6b(b+d zsV*w+iLQM2VcpY8hv{344r^b6+Kg(^8Bz4k!wQS}wg`MfUDlAc!N2q!Sl^%@PTz0i zz7m}y^LQBk)Y-Q=k9y|>oV=aB5PX5JU&C^qrB zsCidppW@Ym&mY&FObd#8m|NMi7?}ya)=afd93v}y{2s|GE|w0HTo3#^{L;Q&e$q|J zdk(zf8Alf#CjS&KrcIt}(YaW6`9Ry_(~El=XYKR84m(5_fFYY%T%_No-2-VCImETn zVYU6Dw;xd`9VXeb4zs81-yfI0@m}=r=kjhg11Hg318uj{_lq}Ke2Y^YzF&|}p^RuK`MfFQS-Umn8Te-N zp|txt+Vy&1D@=hk^M%J`33nYmH$BO?mk`AfQLS%uu9@%c&C4^izmG< z#!Y(BFVe_%T_3t^Z3g-KGP>*7d?{xt!d%i?Un?-Ng3sGuJhS{R%P;zT*`%X) zi_v=ybxHwFZ+Q^^OaC8nk1aYQU1r~TO*+8ya>{DIZN%KC?r76IbOF847%Y}Aqi)3A zoK{!36XQm+`PZ{_@R2c3(_5`q>-&a%R@+$R|HFDk&dkRJ{1dcyvxmg+0#ETdhi?;a zG{4_$gTeOX&w|e6Y!6?Qz(e~cUn4&;Ol$%DqWsN(oY`vX2zrv zCCK4-t{ZJ_n(o>X9BZGl@)0TRN3h>Ww!?FVeC$H(1>4aX7t1fWds&VIu5c==47fn! zny%MlXVld_E3MkJF+>KJK=+cS@_jlRgKjZ*kb|?+=i7KQ183*{uDtdCnf$(&x%|#1 zIGcRF_CBY2l$dXJaSSjHy$RpU6JKCw3C%tN@6m&u&tL=Dw!93pd1fETy>VA!et%`e z*r&+4co=Vm@nr{i)u%fDt^0|UmVOuDwdH#|l)k6$W!6%4CmLlN_qso63yo!hgw8ns54f4&--blyp zp?;`ieG%V8hw9CtUQID1I7oMqIl9QbB7y_o)Q0p*>F{0kTJbZi*~q^B{l*4Qv*!}$ z%m1j~pv(uLCGb64#>25P?;WR1Rr4jpJi>1+_zCAf1m~jsRjs3PG4B?aQsxF|6hDSV z2krI+AE=m#e*e@^uijA^$kh9^uea0J>(V$tb;!M?hEB^LX+3$?0OlF}x;~=|lF}yQw{6ePwQuON;+4|?jIrwM7 zSKA{N>OYzPzBP_MskxX`Hz*f--Dt?HF$U85^8j`oV>0Zj1T#7hW~yN_5Rq?C0uR4U(@gDt))%b zM~~W|-q+n)zU^IKif_0x(}v`R-B|h8Q2s4~-J(A=-GpYwuBI1>`~&Z?_Qa4DUre{5 z;l@mR2hiRPP3;BzOb((;_OJter=L&lqlxbEbu-Kz^~gRPhZB*<=gq4 zE%@FneT!8NT}Gc~Nq>>=645eK{eonB9P<@?tHJ}tP}w^Xv+`Bj5%fyF-`wW*CXhBh zl+dvPyw!R@#IsxTHmA9LbI~;7J$SA;Qe#-#4)*J=U1P%MIGK&XazRLk#8dHkccO1L z-r<{ge;NI1&YwP;_opAB-mL$mjQrOD6Z_K()CO=baQj%ypPqxiJU`QhbWFM_oQP#C zo(sQe5c|8n83#LGDZlr)n;UX`%hN=k?cxRKP<&we0Z+d|dR0@Kn;2KC%{No$-$uNh zW4Bp+R(gE0Ha?yYKQ`0eGH5)ysl7m>#WdjbVrjH-g_qT#nKn0(K6soqoBNIObD4gl zNxr_{7^5#?PI1rr+tR(-(t+wC;u@W?WiE{0TvcB&QkM@qpS*MFN1)aE5&ZqondGhZ zeaM;KUyvssV0}oYPq03OGRR|{WM%RW{*AM{%1>mQi-63-fN!qrFMlZ{7Y|a;~RGG=r1*81j0x=FXTWTc;Y@ z%d`PKJ;LoB;FzQJ%yOfT^Ye|AO>G8eHGcVQpX~g2!&foCAwJ0lh{b0ozMZt6g&*l<>KABj-D!T@avmR_N zk*54~@Q{qwmC+@^?4~c49>wyDti2@AApEV5hK96{Mvq(SEj~S2?RYR8d~eX(^L@YE zq?-lVi{SZsHRdv8JBs16`~r{Wez_q}&sTVp@0SC=P2PJ^pK`@)zn;H{7B!_ydP<%r#tl( z-Uc!<32;x!ww?KYbgQa;4Cc>T!YX4A)ENZsx|=j_MjHX{m@%|)(RhtMxkEN0|EzJD;xy92 ztuFggKK@p*;H!V_=6$NN2l7K7ALjVbNt@RjZg+8Go#!w#pmQUdYi!KnHR8`t05jWW zh~etat6-(o=JQJOiE+@j!8>Xs*fk z3zlSqzp$8~0p5g4dms1m- zS5im)zT#Z9bs#<{OW%Y#Ec}BFH0iU^-$I9#AM|1Yyp&!?eh(4;!Sr13!{oC@U~;!I zULI)~-mMH}rIWI+*zDEjf!*FvV8p`DzNL0*_Gl7EE*XUNA+tqv!RAY{Yc%lK>@qWFWOk{1Z5Y%ZBwXo8~Flfv)f_UAOPxA~_09FZ=qcYKuJkj@{~a zfvpZOEl++y?F)8jOHZG_C}%t2jDCg(-ezroL*N53rSTy<*F`*OJn`|S(JS1PFWDih z2Y#869r-F#l;4qjn{0akdaJ+}ZU0D2?QAaK=j3@bb+UWIjPKOz3*&aujrnF*=hfrX z>7Jm@yrw!O(FJUq)6ccxeMlF-ajiO;{v{HfT}~&$UQB$EyH7@I1JK#f*R;>rvj?7K z;gkf2vTFmrq`}4QLE_oG2dM?jk;j{07Cg*N0VXtkhBD?Wfp6=-Is6UbaIaLy_cAgGkwzcf{V`wwa@M@?Av&U z9-(Wth9ODh_g40sUurz% z1LYqweYwt}@7H8^p`U+;cujeW^Da85Q?j)6cZP&Rq-`>!6h`|CJ-mlHV39+az7vNm&;b^@Fyv)u-mvFST1L0)- zRV3S--Hn~AA3E6Euxu!c*Cig_!Gf3VBS`1w8hMY^r%_*X9GaU`n^s0^SUz8ErF}JN zwWV`KD%-H##%~|#cZr5Zxi?|7eVg%9eYKZoqZttZsVj_^5bmF$4dYQnH441Og~|at23y54r^s6?d4TJr>w;Z(j|D{b#hSq z98~6E!J>}kmskU!pG#zaXA_rRG`myZY|N|o=;cSIW#Q=nd7FT-TQHle{)!U~m>5zVA%W-#G zD0gwD+|E#HG*;#}LRaY=lw>7* z1gB0rXN$hM#3S^ZyF^E3EEDYKt(h{Z&7kW==+PMIM7~#-jbk(T1G5QqS+Xu8Yh++| zl$sBwo~^+GZ$7cmq;TMIv^Y9a_LXGnBE!wYqs-Z1FBS`AzU?*KC~ggRYGQB|(+uheE#$lnw3t19hEj^xMa&^Nt)`f+P#!!LMW-Asq-N^bDic%b*0;Bc#J zKlbgnW!nFN+H9hKgX||mKl8_HWTPGr>>>E4MxP{mv;IXk{w(JYwa!f5-$@?IJGGH_ z`2czN!LE1HH_9J!E?4xCicG%>#i2~ zZtHL0qPDri&(R0$D!lE!e8or{bnOV&zsFu*TJp8L&lp*}CBxU%!ol-S_{YE;kAL%i z2mTFfENC=1eSL$cy*1yaj?1^M4DNy_yPKcoBYOjPK0Lan*g`jw8}YI1H&@K#_J@zv zk%#3&gDoQWr3dW2j_eeTz^>Bv#}nX8jr&a};HiF}?xV_UC+}Kh{PsDkuvR}_1$zpB{tzu5coz&MI4@9r5%-96KiW;7#dBp+(YmL=OdePCG_ zEcrq*28?Zpi2+%b#+E==bbt)Rm;f6m5MnPmNHD|%k^muzmxKgzL5|%eH=ASw;man5 z#XznNBy2FmgzxuzRXsC0Y)E$ZKL$Mg>eZ`PuU@@6`qi6~U;n4_TV8pVb0yZ6O>Cpq zovd@X^IX<1#GGL6`$vu)>}_8;NL??(ytWKB@gv?z2b=s+%kDc)6<_sk%)w`3u72o_ zF6@tMt1EkiMh0x_fw2|uzV@S?09%@0%6ZEkh&jO6~ zuCD$T}iEKBNN~eaHEi_sIQ*wP+uwAY%yN#>t&0=rFy&E#E#2mB@|M1={KL0zh4g!`jhCFE#_5v@#u1HtN zeyGy(@k-2L+tmEZF(+p)cxS@>%L_KrzUomP`$WEXbZYzHx%V9?Lp=I1dJXtTh)w_-(PGv?6+l6H~CI)yQ~;11B1w5eruzL~wLk9j6Yp!o`^24iueb~P`2_d*c&9NB#pOQG6WzI8;jYHr z+d@p8jV2#0h)hmeEe#nIHNbuo^JVsvdf&91=wl4cj`f5mrJ-fs{2cSZULVKzC(;6k_`(BM`1t$` zJbrIF>f_n3py&JkYghgt9Y+EkKhrfj0woHGB?WyoU>(=h_>MV*)cy19zixETqq}_4_sExI5rW z_&ECg&NA2%+6UeG{>~pS<9t`P_aVgLbM1Pl;7L+DBVr`|wP)4>0Bf!TE9qP_K+{ z(zC62V(t(bzQOU0bQJb4@BV;gtl%l_B`x(bslC0@7S17RJ~KIQkaoNBN&FMn8Kld+ zz;Zs*>q2@B;l51jggsLqdwDk|Y?QF4Vah2w<5<9b;>Rr}P=A@vZzceq0P=OQ@4080!*ef_4cmLnlw64$Ox) z_%wdo6}=(!Y`c`pXuG6!+l3ZwS7j#BQeNWO_6hkJZ71GuyU?I*>UjcQI-hMn0{Q(p z396VuSe+^v3Rfr>iA8x7cu-NZ`a?#1MQwxHyJ!K|5k0O`)<&EgnJ0?WdT!f zvIjp^#}5EUd3m1W*MqrCY*PI9%!l1EpZebbz3?4}W0v!>imAt(!*K)rp;I*s{&@G5 z`JLr>=b0KKzF$?JLtt!(T$r0a$9V|#Nq=xIqP&=+Ui0S#(0rL|zpSN`V%NZDLfh#d zMVoUuU;AyuT9ay{$PS+d+97Q~p0q*hN!kn?Wp@$BG-Z5q{l=X5biVP>e}-WfdR{az zmmFbzn1`PZ!w&M*nn^zXJdqkN8Gq}P^Ozqu>Bm{p=KOKXb(HB$Tjkn8xuz|bUc==c zH?i%Eap++!q&ygpZ}@lQLjHJ#jKU{lE}WLnwZ^|8b`>#r#%}O0II_~%{raiKZvOU> zn zpp4+K?~`}=zqS0S;0c>O0=b?7jDFh9J__P|ob{#p$Zw0K?vaH2GC$nG`2lxD9)W*} z?=5AjZIY*bH=FnyTDBK?{(fo`*K6K$8D`!L-0g^bwCM)w;wkXMJ42XvVIINWLF5DN zQ-E17<+~KN=+`TBC^N0B)KR9aXp_i_JrnAqToYuSF^#N6T2^-&S-JOmiv2=)S=R~V zJ(Ke4x`pmUy2akhmr3Sj?3*a>|Awq$AK)jlvYwO4s_Q*MI>6KF_5`v@%<3e)&YniE zB^q}G^9OCg*Dud%o|5@U?BSuOP(Ruq7FjZ6rk>2J0x`COHc>+zpFnQ^PDTG7#jef) zEWd`))Uasr5lgP*WvI~eaq+u+FPhQVE1hC92G#P<#E;=|a*jLpg6 z-p)SZ)7gzT0OD5<_K&R|92R0tmmF4v?E|C9;hkWF5>mdsb7j175Gs!Rzeq?j6|WZC<;ny>&xJ``KI8Zd%v6dM&1T z^{MYpUPfqiboY6iR~bg{K<}uxv$MA^*2>uayDlv+7oO)KJ=z26p=4L@&fa8qX1Q&wt-f;PqFky>J}LS%_X$)RRTXGt za#$F5cK1WZ5wv}DaM&A44)^ztjIhnnc<+EW)HyP8`QUIjVoBta?CKfxsv4`jtGto1 z?m@`fKiKUpTei&8vUo}qoic=I1lsUw*QH1*yQ!bCksaRPP;x-j(_OC0W$3HMZ)ygS zkD}I^D@SU)9i3y{&6V9L1!VFa8SCmwj*JLrt!-iD<4?xy4f=m|>)8`KU+Z<(Sm$sj zbgMe83f8`3Y@}moI9WH+Q|0Z18F)RNBi@cAnmyWiDZXJ^gVGUI^*w|A$@-D*uFm1^ z`klSQ{g-zRC#$^f-r-~y`et{H*SpgLM{hW}3mu03BddYIQN^xnaA0Teu4K0|MbSID zW@vbD2P~>{K=jn?Twd%ahXnn@i5%MH^N`A_gHNnVW*QH5JU^{vTx>;g4**|z0CPjaArmSylV5o0w z7wkoiJIrfR!4x`WR%64Oa0}+5^=G$x=$QT?%tkxLcJ72F_KtX6!%6gXw{DO>Aytkv zd#yvmXN<2O=#{y3lW)9I2ED5W{uH{^$lB4_b?Hgysh|$XH#$7n2fG~OtlFhHlHaDW zfzjUn)%!` zT_MYD=^VLqHFdnEbF}lkp>CMbqK39B-cYY^u3Wk<8aTRfc(mLwum$ii$799C?1c2H zLCm_|*<<}XlEckjWw)o-qb-A&fxIm+Bf*X&yHrl)h^Ri#iNT+Wk-;b|c-eNy)6L_a@Ey^%>JXgu`c1T|*K zfpjO3qaVAT;lE!B!w?4GKc)T@XVwn=wr=#4u08A_MtiVWd!E6vN7NkFamhe$hrgzZ@ELST z?gu%ka4wpLGII`MSxh#Q?Lt^$>D=6TSyIh6n0N$yy3i8Cz@Dp1-AbS)E?Lb^4S#ZpQIRr58;| zFP%icWKw!@-BLxr>8y=XL1SHmkW_Zp$^U-8u^+IPNRD@mH&@mz+F9du4(uB1>m2U5 zLehHsDE&n`Wb7Oq#!jfaqrcNHr2A9nvuCCdupXZ?3o7oROupkCon2j82+eA|W5+Od zWf>VhkBQQ;-@N1i_wgM&`#N`VZcr^$n>g&cF2Sa)e(l=JUYZg`#Xm^dO8QX`;v8C#t`W%orM)Har6fAA%R+Y9xISLclm@Af)(b@mR_DSJq3b`v#=!p+#SPBOO6a-d#0xYpJ)=F ziE~BPP5yt8@aG14l;$wCm=Msm zx*+1V%5l&CpBdhc{*g(g6n%Gc$JnlIm1AJ2{^@#p`^P5HqejR**ge?4t#YR~<^PN3 z(-7HwSsy7#dCh9AI_}UqHnYiInxZ?2JyLUJAE&@Hc51mTy9?-IGNlT<*_MEDJHYoZ(RQd3?3N$i6s!TI4PfY%-(10hTCR( z5rjcHZ>s)TzO}3Cq~$m79@*lv*Ig=nQ^?xdskT5u&zpdkz83rhbY@qcAlL7xlV)Q% zMwL@pr?otlK&wwOCKlC-Q8{Yf#`{5s|K>miFwHr>TW!Y;uEPEY`&ztB;6-!*Yd!}y zJbIp=nfU}Ce;>bVT+@qor`b=Z2)J7}PEucT0J_ht#fOEnpWsu=saMXE%eiYD6AgSf z10#672d63f{Rsq0Mpk&@`u-YIbrd;m;ixx~cLBIxW`}`L+6e3aDG@MYJ|e zdv&%?Kee4FZ(pYS!9yMLUf~Ul_3Mp3UNL%ictel@J`A;&hl5r8m)IfTy>FU)u}3Yh z%HOqncyOc(PR@+7tj#Z<&iBi5v)F;xGAu;tc|i??z7AR2m^GXR;hjt;M#qK+(kWRt zPRwsZ$60*)?9fv~x3_5$;tk3}_-zdrQ5-^zDQFQPHEOZ`oVb2$F?4xCsyv|y3xl zAFszcSxJ_UA5HcTX{4NO`0qKg7ly;XbF^7?$2fL(cy*BXCoK7boipwa2j5@BUEGAM zJ~5<@VR=l+h5xu8FSr?H`~xoE|10julX!pGj!Q-c2V}>Nx6{!c`n`NFgwo5@{K^qA z8hmvwRM12|EFp&|sUxAJ_N1JQPS2yla3Y;{*^;ds&ftBZXYg{IeBs=0y8164?!}rk znjD8$Z_vvqCjFdlkNAT#v!~>9=41`n#?)0doYLnzg#3}Ho)}fwOTbS#1~+xGd}1b3 zsebkqr{1CrbJ^R27&wuWNa4$Ufo_)_Aybne;q8%)?quAb~ep!d`OtF@Z zO*!2+t0gFvYdrJi8=m>f7oWTJz|sBp`B=7N1kNoSOwpUJ&_v?nyUtX~FgP;5_V9Bb zxElwzJYs~Ry=Oo6iRTX9@Z7Br9{utMp8M!^M{m9T`NP*D&*xujm#3?#b+Oqyf#dYDWKVAw&KK}*iI@8k zd3}QivvU{`2>jG}@-WUwt-z@|U|ZakV>_e01n|~m9Q49Xg_kMcZJ^nlfKPfyptqqX zpi|xm(x~?9SqACp+pqKg?$+bHT<=-_-d0anKC`vc<)>STcJll{JOR2NlA|Nu<9GHQu77OPkfPzK7GeVVZ+-_ZYe&LyVY{3LF*b+Ud0rS5tFC-HG}0O+UnPnZm)X zBtoYutkKq2j#hwPd9dIZ%qWBznrhHZCr7PfZwh}cx4+LU&tN0Fu@oOxhR=ldr832P zrd!x}(iWab-c(0TkoIKy&{j1?VkKwV*QC-|0|)v3BQ8w#n?f6zzB!^K-2rD^N+XIe zjh{FN_~X~#+h})`!Sz*-Mvpjb3q&s)&RKnC$64pBSxb{#y=4L+;jW&qI;xc?=BH)zzxJo0WfU_bUXd*;;xuF*V_S|kS zIgXR*i4>}}SWl*8O`804!|8)NOS#}ua`-szh0tgWJsgmwoOP#qgQ#*CetpW9nZt(3 zzDs;~N|JP1JcBr$15dg1wNZqS1fMR7boL=LrhrRUS%Z`Z=U1W!9t zL$b1N>CV*ptM|BPb&j7e9@EVrqlPqIM{zK&2Hwx!{;_`LIP|SW^h*9Hms*wHsO&_G zVri~>>M+C?#FxXzzga;t<#@xg(+HyX^u8Eumwz4uUwz+TS1+brUll1tdd63+F^qK* zI^|D{nyc2GUtHcBd^6JpaV&s|KV>}1F4IYo2fZ(62#OYKfEaIzD5GyC%kf4fwL%~Z z_jx#e*(t`L%#Ds_Z{+gc(XJjpU!4O_lRZIBoln0wh9!7p_y=mW;W{JrU7l?2JYu|N zZfFGzg>qFUomI?h_NL~Ipqr-26Yg*_d7FK1bzqkqM@R$?qP%)JuNog8_eONxvaNLL z>#IhpHYE}MGy)xu@SsTapo6g(#5FA!zXd5SUDI(vn2bcvK@yCAC4FkKt4(jRUhWI5Br5n?*upxc(c^#BR*&s$9vMt`k+x zbX}NhWY~phwb^ledyq{u_HA;+-Rw=mLxl*7Y{udJxnoJ}Qhn2(xDnSbf(b0K1!pmS zR8b%>D0f5knA!Rza$-UOwO8d{T*|Gc%S)oiQrmNmB(!guQhLoqP>(Lfsn%aerz@4( zFHV%vZ{EOQEjLE8Ip^f8QgWIq=cJg=I8TpE5JhiBgd+(2F)x!$swnoITw*6NoX9A( zK?19jGa{wzy)rho6J$znXqt65Bs;r$yb%bG*BSL1B{cLYOeiT^AJ~Imj5{INEcPU@ z6||r`IZ^1;770SD4(9@h5i^8{R|%t)A%rdGR0+s-LgoJcinCVNBmb6J^gc=HK80=0Pamv?U?R80{bMr2O;U- zvRTp7unfD5?HF6Smb)i;ub8mAnjoEC1+W0Hgx@GkMF>HXgML|AxbaZi8@}V7bK=z<8N$yi5Zdqk8b*YnH>RIPU}Y6swL!(x3t56v%X zW`E)s5VH6ScxwIE0Z}UCl_MC&LPDM_cMhjE4!#7e#^0R$J@xoyGd4wUT;YVB&E$4X zXcl605h?-o%LXM=Xy3xTZD@k87VLM~Ab$o*?L$uG3n^kRx?ucMGBdfREn_lYwF^1H zE<^aAe4mo;U&htYAH`66iP=L$(`6@!gJfihzd?TU<^1qF_8En=1rD`@jE`x)b9-@ zDTwvL0msldZfo&E5;E2zghXQHwzO_p>$M}Q5c`dG#Qf+64y&Ixr0B%)xsGw!^}|`aKIlJ-yy0 zi6r(55U(&(>9=6Sa({v-DEW-Vf4QoNiOQzV-r1WaU+Vfqra|br6nuXtYBAvGd zdqVj2Af(@^HRoU}|0Rraxn1NJuU%H(4HgPSd82bFY^D%|&+?`Pq ztqA41n{gU5A(T?Ih7hw|*lr_kWif(_M9Yj!UF08-rOHi1OgqklWYsU06cp7~jV-j0i ziC{bauc*;}4W-T<^ua;@rC4;apYZ)%BiK%jVWz|rD4fUW-&tL*&t>4A7nc6H=16ka z<(<3h;ZN!2&sN|<+?7fI?xj!5*V49;e6MdirpdZL#3 zr?VehyfN{grR=S)LE;!IwF9+MQWWlyBQG2~Zd5LjpZ92K4Wr^h+YRM9#u!eVnd6@v z?(FOvA&b%BG2ygLg}HHk#D*6eb?g~AePF+YB@Y_|{_YPxN9lG1sp9xf7K;h#8m|vU z6bdn!B$$-XaB(@k^w*Qpl)qJ)ua7-w~=1E=+41Cn0P;1GOT$JBV-oD{Vi=X9xYb@rhA9MM>lR40Qd=PhdV z7BwtV7Sni2^U~$bji(3``7*z6K7qe8_5yxkTWvmL9y0ojaq|ntM)RP#&sgKrZT-H2 zBKqm$O$}IjJo)LLO-j$NSA=<*zF((Zoqqlc3h-Yno^J~X0>53A&m->&$`ijEmXEEU z_|3C?9@Y6Xb=uF*(&@cguxy=fIY$9GI(;an0KdQAr{xRl{DgigDe!xXeF{=i;s@lg zIey~mVc>o}`4sEt)|(aJ0{d8pa#eP-nYs7u5$DxS73X%Q+W&?)6W<5Gjg%Q zAJ$L$5njhX-#_6?B>Xb&&+_sA+fV;quE*~8Jvyoe98c`PFEf#NTj%fqoP~ha>X=DJ zP2rcJ|07Wn?^1g3^s`z&8}zeDKU?&(O+Pp4=T`mPuAe>nIi#OwtX|#hRpV!aox_73 z5*}_ss9n_1hzk;$<}*=8XIbO22K<-VkPS#E$&|-t@Ap)$@9**bS1Es%wkO}elgW!P z{Zs+tSNNWuLgjxF%AY>JM#}d?B$dDa`#|6`6r}F3rf`nyyoP8LVY^SuK;{iBUqo|DpF`B9&K%@RdF?mIXq)u7sY(S1Js zBdZksGto(eI;rU6pZDqS+M?*U7o3bf@TgCpwM)_0_zurW#T5UG|J|o==u`CZleV|_ zai4z8fTDkC@&q+O{y9f|`lc~Of46!}lE%>b|K}Hd`XiSq!t3TvAr*v@|J1mt?V2Exw=pQ+$J^x~nPru<_MZeK^;7$@t$#Z9`Pk->A6#e*|NrXD7=>KJ# zPapqxMZfo?`Y-A6=|AweqCb98{jVAF>G%Iq(LWP8nLL}{>C=z?LD8>J!);0-CI55( z;L{&|SQ4binvDtUxh*NuRg)>|c0;_3Hmgc`~(AEv~DpAK5+9 zog5me@9Z4z>N#aeeHVV~Qn%Sqr;npum+z{TD8Z3F{9LS_zvmno!uedixB##Hjqz!XMZ<%;o8h(pCTP^I;G>3C5l%)LVED4KEKLZ#EOlL*X|k^s~;KY z9Kxa8=t%u8M3Q#Z?dl!fgIuiidluC#TD+$pH$dT>vuk9`IOFW|yw=Sg(7YMR-1{vw zEDN{$vw3a!cJa@+3jYFT&R6jW+E{1I%7w%PvVV<7R#rC78;yXS{Qz_rydNmD;Y{Y6 z_LqgsdX$eWYXwX;U|Y-Z$o7E38fN71tApr20kA~7>$sQ7Zo$__@J}ehhIJd@z!~qs zx6LD-V9*Ix->N#`M_kY=pds5A~m^D2xwHbwmbsRDU zzBr*7$0j#p{|B}4K8Vw=EaRu?W_%K}bR|~S$-A7hVe|p4kw#!{6TXA0vjXg_K;?R3 zRA&X|un*>42#oHxY{Eg+c>#7_py3K)bmv**(0C&;0o9KcqB^+wjOdK!zML2BDMazS$e}=LV>o&ADxaJz*J?p2K$AfE$ueQE|H7U4`aFg9XI%WjVxEVBU z76!Z#Y$JZ7^%T~LVEZi8zTJ8VY7VwH;=9LM4oeTV{|xXg*2Bdhqt=g8@MG3R zl(W4SJfAQEXPplnKA~Gp<8|zZ(a7x2;0xOO7BJZl0uKBOcxGQs!od6U0bbif@Vk&Z z`#ORl+p$R)ehy!+;h)Rhu4&{Jq3WDc^Y=*Qeiu#4nPIZCavwkwa%P$=o0}j_xuW?# zY33`MFOg<}&;;%T18W`y2(zB;XqQy6(#ZKEWQ$mfuLsInh}Kz42^!W_=r!vU!ZzB) z5`jNMW!5r+Ia%1NRa>XO4A}Y>DO)I)VO>cMtu&1+>vr_DwTgJ#a!IqAc-N{Yn>EBo ztT=kaT1z-?eUkL+ZUD=Kk=J0YD2HVEpGBuwZ65+M|3>J`Y8UKj1lP0qszK~PX;8fp zxSLg-Ny#D&*0xU|M@e{*k}yby7b^)XSbGOaY-@m$ZzmkFj*)#Q;e^#r{Enm0nrA&t zHFmLVwZ%U@Y;_Z^q0uh_8HB!o=A(p8t{^Bv?@SB5ON0(Q&eA>i;afW7MF1jynGxA< z=j~yghasq)&x#G}9JI!cC{_Ly4?9ZOwSI*V5W9eI#JUc{#*Pt=TVpI6C!Daj+S-Ne z_L|l7@t$=iDzQtbxoYd$GQg#jeXB*Iw`Y)kpAp#IfW&NyhY8{^)D`G}dYy(_ zQ8;HCz$Zd4CSYjR@wdT@|47c5!eQf~mubtk^#e#1Iz~8RT@Av}D})mkE~z&{uM+mG zn_AGk*luf^dZ(0GdZ`uE6NcbiklaL+qKbevrNM5Ltn3Z?X?>iMBDZ zKoWXQD zJ`Ku3Bl~d{*vG6H#1wrP=948;Mb!*&FRlgBC?19(nZ;KlFHn3fDhgu3;i#$kBeHWI zh1ROwx+_6%eFd!C`dSn+tS8R|+(5K#Ek*#1+eoX4STolHUPL%ywUW(ZR^?eQfU~=V zW#>X2`_YO3S-VT;Av0^m9G|e6Cdp{<(AOfG;!xA!ZciBaw46 zjKI!a%mT8Q<}Q)N6vC39V^bir&`FuZgzZWX)n#O>Mxp zSTh730NiFhiI(OyaYor_ZG|%PnyA{XM&JzSJU{dlW!nQVk{@Md){hqfT|jvZ>sgY- z2xnQpS_e4Jx@;qG3o`P&S)h09IrvVT3z}sBN=Q&b2st-W1;3$;6(kJ|v#E1819a>Q z@GYf!0F>|x$Yux=IG+N~Q&e99I#59A-1mYcXB1y8k@A=E5G6(`loD^E$||Th+xiR? zq~L@oD^fvaRa^H$p^*wUrojqAs7M7BvBXLsSHVj~aghqLZ^AwSf?ySO1J*)(N8=mOZ(oq6Mhn^0V`^@=9po}&Tx|rtw;qH=yo)1e1&s8T zg2=^?K*|(E(>7Kh^(h-Gh^B3rlTg(A)8xU9jp^>r9!yqLUQs}lwrPY{k+?*L`Ighk`nNe12r(E>kXSC@W`Y~A?W7UbEz z-9~(#8Z7~|CtgKivaGj*JYG#aMoSqclKA{M$a7vq&)-s5YXBoXR9Khpp~5<$msy~& zF5N?gb?I54urA$0g>~s3Dy&QQP+?uVhYIV`Jycki?xDiEbPp9aqsNGa-NATFgX6*+mdPXC0byxTqxtj5MXFH9Z!KTGL}u!D=iPwWh~nQ7fCP#$r(` z#ZhBX!D=iPwaQquu7ueXtzr{ftTDo?DQ26s0Nq`*<{FgUXuSiSSG1N**yFSO1;7ZtTr&h6H@YXPr+8TcWqfcP_s-)rR&-avT2)qqA9 zolW?V5$Hx=7w61Ift&;kwYoU53$Rs#&Mz+cAV9oZL5AW|(%aTr;%BhE3F{d66wiDw zXl9Duif2)8o>4Rl!ihx}7cjT@gHX6p{3O_$#nOq$&>QktL;+xStqj(#-*DQWN1|VuU1&N~O z?;tl!Ra$6-Of(K&I8b_fV*Xcw62TJ-(jA^ypc=}_SHY^o6ARKEo>-9X@Wg^za916! zVAbJ?1**f@A&G^osznr*sG&4#t^10BuO+|b97_3TM+L~>B7fLP3B^;4= z(2_hhAz@tr1||8d&J(qiM5vZ(BXBO5mPDUMcHmBYm4?m&`<&0>tGaa79#-|O)j-dV z<3-MpWvg_y(&Eivpx^}T3zS<+-5{uhe`#)7?WMVCwJTVuy)-wi_R`$6+DmiOYFDsQ zdugsx`vWkU(!4>)(_+1ZwwLCMN{zt3qIsnS6xy*@$v5Q*+yrZx;Z_24?1lK2C9)Yn z$+_TRzTD^ba;MI1iykD`la zEoQd|v$8&m**$kHDwuh23|z71A*i3E4Al&?0nH4j6@E4vZsh!w_k;(2uW6j+Ve zBYWj68dHn?4FILFuN$-0v~M!zU;QCw-i!vw9{$sQev6TPE8yHRR9{|e5})f4t`j&g z6J}LW%58lxV&$OGfnT6)b7oS8qL(11%nfrB4Kd6LT*u7fYf&Un{4rD&EdC*c%qqSE z+RH8u0iRR68Q-DVPoq&>=gNM7-o`WMKY)%@e&jr`vF-=1^42FI3cMevqVgco0oAf3 zKxtX75%>v2nHQ!gIs8*`Zq=O6u>9A-t7e{x)MPet96G_RKJq)T zOLH-22q(DlHck0EB9}Ul-w7VlAqHLvCV#V;I}s;%SQn3X!z#?vxTecHXilMSexosG z6Y1N{KciVrulHuH(qUXCD44ieXv- zRvJ8TtV1{9yGT~km-l+UF@KP?|4M4#_wTCMW9ng;2dnTag*lh7Z=N!{fDIfNRdqhC z#T}nFGSFw>S1Cj2_rQUkc_W7T8^0;Wf*R`XF_ZFb(9Bn)m@hoSKDfoK1t#%Rg;s#bL!6pFxstLJ>-JQVnz$*jPEAtTJ~=7*3Fb2N;F*Pn^}^+NubZbX~v6trbE z*2y^!qHoO&CY4KumtZKGXX)ggdH7pZhIx+kXYjz`tLHq*mTxp!67|jNM!%hFwo9sK zPCfhSa`PM{g9nc6ne$1u^-5j%?mct(Mq}Cll7~VY{%z>q|K)Tx7iSYhu3E@ulfl#4wFgUvsz(B~2Q@I#+?_(vOb zy$7#-H>kz+9=wjAWoO%DAb!oPhA#oM#jlzD;u3U2~ zK1Mj=(65>O3gLu9zh?HUggu9T&FsGru6F3x%sx)I!J%I>`!&K%4*iDSCY)g(Tje$DI^3Z`E(`!s)wzk)JqNz~F3U#q; zwZr48P&eV!aTSEV;5#U!gidmmRYLDf3%yH(mgA~W&&NO!-yhEFWY^HR!uhPoaCkfw zj!BO4xOHJQXe=9C3I&6^;>(J7X*xC!BD2JQXhFh@I*1cq&{(yyx(EDqKQM zRXaSM3YSvWtq$LH!!u-rtK+Hg?4Ke-4xHWW%ORRA2hQ$kj8AfS;Ow6MGC)`ydeU84 z4^7|?t%AMVLfCP5;Ow>%4mtGSyQ>I?9UeHlt6xLeh{FSCcTF?!p2GuYcP;VN&R6j5 zt|Q!3%mZil430zW^hw`F{6>cd&TczjOtw2baCY0-tR9C4&Tc!Kb&JCTXScl#Qa$SM zz*)hMIXrN7+w)NB39O591ecHl5_V;7)m~IkA_pWTazIid2P7re=3-E)1CrdDw}Hmy zDMoc}9hWDE2PC=m)&RxQ? zb1}~DL%tl4&ZcU@A>6lA_sP9eue5%`rh*^sAk)t`$xeEhX)n;6|At@q3=Dv zg0(a_^u6a-Q2ZqheeVih>hRDazk=+w?>)cZn@D8a+?bZm1^wdyV*CPfrDSm!MCf~W z_fuS39LSMnF|c*$K#nY@B^wSM$dP8kSt$EoC_95RzF(JK&1iN5Ft&I#qb;=%SXvov zO}8@Inr@|nRV$;d=~hNt)2)oQrdz3C)yinAw9=thGrEfUZgJ?(Hwi-9UK1L$7A^Y{G|(!0A|93bLEfcKeh9NK!EGDeB>Z(}1q}66!Ua_h6wb zsAg~2&Jn`%3A@e*Nwa`(#Ce$bg@ohI2f?SHhH%2^z#>;rOa07r=*TOmW4kqo8egR4I zNX!Cp)-ciq1>{j8{@N1p*Op}XYYU3DAvfEugn1>t2i2%DIEwoSz+#JkHHqP6Vx67lYqhf8yt^gh-7R@P*lF)> zwE4H7cB%ULAd^MV!TO9*v^_Temq3X!VhhrSA6uZ5$KkDDW%#iLX~T~#NE?1^LE7*Y ztPDT4Kp8#_Gq#XbwMZw#YADTGF^X6%;dKtZyD>44GaPz%WA&7w&7pTU*1%bMt7^o5 z`Hj%t-B=@=6`^-Gb`3La@$SY$7r@NKF5+Qj7xeDNUD}cD(7PMYB^;3nKc2@XBpiBo zYH{eHEzB3SC=YF60c|7OrX=E&iMH(L~a6*ScjeX~UcltTMvi(=&LmH@K{fEd+1 zMufiE;s*wpMdFY6S%pUAIO;0?;(LIJ&^McCpdb2k7o-LJ(lW|mfhDDnqjoZw#VNQy);&6x$Tp!uvBWF;sgreN{F-_UY;u^Wtm-bf~l*jzyH?avN zs(6cEd=Du#@@~I)6?tl;r;E?}I*UKPmEoHB+yyQ2V;(HQ=4ke-WHZAg95~Q2dn=O_ z=6ocB2OhlIa5Cm-{KW1eRuB0`PwnU790rzrj2uAF%bZDR%DC^8mqm2C^zJ88>(!nNTQeebZsrenC zqI5l2DsnbT*Ml`vTD*VVoV7C|XYGv0 zS$o|suuNe8YOi<=Q0%kZeY6b|q$|R17c5;7_WCZ!sRji*P8y_L5%!ssEU&@db`5fr zgc*^uc1Gl^-9Zu+IcskxtRiRaPQog3*52_&^nfRkvvx-0tld2!auz~gK(kRoCldrk z=$&bycZtyAim-e3fkHau2LMF=G9z!lllOK^Wis-ed{(R?XPu15StlcM*2##RbuuDn zos7s?r;w9_ikx*aB4?cvYEDJYI;E6dMb0`iNWagJ$XRDL#mkJG4K-X230355_(lF= zOd@B)8IiN$mubr?ayER7u!@`wzd|@+@m)RqDq$5l8~zJn6*(I|PFO|GhF>GBB4@*Y zCEOCHhdFGROti)6VGf&;*chjWIUJD0);K-P;ViQTHEoa6!yL{r7a`FTr-wPLBWL6E zFo$*IY@8nEaGv==upW=o!yML;vvGQu!#Z*{P7iZ9ZZ?72wefGWOu|HXzOgS(4|BNO zJOl>&7^jChtRrXR z^e~4T&9hO@w~a!2n8P}9Hhhqcl*rleZ3I>1Z1{FIS4GZ-b>wW={tMM&vjfHSD7Kg$ zvFu90UhHFIMiD*CQF@rer<%k^>0u79P%u5r;nM^zriVFnH|s2>hdFeQfb=kj?iG+8 zW>+F-?fq!q*Fl*uLZ4>=dYIiA#FV5WXLGCg5>P6Rp;B=Sm5O7ibb@2(hoDiBv$=I| zgJcppo0}0io7+INik!`Dq}8a%+1y2hRpe~$VpiozXhZz^lmFytyIZb>wVb(QjF=M9$_dW&v45^OndWioPSiuuXx&_C@%X$k}|S9F!_@ zHh&q{Jt>vnq?TSr&gN%C&gM6fL`BZ#H~kl271fyER1)Io6o*vPd4N^qYZwG1Qk!f?Pt#>7fc3Ih$WWQi+_+pG!A**j|cnDYb^B z_yuGUsTet%KTlCHcwM}AQI~%vMn%p>%Nb=MN{m)0CDMBrt)SvmdZRXAs1YuZ2*tPG^ERSZPJISW@&Gb)_3a5Y<}!Z{1qTmwEToU?E(HK4*d3)j_S zuee1v#Dy8*oP}){0k6V23)?BD3g;|b-vhh~=PW#vcooiBxPh<==PW#%@FC?yEXsL5 z+OEPmixN*z4|F0HmE?dAHmq<26_t`+g>x2VgmV_n{0qocIA_r;>diAsW?@cN!IlNg zEfx1*skjGAGu(qkMXV}pUxiL6NriJ3*0Qyw;_xe_QzuZG;qWVLbdg(<3g;|5g*qq| zhhM2U{7N$%eud4=$dxH}9DrEAAI@1kzZUJ14liDi?(pITs-blFDOh!Q@q%=R7iWZX z7H5QWDp+-R@dDN1bodo7WK}IH{pYYD4x&f+@4Dx9;po-(L#&f*3Rk*%r` zr-6+$LOcA58`-R4I{b>SVWtY_OoZ-c)7XcJuE#?%dAURje03o!I-6a_XDFM zPa~@V>d4cGl3F591y;eBrO|fKs9?;}0!pDBex)&TwpRl40|3$=_ZY==_|16WYs@0? z^L|#LQA~&5j4wU`OfemPGaD#KF&%z07t#2O>F}Gmn4K1tiK-&t!LJaO_sZfwgy1w- z&OJ{tqcCSn6lO7_FlS2?W-+5MXG;`ju>{@4IMWwPs9l`Xda-i#aekXE4!~l12%O*( z+V3{I6>qX;f^Gr$6MbY5J^{0u)_~tN`^XoFoUf3N`N&@qxlkdG_{evWXYClOcY?>X zdvW%c={9=5qCDnP{+yH#QfE%^6`%4mL_Rtu$X9*jS6R__xCA&s{%hgc2#}MgXO;@eW%2(eO2cIBOmi%#lN!Lh34H;a^~E_a&MD*Zqd2u zMO|(#Bj^w`wnpb{N#(o-*GuIb2%a0G*e`5GKk_3U2f@)P6v0moK{)SLvS~Dr9~By- zO+DauY(eR&Z8$kXE|rR?Hluu$`dA==UPp9^nW+-h50clb++@vtMq$5-9_Gh9_zc+1 z=kIS!d6z@@*8GpLeLA&q{=Hs0)wZCw8{WU;EClc30`UdDM#k_3F8mh?k!QXnnL`UN zWisE)0ynrj)mUJj3==e)J{D&BY1(x>ovwL-V!U+hKPjiW?SW53wcSm|f8eNlMrVRj zKFItH+xnl(yisRvO=s?7$;YX+7M+QP%f~!e)4ddqq)P0xYKeRz-^rhGppqly8e-E)Fx=)Ov0%#1x2}U6}8bu7h|3rS>t}5`{ zzxOG{?E5L6A0|&x|9*n(MA80!P9A{+8&$X6th%jd!Dyple){WBH~VmOkzpQIiJ|(_ zQQG{c3q`IzOgrqOnw!|n>$d7zt5daB{~M|6Nd1NXP}sYI>S-Q)1$oLo8nk^#Gac}9 zf{#vUrr_927eC8IvAQ<$^|orB-(dznZDs z*ORYYdK{4r{~PY>F;qIybNy~&Cftkg5n?9Xi|}b;)V&B39naYhAtxtGN^JNIVC&(*f#AT37)|#up#&a1YleL!kYL`JWS?dTlf{E`n-YhQHZM2^ucL z-|SNe<5vjwi>OiioC$^{{LMa{_w>6Af73o^m*H=A>qo#K%VqeR_Bp!@f3sH;@49@W z*FI;L;cwdK>@xh#UN;jg6Gjw1XNC_JD4%l`LFIE6Y=+O-p*GpEqN9}0nUcleb3O$E zDG8O&*=6{feX){|;cs>aNo<$lZ}xV=5%(A@&F&HZg_FRU)*7V$ziA({%kVetV|E$- zrhUvV!{4-z*_ADs@-e#%e{%|{m641aS3zeUV!f*re3Wsn*D`>(J>g>Mwbqqe2q0X*y zM7s=ic3-AJ+b%<$-D89!E<>H&R|qFuI-=cI341O>o!!3>u67yf>>elF;4;+NeT{IF z%TQgRE(HVSh<4|j>}chPb{9xOIilT# zl2DFlw?-1m5$)EQoLZG5+Rb!CyNzZ7^=L=5`=PLeI=ctiNSC3`?rj7Om!Zz??QE{? zKEh1xh|aV5yO%th9Vp|8V#|0UmR%{>Y9Ff|(GfbL-BV5CBXmT&D-=vew0oMs;)o94 z%{s*q9ll3EI-~%!6w^f_;voALuh%fTL}L7bAJlFc0}hF@qVnZ zIHL0xvw*C;`AcNwMc-XQjoB0^&#uC^#85^;bYF+Hvv(#INS85`k%F5*ZMck~jKm0M zxs0KV#A&Ns1r`Y(F8|sWyBKA|5=j{?KSVxU_oEeR-B-TYBPe6L^t?nX2q#=RuA>zd zAg^{ANg1tRT@5ZHDYY-wWhABc#k!27j8>3+$`|`-B=YQk!gndRq>liY!7m`IC5tnv z_Qg`%us9S8mK{f?ONU~Cawxitq%6=5#XS3QWX~i`rb987OWH%H$gLQ3n8A%yy>j(ZqmywjQcFMWkm4LPNHO zjHHa6N&H@yk(99wg!j9Qq>P-v;mUUU;&a=dwXJxqaVvRGAtK4}) zeF`P8#GPk}JI~5+=f#@WBiEs!?gJpR4q}}jC`UEt-3&~g&5IADpFaa&276!zjn)Xi z3q+CFMgI*-Im%*E{4#K9(fX&!;!U2~-nz2s8L6?DSlIBd?Bl9 zaTzokS8ha+Gp^i-F5?E{%8lqUZZKX?8QNUN4aOU|aowtv_s?J>%F}Mdcq3lIlp8UA z4Ku?MH&_^A$GUVQ7KW)xY&^iK(4~dhF5?CZa|uUe4_v6+h%Vy>3-ei>Cu%8-P%YYx zSQ!0(~CWAG;41XWRph9R)KzHJ(SCKk?3x7HBj)CX{xf%QJiN@Rra{XdT(Pb9}TE#R%CMg zgwL_j@D8%cr2+Mw2mmSvF^0Pc(+k<>>eZhi;@wr>Rfj$_7$(DVH@@)u) zV6yNS80G(k9k1CeCEBKxSehzvTDrs+S)wjTsUKv}5kC9nn{|8`B`O97NMNBu0|y4n zzD)WCse!*5mR|xlN^$s*=F+kFDHKAFT!2pI$9V)_#EDL0MmCw2AEMx8!bZFqpgD|x z{Fn!S2@2J;ij<(0!`QT&@nBE367rDHlDZ7urFnzw_qY~okH}FEyb~OnAO~?G2X5M8 zxvC4<9r?j?!L3PiZb)&i`X;+2q@u_R{mgwuy0k~<4y8Ch zjk?P|K#IQv*u5!L9+v_WRk_t~Lizo4xc*T{)@Yt{Q#|8XE>wTKZ)Ib?C*>XqsEX3o{S+va3H&hNTX*FVxP8oT2G(e5DxM$nU_KnWWqb)Wza1dV zu^`h`84^-ywo$o-4SOi?eN)vnt_q{{Ei64Y54m6QTTxc&WhD2^>Be7MOy$0_tesPj zPkdEbH|6q^SC%cqlAKCjVO0N~{rq`h{Z(CgBvpB3J1y|Oz!sg;lggo=be_So_XX(Q zVxVi){gmtD0ZyAWxA}EDhH7F{DyIQ%;CU{29Sn#E2nwqD4oB1n1GN1| zbcrRY5>@xGQTru#zs^ltch%2m1MdxR3f!x6(`}mnZV$P8A)}IGZ;I=`QjW8+ARw1h z4h((XLiUTF++&o_phAYky!O7XN~RgOm|*6$Qt+X`Z-l{B8Iw-6Z*k=_Ns^R0BoGOt z=?>pcCYQ38k^ve~;DEN`UA|Dla|mQkFyZqQD<)11D&NQ^o2oO(rb86*#9zS+pA0oU z%L(M|lKZI6O{=N=YZP+5)cM3~s_gUXfqv?MPj}udcG>y>Vcv3ZDf`4vZlCu@FC)3N ztcZQGL66HlWjC|#v;66$Y&}_>t&>-jT~4{r33%us+%cdA@wvMByQTS;iR;<+o3C$F z5iKxFv=BD3cLFZY<#c|kFt64vIh<+<&(73XK0P&-%iqNkbyDH}|3%@_^Ub+nrJ0ZBKR?#94`~W zUolsrGF-i(l>4f%3mj0&y%9`sS;+*!i4(!$17RhV-=_YaHxsWYp`TF?*mfQ|f8HWa zqR;C(x6V7_Wh6H$iGGukNP7RbIyqE!8`zt_Gsy?zBEwt{r6i*8vym?nnV9WZ zkz-1drj$TcOQ?@uNbX^s+mOz^nuFzMa_OdFJ z!FfH){)^;3IwiM!l)0amjph=a`+-!wG1&9GT1BCz!oISvv9brG0GEsMee8jI#DDnc zpH<1e6oX+fD7)7K#iva*4elv>j0Nt~$*am1GWRn&c|}>AQ}btaa@<(Z#oF(X^nIE= zDCA=vyeq~2PF-S;QFSLZ`4MUFRk}omHuf|31CqN&=QgGIRqbW%@0VP6YVHR1;Cm(a z7yqpaWpKV5!kE`f?tN2p+o-m^l6%$E+$Og2O3B?YHTO7kFO%H3&drcHhf=*ma-Vr= zid2mra{DCru+CkQYVU&MlQ*q9k!1*xn zPOxDDXX1qOY$KcH7G6({zrIm3P4|Aye_-l2U%U#4D@x9izI(~d2K9i_xKRMR)4=<7d0+7D21AJCcU?yTR#!Tf$^_UO!-bjcr5g!oDp)qKp%ncX z>5C{zziRMRjq-XwKyv?;^m-6sQ#`?_i4&ua8`)&CC_>xX!AcMQ8fEe6Qx8b>sE1mP zkf1vX0xaLNYN?x@zKn~SIV9fB*OE3}dP}Nw4#caYugiQpJ%E_?>MqM;ie6P-&b8<# zWPNroc6~GTX1c~y#m$4;QF_++Ob~1&LEyml#(}}hF@-8gHqJW0yiHx82j^M8_mJA6 zQbR@!joCbn%Gmy#;`mkdK&zglTs$991c3t`bvZN#ArBn5xNa2)%+uJ#h>Mx^CHCn` zt=Gl-G`k+nZWf1uxmt+`hv0Pt zb-+iqonwEHNp)wHMOa@sbss?g%BlGQn3}qBY6sB%l~eC0iN11*uz%$g;e@_&im-p> z6k-3$DZ>7hQ-u91rwFI6oMIw%dGl5QddrK zuuXsE6iqyJn|v&AL}Wb^Fu~6mY)@D&92}HLO3ez?9pk zsB?Y$)HZ_Z_9>PPEXhZW)ndN)BW*Rvj5y^Ys{AHiN>7{7Z91NXpt{b3SY792?|2_-^5i-vyNhMjbxw9S;Z!^egub8@%Zm~^xfkV?&^yyY?-HT)Zzx}2 z4f2yQ@^PxpM&X#8)W_tcJ|-viv5b>?r=}7#>MkLt?z4d9E+Hr5E+MCZXmyv6)5zIF z-6iBKBCPHbau%~Hb(fH%?-I(f??Aqs)H_QrKz5G(1$;}yS}2=0b*gKfLZ{u6gK9k> zLZ?5BZ*{FxXk{}EL#}lSwGdXvY)SmDBfA-!4%C4f?8^7n?)3?t#ckX!}Zg-N- z+#yo~N$AelodgIHpu?1g1ZXfo3jx9ygeaqsFbMb>3#>#+er$2Z!hASh=DN@VSIte_XO#J_-W)<14E;0p;?_?^W00^u5eZ^9Q5Zt(w<2YfN%7XL@gzl0;A!*65R zOF7?kMw0BQK5!#r+8pDSsB_4m9OIU#cSu2waZ5Bfq#(z*A$n7A=xBl9O~K(-K4LeC zQ@t^nZi3|G=&)plgIbRcOJ<3xM~5YIg!SmKWEo*SIxJaESdR`%RuI;s!;+PpdG+Y9 zWEJ!E=&)ohJ425SOV+V7^ysi;J@Jk2RI+IkSdDue7vgJ?3U&d5dR|p3_h~XqUyD>3 zdq3jS*CJI;SkJ3URj?79p?-u4#LFU`JdG5@%Oc(SA}MgJrt>;h>1C15bNuLeRSN5= zEa^Ne)bpy+dDf!mRi%s0t5R4`Wl85r-gsH0%U(w!?!Aq__3bF@V_Y`y4>CU^k0^UN zuPWFm?4FHPWTs?1Q1sxbOm|0M*v<45*v<45*i~5B&GZ!5&GZ!5%@iFxrLeM_=@EA2 z;Hk`93QiB6%FG)J#`NH+jJ%3^@Kk02yG0M4$}HRqtSy&UF(a>{9z2!lU5|V{cq-FJ zKK0TyScJ%b#Si@QX*xJ#55xl3erIS@~iY{-`Y$P0x7g}61G%|~xUR@{?0@~;4M zI}6CI;oKq_`HV2hEftUvCb?wMy#stA9|?;%`Gc)9;x8{itk`})@qt|i>>-^;q{ z2=DJ7K>T{b2l^{Xzk%?<{T)Oj*4-7$8@SwSm%z4afP{~Vq9VFs3K=tB{YgyZCql$jBQR`rsUaX35!I6`$opJ-e$i zxPnbn9~{n*_<$j!GRbL6&+e*B5!SQ2DvQqUs?4yu7Co0MORMSs?*mZN6zl5&h7+I&+e+uD%a|RLs-x5s?K!*N6+r6E+ZEv zl&`v+l;!L$`u0eFn6tZTzO|K)i2N)2$ei6(^X&(bBWHKjc9Ib}yQ_95&g61-SM5}G zT9U`xmO~de6K_^d%20(&8XZUNVrlp6~{An^uz*NyPj;Mdu)KE(c zQ!kO5*rv_vBhBYA{m5EFs9VS&XP8dZO6V~;uNQ>qXX-r8b!&9fiIL`~S@PCB$LEWNY!;fFKKaSRC8d)oFe2;wgW5 zIi72XmD1XULCG&)`;~0+q&p0AFsI26CctAzt=SrR3J)TCLX2)?F$x=l(5sk4M`4(J z@B;PuV^I|^_Z)c~`6mV;oag*StQlHbtU5 zea%~3g8WLcXL(B(1FjN#R+ZSZsus0inyyxR7KrqpO(NG~dhu3pc?L5CW({wD!co7D z@BxHf{{q4X5{{!HCJrKT&{%mpX?%+`2ISM~{{n_>?-0URlg#Tt;?Ro}clB?Gdjn=H z?=XT`gb+TQuxsP}q7RKj-Vxu?B1fh%WBVoJk#&?7NfG|E7Kxri+%+!~*Y%E>MBGX~ zKUQ!f(QdLjREvDDdffhe{yi2sUTOWDkJlPndy&->b|!AzJLwesUvtFC$3?t#1kLCD ze1Ov1I12V<5<2-X#Xt3C;vceVRm3|@@uN+Ae){FeFSZ%_MMuEj)3=zY=(Z3&CoBh8Tv&wL%+yo=r4Q~ zNLDFU;VXeE(l9nde+fCO==2Xr!X%*_ z7TFB_gLg+s*Qd?UUr7|T8Ttc+)n@1)LRf8vev!@4FR~f>BW;FYdc|xMQl=043i%hN z4=*rXWHa;!%Yj@U+6;p+jBBV8n_-pM46DRuSXE>*3?}pfM{S0|q{je@%`hmk83vuq zR-0i^WHStkY=*&9R;4z>V0)WkF#R+<7HeUmDLw zz$c0hflu^sX{Oe~MA0GeiFx;+tXc~bMTfvA7BF9}g^7iPyJ~1HOcWggpXg=2S_>0> zZvs|pVWN*iK&^#|K6Zjy3ln|!fLpZ|Dy-JRgs~Qib&i*p$>=fGxn!NghKhAAS!A6{ z7Fp*I(k3_$qbfwSar9?sokKv|k$@{UrqT@55$jy4$U2uQvd*Q7taGU%>s+eHI+rT4 z&ZUa1bEzWhT&k9hSLtPp-^Oh$rkJ{*@FEgTd==m#s1PT1Cx_;EJunTD>v)eh7x8D zX=a7ZJ?7cWXP9}J%;B-D&HTYwWL_>4cdW%`PG{y9IT!n}4x4!vi(kQM7%t2<^LS?d zTE3;RUX$5)JXt!)K|rH4rm(th`Yj0`=kPoC`lRiiPGGsC<>^z~Km81aHz-f<-|lJi z_sPgAhqAriJZ+KMkv;q(>|!m?lKLu#FgJva-)3_oK4;EKDY#*~f_Y5ST5x4pu(_R$ z*k4Ml-mb**u*CjhiN@cIMv1+hSq2-7$j=#W+{#8RcJ7&|!Zxnr_&69N@2iM};+qN6)DiJxu zUFb4>Ga~JanEh^zDN~S3`xSif#&hG8fx?4PtN7q|1Li?NHfgAJqvc?Z-xGub!e}{| zlHBZIO6E~lcReN*((QY)ZBI_vzRv5}w5v`Vqs-g^GW9l-~CM$7|LB|m4F$5eH^$g20^x2EHj0{B)4j&@jD5ZIEj-F%rA zaYlV^l(GxQ5kv535FB$o@dZKfzd-J%5Pz1z-xA_q9pVdu;7=y~F~ongUFok0@&6p+ z3j!Qy#yw?_mK&t;Fer@W6aj+*&SW`-%ruhP>g}lUpmF6^5J+uk2h^HFYVE7o<0)$< zSQhdHBP&Ms3m?H zs3WyRaz-uj>5#(@)e?zfwM4>JOC#R?m_|H(~WGN%Ro5x*}oqEJ@6}81J~%75NQO&yvIf=38Bn zuzHpx7VQEY^(;yBGT-WoKLu=cMGge3E3zxBu6QxZT3wOw4s^xa(W(#Vifrh|>578$ z5xU|AaQFX6S7hU@uE@skP*?m1+GMmup5sn&nDlEjDtW+OcX4I#w9P^mtgjW9`*E=VZ4?i}|tbprQGxKU0WU)%C zMSg{u*HE$AGDTNLE#R0xXZSJ?yRouR6a+35oAx69MH>xnVWHUEOqR}Pm1mlVSP99` z8E)w0!&4}W=XeGOesn?P&l%?V9xb>+MIK|l)EY76dlkd%(VR&Ga1KD-pUc_Fl`B{cd{;^+D0 zv5T+*K9nmQqu4H=C5S4r72ntWazW*Z+lzJ8Wi}_#@%Z1k>JqfBx^iX(7gS!+ zg6hBLs>_w4UU%{mAamV`tQ_^|Im!K?t1dT{ix*Vh5^`1nSKT2rNu7y{7F1r5+1*=7 z6zi%>*t+Tx{+C>JdELpiC}gfXDJ3XOA6{U(XhG!-o&=1_a6#pd`32G+ZFcu3Yz2;W z)t!#-nQ_&vM0@qxPrsAdALpves;sLn%eJGFujSBqC;*-5&)~5vrGk>ZNKKYf!R&E% zDHY7w6|amgrGnj^`jqI7n+*5W=<+}joXZB|@M!Ju7nQPyU~ z#qO{xF2WyNaj{*-Bb5hsd8gy++npKz4k?_0$s#j>V8ovYMiln^=V5-yOk{r6e+7n@ z%w&GeYy8ikY(_SZTKuyK@5KBL|3<=79en6J{qOAsc>2Z2?*ji9frc>^M_F@b26Jkz z1n5X_esB@s4BrGYwQ^{)AVfFy)@>qs1>YpBeCoc-RMnBF0g+a9!%Wq%K6tLweVwT~ znjNu(s((hV6NCRAp7K|BDIZT@4X{?$UC7jAEs7S$Jzk_6`7Kr|Ze(dWWaacCoy<+t z^~(Hdx@O~H^!yz$17tXlN87vbH|E6eVZuw`-BiI%*`9O~)O(FX$jKr|Dz_Gsq` zL{-NZxsyCPd&+f0x*ew8fw6+n+(^Ch3--5ugJUvdr`5%I5R1ID@1An}?nIghY<&6k`{SiR;; zE+DL4^CcG&R8t>GBTUs@g?Le+ZjJ#kC^394}z6@(Bpa#tZahER}w|P#_<8d z`ZbOpLRi1X@k3umB^o#r*Mnf?9`yLggJ8k*iuEX@Ods}#km$d{wvkX#^fIKQoU?U?m;ir%f{p$^in+tR_;MBt)x^m zn4wfJ82|>+=NI;2#{x8hIGJNmwHfgSQB4SCIvACxygdj#rTd<^Qa&*!z~*=rS&(*q0MhGnyoxL^C&1=-6bXBs#;eGJFQ()K*kG8Al*q&2YJwVh z7+k~VdJ=gUm=j=2y+DFA{Uvm6E%&%`L~_jCdiF*HY%YB61cmPk;?( zDa^>jV79;&;{Lsbbyn~yGXEw4Uk0Q8%>pvqFd-+v2G=6@Dq!Mhv5Q!M;f9HN<|G;7 zkjzKrsB4d%T)_~B)XoAj#33c8-&HWgAtk5ZRWQUMwTy31>XA`cf2A|ifF~gi>1+a3 zX^2BQN8xFRL%N(niW=gOt{|)-4(Uq58sd1x6n;*hQ(tRW8RTEZIQkgg-F zAr9$!!W!a`ZXm274(Ue18sd;{!m7fAIHa2iYluU-g|LP=r1Qkr5QlUdVGVIew-eS7 zhx91I8sd;1O;|%5(qjl~h(o%Au!cCK#}U>LhxB;D8sdrAw7|>hB%}r6GuZF z(z1}%5Qp>>=4*&UdMCmf;*g$7SVJ7r(=P(7Ar9#ogf+w=J(KWe32{j8OneP-Nbf>e zLmbk(64nrh^en;};*g$ASVJ7ra|mmQL%RDrfHlM+-9uPI9MW?MYluU79$^h}NY5v% zAr9#Ugf+w=y^yd8aY!$E9)l*ukExfLxtimOAr2WmSk^xWqYJS*z<2Qi?S{uy#0kjN zdI0in-4v zC|7kTC(-b#4(0UbR#As?J*2JbP;M?^Rflr(W}vL9LpeQV-{&d&xdqHubtt!xu&P5j zIagNIpaHLj@{Iz1_uPrk2mrd9RoD>zujq-9e$ zS!noZ*-nHte6(yTt5Th`Y}!QRx1-be!4sXdZ2J9pTq=htmwL@0CrV0r&;u|f$0(QQ z$e}1H<$8>=g!Yx|G0HxVQ7*6GgwHk94eZh~NTworHYuz{y1Sy4vz2sdMP9pt);MZ$GuPl4;oo&whjE7z4h1+FW5 z_@-+>qPbyBxHdPe`8@WyvPZa<2*1j?l%GcURn8j+E;YihQV&G->CI6cg2eXdduMD{NrPVX0xuMvKgedJRk{3;h;iF}Rlt6ai-jqs~nN?0TOD)%6~8S#CIqzgmg#t1XJ~tDG_mPc_0%uxF5i+Dm0*ON3u-QG{RRE=S?1%m!Nk z$VA~|p^d&6s2aAt;$~1( z)p%B=K~Yr`jzS|fD5^>iCiZzSag`oSjQB&qlgWbyMOAh3UGLXM91Swk2on@lHHFQp zn2fHd`Ya!&jfwimFaMX@#f}*N(j7UvMP*hEF5U7GvlPZX=CRGrf!YaC&R6%q#dN8rPUp0C#v4~D#6BK z5)@UNJszM2Mb&1NYX(IrtU*z=xs!pTK~c5E2NTzplX3-*7_RFi$qL?7R<{#}aRqm` z>ZVfs4Hr&?dYR*F4rjh=F-76ma6B{1Wa$*^-)u5-laRR=7f$fEGMJ6867x&noQrDk z19S3ohMNxNgHN^0&JOc*tq8KUT%$2CWE z)9U71m^xom1I-LmbS}`;fz1q5bS~6Xe=|cBoiAu=dGj7^NL{3^%SKsWo?5Wa)mX&n16cylVaBkWyT{YJD#GhUAH0}Na)#=NC-(CG;Y%t%OJMq*J5SV(GMhC$kUKO%h_Cs#!hdN-0WKdH9s zzw#R_deS^+$A9%uAVt#DcKv@`4A4ve3{3fN63(W1---Vg;hHq>JMrHp+>+*fC;mHx zJJKhCnEx)}&NM^y{PzfVrFq|p|32aF47FV!!x)L)47FX~k;JkLwO!wYRb{B{`mR%s zw{{>yZP$;BBj{j;+OF@3*Y;3`+OD6J#M%tCT|ez`l&;HA+x5#F3hc}bmq~uP!}sH? z47FXq0tZk-+s#nh^=lk@C!CwvorzZGRG@9lP}}v#I$uEI$_%w#f1D&XXZB=byd<_{ zsO|a_BymTE+O9vznTRrXWvK1?lZChYGSqhcDb94%bAKdDZPz#2u0PC1rcWpK)dVAH z-gn~5Hnx|(kAk?4eZzBho`r1t{uF-ZqYPhVP>lS9h2Kka;W;JOul52gVh%>`8Sgsh}7gr z>wC^JQ`5O&O+Q3UwMQR+1fNn2(M?OMk740^!%^y#?vFx(6UrfuQaIqU{@bc)D%v6 zByNqxZ5rM~ak*o|U-enU>vJeke2c4ZW^yrnu$ery`cfvBI9q@j-E?@v>&vwC9a0u{ z0oL>maZWNg>mp5$?xjd}kD~gUM7Yo(oQR@k|0MFK3Vya8f_2_}w!St6z1<0Wz;Y!q zP^J}~+JpN0A%SQKKe;hckfXD6z;audJtu}&HR3W%C%W4_WP5JFfz?gece9wBqdkNJ zm)Fom=Mql1?fAY#=iPv^S(k_UMCb31{1%rAa&!UnJKXQ$O^hxi+*Lw7Bf4k}aC))Q zMSd^ym$|%#F4~tv?E~)JkZiOsi@$>|m8fVRU)C#KUPBk{qs99n_wf*Z)a6PSWkD1B zh1`6JwKpIU*UxXfXvZZsnrn+vx8%rU)?yAT;k`ie*^71Z1@zdac+s{?Y|3HGDcW|4 zO+Af>Y(Tu|vccHQiZ`=jljyv!1D0KxlCx(K_K@neVy0*RFIP^ONpmbaCl?=4V~rYgf8}aD{s#@fRKi zlHATHofScs%g#V)?+M71?Tpes$>nxN>0&lFlAstlQba~(JEL?7Im>pI9re!;$bdV>3WH);0-BH-R1B`hYRupmf1ovK6 zMaS(7FGo1(@?JZyjBwWFy>?zX;R^QzmaQOMMFSFN*$s>F zpcZae?21IVVew<2g&P*^!*IibiEzV$iEzV$iEzW>awNhH3-WfK-LU9EJ>iB$%xqY& zkuH~T!PNvKE|+k@HEgcuatRk)MHj7FH&;MpOCH= zOJ+6A3Qo0HGOLR$naK%108UISnaN3uF{)g;j3y^@@{hQ*WF|YA?YX?NE;)r`BkMLS z2D}sD8n*|dJ2{nAwYYzS2$R!TwjJVF2_cCkGdcb5cq~`er80+uT8uX(HKrPV4!DF@ z)}UhuztJ(61k$oW9OH>(1L>Lk zuu7?PmwwxMOMJSEpDxek@Jn|QCF_0`Q*yfNcYs@5nwrvGNqp5iTwXz!?t&p3Z|A2W zk#rYJb-9hKs;e6L-7f8q>8{y;d)+6|(sUQU&&%9?2s7P9(e_8g4x9-%p~S=voXN2= zmq)y1%E(W|b0a>A}lJ8-6gbz#f&N<2unyaasTdli3c7#J2ueYHfWC4?sjPz3DM zbe^cupJRbUT*PWD_$x{4-OrKc$lHt*cH4)ijZq6oG03{~o=4|T&fJKPeyb6)# z=4_sV^IYE7r*Mr3E1RdVI^3Hf&}^QK>2zss&gLnIX)evp3QrfoW%DF&%+1-d$B^*l zdOczHk4VI?_f6?Qy?#fpDL$Kb%U%}#%NwBOa_&E`qbaW%zR96iIC-7sv#{5*@ zN44QIQOdDqHU8lD68elkXP8&kHT-ZMz~iE_9ga@fW;UAex2))?m`^ZfetO($ZIIj2S0X|YXrt#3L81Hm~x z%C3QJtBK>zIU`D0VnN-sJDTmRkCHPu_cSj9pLKwnI+=f|v;+RvO@C*zZ1TWJ%bCDa zoa+tFI>oWcehQWySzplmV!+VAdZ)W*rhQq<8 zv-U@Fxv6w@Q#Tpg$MV@aYn76I6#Vh0JnlD=N1Ge~cXzUUtvq)R(Xy|H+;Qe;5P{W- zz@)!~+uCSc`fv04CgHE%@Hf=tk==%nU6FpHY0N;=AUmVUB>S6WEHuklfLhojL!ni= zGP-Hcyo`jrN$$}$X!yHcT80~kF%YzUqip-N4{WkG(%NDq{;(;d_&bf1hfU6JJyh1_r0TaFH~-o_&_p5JmfzN4EK z>41C3(E&Hq)JJOXn&e;;wI3&HntVjlXV^OllU&)B9MJl#(n*VtwkS4I0ya4iY2EOF zGK!xXDFK_rsIBi~2R`g@0^CgN41OK@A2oZtTn+Qcq+-BXPT#2iFwI>zN_zYehwoed z&=YVG{G$%15x#q!?ES|a4jsOG()*7)oC)ym=}>+`1PhCS4u)SCxgDT`;g=@4|7hOO zMwQKvU3s#ZUlLSjT>)R;8%Z2KIX->B^3faSNusJfoFSqW`!V&Xy9- z9HcEjGb}MPV@sTEOXv)AHZH(mJJv?puVa-*34w?q@JvYHoRGj#hQMHhi0mj483iG8 z(vTSw>muztQ*4Wb-kS#~L!SP}5f{>1Wa(kVAs}Lr!$+Xkc+3e$GkKEmcc7BrD;$9x z?9IJ}IwMW+IRIY$?yPf~l$0`K#+-9{?{ zei-fYbB613800bz-ZvkH4q@kg?bFrD4X(wI&jbReuOl~qA+gI0vH2mf{*c&Tl-Rm) zG)y>uu>)l6a~vQN_z(*5IUAaNcv^UZh}Y7gnha8TZ&sVL&d&NOdP>jpz}NEwQZmoMQ@SsjMQc=-^T z)M_lg`OcAoymMs{j|_}?gdE<;BFTQ`&{*WqzMqF2-e@?SAe%c|xR!^BQ~AAZ1i!Zz z^ZR?@chK_NYifvSMTXz6jo{a$EWe~6{8mIfvNL8Qd-E(7xo2M`V+?8F_iOOW)uC|~ z`Q?&AS^V4x7C&!T93NmdaxT$l{o`edyHsbmWo^$G>Q=UAfws!`{1N<`)appZV!y2nIWv$k`GzWsQ?5YYAr}7{SNOgt(8Dw@g_38G%J6#o6Xvn6zfe zWnr7Oj$LdW@=ot!W*DW~tyI@xHo(W!jqC@_&R9F&n5x!J_XuTw0%kb=o`D7-8d22e zYpWVjbmor%tF^Q1%UJhCTxvwoE)U~DHKJ&dMilLOA2_NJMZ4M{FV%>mUC$$5HKJ(O z5X!1X6z!S>9My=TUEFt5jVRjnC~#CGigr;GhDJn7Y^>x7@+Owp*la!!-ePlIYAvi7lFYAhpDLbD6J}SZ^Nl)e`H?XTDluy#<8T66-CDgCs4n-mGCjV$}3{a|F3E z@cJZI!@StsNP>dmND&!@H!_g3EW*56Fm9B?gOo$PkwH1s8ySeAmRN6quv%ihLkO!S z);pB1n_6PMRV=HPSZ_7qB1^2dg5y+~KJ3nr>B9?5A0bSe8yUv1wvB$8cRz?F*3Yma zwZ!^a6&)?HevYtOV*N70YKisB39BX6uOO_JSih1|QA?~}#eB8I`n8mlT4Mb=@~W0t zzn=KU66-e|hzG@%*q}4cc|$C*iC50XKoU!A;#E>sOKjpF9II-HO}t51EwPEW2&*MF z@it+##3tS$td`isyM)yen|P0~T4EFL6IM%Xf`$QWiA^|?P)lqgDhaj3CS2#cU{5Wv ziMT_vomyfOp1cNXiA^LWp_bT08uyo4OKhUd;R~;p*hIN=7h0&6*hGc%AgHM&Hc{jJ z3JJBu;vR&*EU}5}*f+Gqo{v1=V+YEsLbl~qVJ^E; za$mN&#g^E_t`76X5}TN%FfFl(*#e6tHrT>C#S$CbB;d=aH@I0qT4IxRWF*mt_U(?c zu*A;Ae`1ME)-y*fv3!wIV?K}cM_Xc36Al87T4Ga^{s>qsv8lSVTBVpCH% zYSa>&+KI4QVpCIDm0Ds`(^!_4*mp4Q#S)vEz6p=T5}VFM@kvrkY`WoCz+#C_H}XrN zme_O?VYS4jn+dBWHr+y4EwSlV!fJ_4=jj=yme_P#Gg~f}*mV0<$TybQbk!-WS1hsV zsVty2)oJpT2D7B+dt}J>ULv=PINyAjwUeJKYwaX#t(_d6oZz|A^F1z9e2>$SSn^^U znIWdoXbbO_@I79CQu6?+=E9_wrE6(ZRU>FLPb4vdM%#B5eEL=kJ}rs0`~xBrS%5~+ z=xAcqO~P`@8HGzi@!otIfAG6f{vvz$FTki5-DH%*@>p}$i#2GJBck54UxO?H$2i1< zEurChF8eyn(@!_vVMwkuBpXC+87I|2Z)p&{#U|H~KN{zn7Llopyro@+!a&FrJ!R@I zFJQoCp{jb$@VKs-W{7^E;qu$i48b)3^W+6=k9Z{0vX1O-W8+^xN*g~vtmof=&?=4J zrfpx>x@H>DDS5Ot((+H1{t-*xv0dq3hov8|rSq_iIS;b)r1WEK!q-@O&32`$(Lq}G z*GH882G^%7onJ&&hFLmkN*5%wPgweDTbed|=Nhh1rSz@j{9=~gawPuXw_5&^=Cxtz zi*4z*F)E#l`68fnYdaagSO>tdk^Cj(;|@Mh?~4*$=$Co`UQ_%Z@;}|bMy9w(K2K53I35q4J6c;b0GK~#IEf5jOk*<$ z(z!J7#^RCpbCzmnsSZ=>9u~pR8K#|5OSPL)egJ_v?HA%PuCA6K2b(%E;%ykZdXfUK$t%}rgEo*BekmyW4f^o3 zmEw(OZjTczJyN|2rB4M-7}duGx6N%*UKW(w<`Su}q)@^#NFntuoAx@Q*6 zlZ@_}DXe>D(fp&p$DY|Y@Ho~kLt#gw>c@Dz!%_7t9+*)jZmzK@uQO-F0E?rYW`N0^ zd$E}{%rQzOm3J4h!Kh!9cXxIS0+nTfJ4ahg<=x%wS0Jp)yW34zm3Oy?uqyBFT*9in zyYna^b)$0UzleNQ-rWVvS2rqmA>po4S}WZ}l$I**ZZGrIjmqu&K44Ye-9B!(s`Bpk zG3Z>Ccen34u&m0v!m7NxeUv(scX~LNY%{HX4SAk71||GT{DJiNj`=NsjpF<$(nfJ6 z7$9t(PZRU;hl~1T8h;9k^J1i|;>?b+iZjbv#aVES;w(5uah9sS0^xh3$(~i59|uXJ zI1{vrGhq+R--`c@;!Myg&hsH1qd2n;t2nd&t>Vmlt2i^?D$dNeiZfxWIBx@aRh*9j zaici@9+^gQmRwbw*_23vf?_X;j6%hkoKbP6hn7*Cl|xmWl|xmWiDDIJ!d7u6Y!&CZ zsKhGHENc~K!V@^M)rHAh!7*YK=krirnLfP0^bx|eQJmjmZBU%Qi$X?mW<^$UR?(^A zOxP;UgstLC*ecG1t>R3nSjCz7R&l1Jtl~^wt>R4lP;s7w2j&wXE=)n^Hsn~vc^^z) zMsX%(t2lG4TE&^LRh$W1#hI{GoC#aSnXpxy30uXPaHu#lp)O2NoS6s}XC^|$`3qn# zRGb<96e`Z-HdLIM2o>iEAfPTxP@FlRg^KeXNQ8EmWN87`vU~%tji;nV?mi*<8;k&Lon>t9u~xJa(YGDr8$; z73Q)lCHMO__XCPE^R416uu+@|8^xJ*8pT<_m+?vjHw&nWGZ{(LqkYX#&MM)}kN=F~ z%p6sm`68vp^dtRoiZf%ntm1qZV52y5;kYJYdJdX@{-o4~j73Z^9%D4%AgQXtFvN%)5Z=F?~30uXP zgOC&ak3qrnn!$_baXJ#k+1<#D=*7@HqGi94ny4k$a5efj0JZ#s0-^}hy(U`W_{=E9 zU%{#eAXv5JB~thPObBY0Lju_oKpVdf`HSq~-GN*$`$@ALQs!E+t{F=sXR?%dZmpJ> z5SCz&vzC}#DDhV=%aT&!iQ~0IR{ujCFNY;kro>?Vu`^I0?eG!S{tdeJcPJ(7(l^TD zzt(w8o(?t2>c3v7bNTOiZ-7(JrDwV!L!mKkNXFX3axzW@!3ow7q@R!4So-p+&ttXY%x=4PI z^7$c4cbU@tQkJFv9G3o}2enwkd;AAX@jkfsfBRIJ$ zEPWzNf0?DPH>C@loDi1YJc5&JM{x30ORH&bcH%jtb>EP3@?6-eACQ)8#+}2}GRBqi zb&gUVYNltIbIz|&Ai4=^_>V~IB+|Oj(89W3e$MbKA+3`Ptw??b+wp1Q_Zs~9A%1HT zb)QUvpH|M%fA4Ma5VQCp< z^NiG5#K&m9w(W>kajsg(syULHzD!yZnM@j58$(V;L61>d6GzaRXlXGF)tRiRliF$w zfpvyJtJtTen5tUEJY`Zq$v;gQRPpJsQHzGcnpcH2S8L7dn#JH#^QiRRP^A4u@?FZ( zR;en;Kza6T$pu99jr5u?WGc|qP_q~|5=wP261fHqLRdu;UT9U~n|4;st;@_+TeP<# z^~)f?j|>N4xbgpOILJRy)`o*{lUwze=mO^3a1g>a9E7{KHXMZcHXJ0tsJ7uC+>f&1 zAh!Uv;UL^Rv*93w|A)dsxUXHj{}`Jxz?>0UA}62Xt;g8R4a_OpdUUs$9Mzz1$7BC$ z;usBz-SJ^TAfCskiHGrrkq5~y;*Zgw5Crl#QXdxtA~+u%1VZ*~5D4`&69hs~HK@`V zg!zG;j{i*%2tgYJ@-Sf0PeulTP&PXX0%88g1%V8Jqy~Y!0Z5dQ(%w%Klz56h$t?~7 zp`bWEL`Go{2svXA$SHWD9F7PAQ4Xm=m98X;4FVx-gFpz|AdsJ+64jteSFx-O0wG+q z^;o)sqf?naEZi?GJ-op5h#-*9vNi;P%)^q!1c9(3)u8@+K_HaMj)FiaDH{YrUTqKv z@r?%MHGLZoinkv9&H->}gFybX1RQQ31j4augFpz|AP~Yf2!yZ=0wHXJKnU9)5W+SH zgm4%H!bBJZ!bBJZ!bBJZQi&CP7z9#}#D5_O;2`7#zZWPNRj3Sa zeu$KnLNMNYSUF%ZMvB}wK}!wX7a2{ZMvDFI0%K+rklx= zJZ!pD)G}p1LBjL6sF4VVrvcRR4>A|wKZ%3LRB(Bu%8Ouetsq#nY%-p3MlFhii1Lt= zY{_V##pF<)YF@Fj3&ves-mlEFS^6v2L9)veTFjQ%)E&)-OZ(MdF z>#CMRd8*}5p6a4Qd9qW+;%U_&grwLr$U!xYBav!3l&AV)WZ-Ja8K9coWj`bmY{=yR zWRCG8v5UGmYnP5j=Zd&2K53*6qFIuU>H>yW?59ljUkHMC|0K`3zz$6|Tztl%Kv zb<&f`YlV(=IcW1L(3c{b3+EVH^f~5 zTxBN5*MQ8(W`52v)4=dF$E4OqT9=Uy+}7}#8d}JZAMP*^eXUgM9Bh#2lTyBgunIJ< zCBwc_Jp~*Zb;v{i?RVChu9pIgSv~7AL}kk*t&}nw(g>Yt-C1ctELu{ zcB!ToTfltP)M5(>tELu{c3F2(=BuU_>np<;vhJd3OuW`z^c#S!yXa1MyR5q?Ve2l+ zriAXI?MUp~#r_+3S+3zJhM|Mw30e*L5hQXZE@X+PyBq{E*Ma|7Nd?pxx_w0mrKX>mqFTx(M67F21;SuZv~vUKimaP0d@u(P{R&Y6%L{hZmSW zLYOvtUFWej>~$^Sw~!HzenvMM8LsbVRdl-7McD3j5w?3>gza7zVY}Bwso1?P=G(n4 zO3LnakypFdMf`BD>s~x4*3^Pdey#0Z*B|huHhW#9Z1=i2R_$IFVY}Bw*zR=^wtHQK z?OqpQyVph7?sX9k_qvz}_qvz}_qvz}_qrPK@elX9+K>qMy2x#~*TqD**Ts|E!@VxP z>)~EkI}+hu*H};s_qujQBHZhG5NP3E7yB^W>tZ6@>tZ6@>tZ6@>$(()aIcHJg?nAQ zp`Pvby4Xmw*G16ob+Ng2uZu*u*Yy&*%k$WQ@~V(+c~zLpu9Vz8ZEmrq1}9PG+r2J< z&0ZH_v)9Es&0d#)y4NM3?sbuo#4Y%9J20WCUC#p4)ROhgQB936Qfdq@X!>YPEj8i$ zz_EK>z4(Tjy)I7qcCU-scCU+L!|rtvwtHQyN;S3AG?wLF*Fj*)>~&FRGJ9RCLCx-U zJqFk~iSnCg_qqt%y)MGmNtCeN>mqFTy7=w4dtIMJzTNA32l?S%*Hf(5IEk`=e4EqL zVCo2e^ZEdhRoX#}ZDumlJ0k;jH_8=8q>_;a(0pxe0`8+?C~k zC$g;#?$&C+lh`{g?win(a+9wE{dSi@#ktP$fIHl|#Gk^R?{s%2yc0XP%S{lTO1L`` zU5!szF8(Zembipm4GX&y@F!Qh9)Dp=$BH^vr~R;i`Ss+XM(b@@i<}1Ow_GFptp$f+ zl4(7|(wl|HBE2O5YWW9(CtztGKS49QjPg{P|D zSN#;CaivTv+gtrCni8pg8-E?#Q^9t%e@?I|c-0k&9i7NE?uY4$(J9}+Q`Hp(dj?m& zAEqltcljN#6BK-cRQQXmkNiZVgAi9#UBYhtoARLwcjvhidCVd<|l$Cop{;Cm=SM5oX2k%0XgMYFl zk5rO$!iyfIB=^8jiGI3>D|u9)C;6{X90{YN5KtP{rPp{G8!#26v10cy&lsIKJ9&yjrP#C8XN4 zJ1f1QD{EV7p_prtP7cZkd>WD zCc8@rgGs5ZXJln_M^-j(WM%Wi$~=!8*Y|TcO_C}fGF2Aj@=sPNV`Nf^ju9MfcLtd( zlM?-=L_s2JvbIFIEg?)+giLaNcPc|BIjuWYBblr&;VUf?=^%TrxO{m$Q(0l`{hF0+ zphRAE4SQ1AYpxEJlNzM5*G=-o2C3}tCTYa~h8tEkilpw9%AUJi#ow;~;Z4036Rr-- zdtH4~dz)on`(8tDk(ys@a-sIUO)k*Bx5@d9{H{3n8B*&Sh0`Cn2gzH0Vk2#i&Op_BYCg`jf&pW(d5toGWBrz7rTSIXRK0V>yy<609!M zx~<{hDn&PF>uxeE4eG$Y$<={vCWqTyJ2})p$Bw*8=(&bo!9`)`klt0ciIMv8n zY0(Lmo{I5gA;%LY>dzv(E0tYCzR+W%2#8Vlvry@6dHI`SYlbokTh`F z$Oi6X8H&``v4L;LIQrk+s0~~Pm_KKDCDvHV!8@@L1M=ON4u3Ns-!sXD4RP4)ocB#~ zLBrfuB>x%H4@ti~@9NsvZ z9eTS#K1?T^ZyDr%op8P#(+Ou;r2brX(twUc?sDQ+XvaNOwo?X1wqsyqI}RP$j#VSu zv3g`X4jb8y!$-Db&B%6~G_oD1k8H;og?0>ZiXSEI$eyq5cq#0U4NxU?aE%(-j!`4q zF=k{tI!3l*?8tVE8`+NWBik`$WIJY$Y{$Hj?U-L^N1Efxmv&ruo;F~E8I#ViQ)AoV zn|Ac;xbjUqmg%@kjBH2JwnGO}Dr|>*Zqk&dPYOSPh9?9&@BbnVglG$4=v-$?!W|GIK;BGg`qxB8E zBWmXsS-5`9JYA^^*RPx8!Hsgn+Fen7KhMzD^=^|qP$%5`OmcsHT^}@*m$lq;j<#%z zkxDBbUr{8$yjDJE%z zaH>ffA)Gc+2&bE;MhIt^q!Ge~kwW;~NFiJ}QV5rZLipzAwim(|i-d47ze@8&2+Ph= z)P`^*e6QXLVctj~%o{0$1tW#9&~R>qu*f8jX?&9JNUup6A@q$D!eaB(2w{my8X@cz z3PC=-pBgEI6(fZ(5DMYSv$q$*sv;rWN4^?F2+7YX>U{kVU)TNyD})9k1T%3o7$KO6 zqiLiNnhod2YO7mJ@|ea3e#%=-a=or0@`m#@I;1C=afWJ zTPoHo56>C#G)}-`+WD(P%MH%a(|PJ|j?PoP`o6wmh|Sl=y=s!(`o6yAa3~t0LePM~4!V+J%J=#Dw2o&HWnnpgw4*t5~ z;K0WBnf$(xQ_~20zUgGb%wTGxT4V^fm~+ z?o*ZCYW)wA&9_)NZE(W%sVqP@IQ+oHHr;84>E~^I?W+xy&14O~f5$StaT30j&UvQR zfmT`-&KC+es;TkW-SO}OlU(1j&JeJ+0v#V08bO#rWRv|cOjZ~<*d>G3cBQFpnbdZb zA-`u!yTM+o?3v;BB}3i}Kbz!`ssAolCu;>EX?QCPzU3`eL~9Ep;ZV-ayGw~j=}U!Q z;k?Jk!V$h5m+%tl77 z661H9^`vbOKCxorn$rl0t zD_$oRcwMd62{$LL*9muuKF;feyFNSeI=K${*6W144H&PJTajSv46LLmZ6JF%=F|H;=v92bBt*Z%P>uSQc^}pn5!Xar~P3YBOTulm0k8m|P zgSElcq#Lu6aW!E@5xE)SzvpT~sqDzrgp#tZCgjz+nh-y9HK7m6NLLeX!dq99C-G6; zfvX9}s&zFXY+X$VTUQgp*42ctbu}SuT}=pER};das|gdKs|gdKs|gdKt4SF)K|@!Q z8YKP;t|ngtf&YT5NfW4rt|pU^2whF+s}j1Jun$956DC4e6DC4e6DC4elXH>Sv8%~6 z)U%zd2^(o#O$b_76E@c~Vb!xik*+4cLwBhcMS`77w&hh}F1u24=iA&5xSBBEx|#@V zTulfYR}g$0CSCgw)KwV9kQ|xN;pGbe4tI0QkV_i*V<0G*H zR}*GiR}+p6>uN&Sx|*=654xIs3ZvY(n$Q!)x^v6}IpcEA7+C9a&#%96xuj7~E$m9#ljZB`OK3#4otjmo|zOdZL6uEF@@&y+T zh1G>4lb7WNJ~3ERX3CmTm*WwmCtxkGKinr^ zFFY;w3E;Zq!+iqe(q}H)z6UfJj_@C+bAD$wpx=l%RAduN@Dwv6wji@fE|NU=Cs^TS zQ-rf}A5=EY*4MZzuzt>F_~CC+r5ga$6q7sC%XSuU zIWWo=@uiVF)613$$O{z9mJzHQ)s0W^(_HsfY}Uo3)ua%t4U+Xc6X6+x;gM;-)0OFd z^|Gn*tfuy@mpzr=bD;1BHd)F4kxiv{_DfU*o@X^s+8g%T4XGCtbEsjMsTaks2phqk zM@iL{vDyb&VC$EauR#cnKWDfN>?>anDqo0Ge}F{pCjOwopRee^-#f&=JH$VZ_&0DQ zPcZmU806;+ZzBF1SYs;!%qa~bg|CLCf5Xy8v$pFQ5Q(2L&7!v5(I3j)(Td-zvN%>{ zF{sCq4{_L2kKaU6$Eyt2H;i6{)LNC(fhx5VG}YhmIx$bu)N|{+D z`JSSwWx6$cs@8CPr0zhHS`N=21Z1@x1t@p;H6aWt>{?7>b(^mM_9eLqT>mx_f~WQVfEgMPCN;)dT&K1?G0GH zx1y7I*SLCbMLQn_@9Mo3ox-DR)O#zs(;?tiy|(bbTSnut~S1mHuM?MEci;OM)4)Rrtj4ffl zYLT&}gjI`-?Ll~RM6^h^q!(?sr)9ALA_sSl%0W-dB0u)DEW-A*EW-A*EW-A*EYepk z(v^0#$fbks0_NM(vIwgd=}NmacERmszCA5#ceKTxmQ{sbu%~75W+~Mo-M(G0^0lXB z5mqhI?PF6+>_SQV1SED4yHGNE0UqoicA=#6U@1|ET_~9{#GInog_5afF{dbYp=2g~ z!-^Hk_%@TH3g!3l*uRxHMxne5uqc$JXD=nls|HIq5M=BEpC+EdpI7lOc_aQ9h0?2Y zo<&L&O0Qn-ZI##sufbtiiCyqo6^9C?H&$^NyWouz968|HA5HdDq4cL71?h=G=}#x9 z3Z*}TFjqti@V_XO{!D_ZQ2KM80xas9-%Vj^?1JAz*=X#7KbQF$yWr1bzQ!*2^O>)) z3;qJa8oS^x90Exyl>RK9$t${<-^&{eMK|;NB$o=MznIO9Bq%7350Q~kDE%emEZgZH za6XNJKCG1>V;B6x3rrs&OiS#7Ke&mtZ4A;6^s!#@56&+(2f*fIuT?onu zYwSW$PFQ0Xf(pVKyAV`TDymQhRm|7eg`k#_QiU?8Bd@AZ2KB@@3T4pr03H-8l!?wE zaHtAp@)e1AWt4gHRZ`a2h2%dtR#l-)zDZaW%H&&wYviiIq$2#mo zRVZ<=Nprw;a+r-2g)(_H zK~*S|*RZ*&P$sWq-%z1^opXT44wP4gY|E>{Ty~}8?q_q070TqU4)aB!OwLl63T1M( zz@ktlwy;i7C=)jcNQE+Svw&16Q*~q{@eTaB6PQpax3T~g%2YjbRH5XHlpe$2;g41* z(-R&9jw+PtNz3rP5QQ>5nNz;TE~Gn|tqNs&3P+79ll@#n5T%3HEDjD15LOe}S zu3W##K=e_$XxwzHk7j>^e3(J-R~Y>pfLi`R=0yBe$9mQjE#va;!yN0QRd1k>y3`AH zD;J^LyVOV9+mVk7LEEaF2TKk|i%~fRRF#vX*{GZXs>(^QZf!R{(xowq_uQNC7T|Zk z{6+Tgd!Sh_yUkvV&4Kb*FJ5cD6oB?v&j<)7h_P$A1I6vZgn788Ufhb4F|MAupNh+26KkWmkrkiK-@*4M%Nd;*6>VSeZEc*(CHCe=g`9FZ8y3Rq55}f2ihdDl|gx zctfwZNp@6Eh*EVxTl7k@6Qk@^FyAD5;U`78$b~x7bVU!SuQSPkCdPm`Crf46Bx*j> zG+?!9K$AEpeLkv^=x<_3hjWfeF2_dduSo7tDZkk;ThP9^tE9{xY8x-IRD85O()e=< zZ%-+Ipea8;6yB*}`8{pAqP}?LLV6B@!qT z0$Xozr0zBPAIC~apv(|3SH4vn`NA%60h{nohyB0W5a$)o}F&vhtu_fwd#MDXwju`2*I+N7lS#MHics4k8c(z>2${rzi5mVRJu&yfD zOj<>vkLc*>&r5j3FZck1Coi1;QW+m??lc6}7y^0m&-@i>V@otI?wKZq0pxj{GFyH~ z`EDW3gs*5@p9t%}B&`1?t$(ofhx34bvku;YR@uV5g|iDrXRGkGm4#sbX_YvLTg}MK zOW?*mh85IJo?F(l?sJ*haGlm&@T7Y#tovMBx3u7hJaF1Y~rRDQsZ6W=k6trZmEh+WZnR>P7>y-}1+Yj+pxRFan zVOXh&WjzSf#Ip2eWr}zF^7qG87#*J++%}ru@g1ntvCdBpZc~-|lY`qnIk;^lKJT9# z+=iJVsBk_xxGhDMI+!g7x_xqR8@{*ntV}h{!}!qS08-6_^*Df33t>GDAk|7(j{`{M zY0CKI;5NILET?YSz2yII4sQDjR*%ejth<9=9pyIfCYo4C~(ak+VtZPJs( zc$1I9HQ3ETf&OgrDHdoUQi_|&y7Q7v6^PJI$72!X=(;4@P%D3UXcnIE zgf`D3({dD92cFxb$Sy#uozfcQ_^~ZENW6@h$H~RZ17Ab^_!ahIj|FbS%Q3-VCD5TG z^+$mZr&mgB=Bc#!-KYOSEBueJM4w|yG{_O-iyc0K;?yXyt4kcd3*6lO3zxx59m*=Y zX*GC%9=tczu#yh(WWMh8%UwXf0_9|E;ChBZn%~p;# zPmgWhlgSCv1ZZc?>~?2{K^|y%&Qy4ssjyjexrqjSU9%{2HaSRfv$N`tB+(kdy3kN4 zs6ls!EZ11MMCxa@cO^@!g38y51EqBg z1@cAWw-|iv5}4NgGQ|I)!OzPM`xnF7{>aiNv-Gm9%Il+H=`Ue%qP3l@C&%^XB_iWw zz61#LYP*w#PgTl8Z4t}@&gnW92HQj?XJ{J-+GRAZm&tq6%9ahLs*R?qHtBk~I~oI} zO?uv>`djWZ$V)A<*iSZa{6YywW@|qswlCYzdyBTg)BiAtvv|$54f|OM$jRsZoIz+{ zkn_1$aDKpRl9%(w_g6lT$UnUhgbyGI_=V*EldU~aB{zWK$hNgU%*;8gJ8SALD5uNA zy633;232D7ZQqUB!qOEiZMDezL+LBmm5Mv4d{!x+1IlN$k!QY}WNMVN{K11V>BUk;JmZ7S<4zM1SH?CR}F=C=MhRkXGEe4T-_Ti&yvw8&QDO!{gLFIWZ{ecFCfR7_%It8oKEbk2}Xiu%JdpG*9-2W zAg*I;vyoDd5-#=Ffhl$_*-rlq0CU-ulKZ61EstdO!DN@cmNMVfVSe^!gl8$tm34f! zz@^^rLBxy2;8VuS_)500`W)~0ExAd+m%($%%>r`YsG zbHv=^l?(v%<-Rd*_RgRda6RMAc^_3r0(ww*yYZdyf&dS_Zo+<$#lZ7=2nPX|yWU*F ziGbJ2Y?EA5Pmc`hNutK=8*Z4jmBuae^Zb2*KzZ zfbP@3AsbBn0Z0bp`DZ%8NN^f@DVRanL+20Ue{nzvW)k$>9AzBmXNcm&ftLGk*IKZka9=|gy3N1kPZmJ zN}_ndG30!Ja5i|8rh^qKD@y65yG@MAOwRi0HbPSB7HLo1>AH=WLQxo*b{>(kyX*r0U?nioD7~m2yhwU zY_I`?I8jcxA~=C%D+vD|_Pzzcj-pDt``(^=yKmo_`ag>opZXnx-!9!vAbm)zO{*`(f@8a^Ye-MkkGAS zOSL4nHvq1ttcwzJh+ji|y#c|kufq*2E_={C6`#h0ZAr(CDN0u0DjE1TygyPnC%W!jfOyra*CfK7RF%=oFgN*}@@LlIf=Q@iR^(*&V<( z5>Ft%BuCgv&>dolDH9Flxo@m{_Tk=cpN}Ae~`)VTIoZ``Mz1)<}-Z3;zTG|)vPk^P~S7}g*5g~*2%E|_NK@E2zXMF z^!T76>G45D6s#(e9v@UBJ$?uHs*0q?2NhAUsz`dgR3yQ7|I!m!RCj`pEz%R&RdW(N z^DaG!@Z7}vG0xMigz<6(5Pk0((%srSO(w&4$6LZkU>B9(D z=2i~iAaM?zyv!8o!>M#FiD|6Pbjs4Ms?bHaBk>|hXRs+I=kO#uEvw*^#Ep4mcXOn5 zCg!o!S)35M6BBy?AHkXpByMB=kt}s{ViDolgwIVh6P`o%+t7!sdgNr5GWQvPnYK8< z4>C8ccaFb=I>&96m3bOq_Amj}V|-3YnNOp*>;eJRV|;=&SD{8`CB<^016M;maMeBz z24=Mr-K{ffdWcoSZgir1w8vlk8=Iz??h>$SgT!XOA309+c8!$26DP!&ub3<#{l#*? zubQW$h`I|<7js9HL++G^pa8gTSAXErJOLi{;$A5X_$>{$kl?~7Z_z1?+x(z){?p7| z9>uRQ@NbI#DPe}};d+cH#b&urmoG-!o2LrJDVn0xr&#Dyoa$55oy5wYAQaF1P?fR9 zr}&UhaY8_`m1Xn@#rgYD-0D;G1Qfg2c9Vr-^Mk64WY8Qw#pHlu6Dh_BMN(4)QdMH8 zshW@RDe|k>R*gcj?+1!`Q1hdGipGHA(-=)=jZi$k9|cVoRYpxf@hwV~i&BN}))dWt zTixtaYmAGG)F>7&hgK+nm_yzROlMBC^_iO9{RJJZwbT?#OaBQe9OKvcOF ze?W<^lF^|{w;IhCeOt-3O%rYQiN$Wy~F`b3?Ys9zDOWOQgJ zh#u5LgSw<&`b0A{(F#SRlF^}yK-BXcRnq4)Q3WhWRi`0shlW9v|88MJe9$LauZb2ZB9-Ks9!7Ke-ol3Xs!#MGO?09nQpxDh zHW2O5L|&cfax3vJ)I)#h*UB<^gM_z)kI!DUFZ|tq={xLB9)8|Jp-cT_f<(=ow%t+)#*!`s9O=KWOV2$ z5S89vDBd4^qI-oXI&|k&MdhWR1l2Z8<;gbz<46_tfTp@#Q+esfw-`FP$2^Ai$$=+~T^eaCJ(+YL;GYRa^a7Q|oB9mt0{O`9~=2t#W_c zH!CsEV6`u;`UeOU&s^czr?0WWz9 zkYpKPA=1$mhD|Z+jw9Fi3e}!FR1Hp1>k|5@3yYOfp+$bf$WbbbP1>N?4q1N|4U#1$ zF|oYWCz(9iqydO<@hCY+XsXg12;BH$O0O`C5l0# zy1U47wn*5nCETX#Yz}|gmvFZEI2JUjqQqd2)=8!F*8$Cm?kdoE=1EgvuQu7#eSs=F zNfq=puQOFi*ck{6#rbf}d7!CNV}VXC%CEw5B7eS&O4lL`D>Z7RMm2|LzyPgZH(4+q zMlQEV5rN{7NJi<66uJgTS9Nq*c zYpfLZm>R@AEiz^NN=;1zEz)aG=ss+blKxBS&8nsa+8p;DG>ns@8lO|Qx3-8Je^43; zA8O3kD8~boW4e}OH-*7v4*$TH;{hedA|=NU^c1P&cu>hPpyc?WDrmhi<|gVQ*&FwK zRaI@X@FnMQ=v!68uN82sZ`Ia8-jG>l0Xu)d>t*Lz+w)o(ggxzS#;iF~7#e7#Dg#(3Q$$~;!ryhZk&x2V)v zhQTA&Eo1z6bdP#O^eyxkcRH5-NR_osPsi!?5b|xm)A3iByVT2rk$L>E<~yILHHsO# zf9DgmMvAff_|em;*7Ai->WA#((6RgY{QIHn?|h<`v3t9mJ9^d2gLV~L>YY#2CXyx_ zMZG+jD1kkXpkId1V-s1k7m0U1QH$C4oln%Z!P!Z@^NCvSUXe|HfB#R^?*H{!wTaP0 z6hEprF-``oH!=PW;9uUvcpC}$^y}}qiIGC&c+dnn09D*aWJK>o;IT7Patd;!MKbB2MKWo%OOyNi6kKV=VPIr3 ze*nK0>!%1)XR_R@)NVvv7?+tGIlJG&-LnCB8z;Xs54LS=6>^;D-QLE@$;`Z*LRdec zB-pMZzsMcl2UN8|@p82rOn=$*aA1@Q-nf3C(~=;N>P@z2!w>YFed*fMme z8`hC}38@!oY8cvbnZv_A^%AeNn)``AoA{4vYkZB5f4`4E+sA*J`0d0W*7$H#H2(zp zLe-{S;rG{xb8@I^O}uh;1*vnS_H6$hKDDCEY0BD51XVTWD#fST<715Fz&HM50vcJl z6z+U{X!dBhX}V8djw!y;jcAuI1Abk*&h##`!mVYS!9{N^^Y)W{0$LmmHjzcco5+gn znEeHks7+*X!jTgord1)HQIudMnMRgEaI1=-Jsse5t9A}r$eB-!`UjA0I9CvEAZ$6a ziJm8HJEs$FB%E|g2shmZIPHufJc?{GP7&eeZy|rG^C!Zi33nO^qP_` z={yQMFa9UOd562*;x7?yabz#n%Y@q$)Ia<^OD zl*Ga$ce}+Sl30}FZnwB)=3zhfCb`=!9>aq=xMfN1c8lxXZb?3Wi0j>MN$z%wmzW<0 z>&;18SMjX55{Yd|?skjo-EK+lc8izFISt#B-0c>xG^d00jwE-x#T(5b(Ckcdw_ALi zc?}Y~lHBcvk0vv*JIUQ{@d=W+KFQr~@rjbyljLr+(@ecC{ zlyi?!%;--1GFx`L#fMo*hr8Y4mlHG`?skh`!Rp%1-E0WG+bw24jqZxs?7+kqfJw2X zo0-e5l-%RJ+?-Lu-EJxFc8ecwGC#%LZt>{~=5Dumm%uUmOW+s(08rB0?H0S9#izO3 zEp~%|-0c>-Q9$l?vt_qi;)B4t3;!}k{7WR@Za2GzIeIsaNc1?;BIitG%f=(ge#y&j zFtV~~hl9l#+l)eUvS}wLn|5-tX(t!jwBt-9sV$p!oYwP!?{L$Oqc-h0+_dAgGuw8! zX~*ff7L3ylLqyJG!j;Y}FmR@@sJz2XJC5G86SHZM%cdRYkT%>deF38Yn{i71h(y`S z6*zKbE;0ZP7>Tqh_Q3bJm?zC` znr{Vr&%BLViDj^Y&1~MrW{wQ4sbGV8_j*Nw)4;%qRu)LWJdvQ(h_it51+3X+bHU`E ze^(MLQhy-9w}GJA<1$YIcBgq+fdrRn2|{HWUYS+jA^SBKY1W-6hL<_~w9k5t*VN@d zChmKgv^4$>g%13~F*Ylt@b{|1`&ISds|sIHE!}pC&+BpWn#gKhv{!eSU#$myUK6hc z0v?E;U2!QpVj@{bhaNn;qD;tD^4_y+pxfqT>Nc9adNom}kV$mt(X*@11Yk~ON$7=| zje{Eu^ANIy_S9_X+h~}Fs#LF1?Oy=BmP^r}qek5#va(6*E$RCJ^TJLOj4gGKPbXDv zZPu2bN~jqeJO_htFOqnr09{&)Ml-fe!Vp)cLOc42rov9G&oY4adDx4ej@75oolad7=72nr z4QFBv;Kpl+;?1hEz{lGgfvOgG`&oX&To!oyIdU^(fwy1SLo!+5?R|vR0&l-aSS|4O zp9rf3-hPR&THx)M39AL(euc1F;O$olcPF^O+lI+RPl5})ZAxNcf(yJIk;I||7kJw; zWr0s{fw%PnpWp&-+a{$QNN|C-lad%raDlf=%n#ts<^&gbJ8K?;#I^(%cspmZ={}U; z0&nXDKEVav)(d=s3p`Fb`!LXUCb+=ksI!}q*p=V{kF(C0*qz`4Z%>fK^$9NU_C!hS zNpOL;Tg^#8yFI}L-fk1w?oM!lx4i{E(gt?Yng2ene!0m;dPl^u|r!lINNkeo`|W;9YcMAw^l zlVl;s;T2EgD(mp9_u|7?7sL4ooA_OXEl_R1?K0w&53a?jWEV_E)tuI5-28|_|MV!p zI|SXC+XVQdgl(sIG~f#fC!Ldt|1rX8XTuo47ZEOX+KF>9;Y#NO!XGDG>-?q(@Fxi8 zo$oOJ63#j;&M4A;lCyfdQOx=tQKb7@@65NVO$sPG^Q{_DW!af;)tclWJM*nZg~Ofs z);NX3wy?%49GWL3O_9sMCuXw{**lp!OhB3^siP>F?43+45Rm3cY9Yaj82~HIbUAl+ zJ9k7-X4L@l4TsN{($yU6wljt@HbB?V9xiH=&d&v$bvj@kq#H?^Q~KNlQ1toFM&;~z z#~Ycg)SuKRixHwYsvE0J#cx39MAO%R3$E(Eby#$CrlB)sWNh#_MTMVZROL~=dF3g{ z$1W5v@bD7GtofX|@M$OkF7%sR=I}khtNmI=?h?l8SWBA|$W%5SDipI<0jk+c7QZv6 zY8J4@G>d&ci{F`=g;BGWQaovvYV5p^J%;P76!@f%UH5sew|mWVf3L)og##4k@QFV5 z-T=Fuyl*#8W>!TA}zx1b5)&(be*@Ii;aj6u@8=takJ}5MV8mp=5QS2L)H5z zEya`PHKSeUoA*IVSYOSs#1@!Dg9bG^Y`thf&*W^*V>{^{3d$~T|x6PZ+MSe%+ju6^8R0_+FTS-1m^I`F7PLF z4!KGVy1nPM+)e&E`QUjiGQ(WO2_`yp|9NB3o!8z6a;dmseqO23z*teE>y#EfdEQu= zHE!@__!r7>HmhK38Se3A{t9LIXF*WT0?5D1}ZlsjTgl!S6etgt&`h20UW0|zKF-sm#kXlWZ?t?TVl?t%_EkVivKJ|K@rMC0mt85jJG|U*ywN(`WWK~3t?3G;6Jd1; z9J6U9#Q9woi8mHq&*CNCSagGcG$x8}6p)@nOgx9=ZNT~i{vqB-Cr09pu^Q&+cw=^3 zyruzjq;vYQ;9o}&Vs_%E4WJ00G9nl8W_T5>;%$k; z1f)Tm5QA3YZ3!`GCEk`0gI2i-?zDdfwYUjx$W3s4H{n9u&Jia`uHOS7qM1gDn{JZT z=GTyw;tR7$WtOM-!faBRybd@eh2?V^t6Vx84bf?)noh@UXDJe?mMlQS8Fd`sapbzkd6n>Zw%_eWf4fY zAAZZJ@_PYP5HPZxW({Mb&KHPROVDtxB3#D`wK)BR>sd~_k^DTe%77yB;QclW^)VaB z&E5hqYBs)`yxvcmCW3}Di|{DIrt?!sXEqa#05@_m8Z+`=%p1)`x{_Pis%pt{EX#AE z{hvdN;7YR0i}6pFTUCh_!E8AXIZkw;b}FihNjYx0WcKLHB;OGKZiw<1B|sW~n;_*q zq}x$}r$R`_lhdq61nC*=h*Y1?irh-UE`32QZh<3FGoBPTv1Z%!%~FvZxx=+FQeLw_ z-!ifvpeYa8y!@0+U{@de}LG z3UxCq*iW;u=1CL(L6x*dOJ)w&VDW8yTo9!!Scff1UT{D=D^)cBwux zufXIVbCbtTm-{lrX4&snW#in;U3|WVD=gVEbr)+>-99p($>Fr;IfeM3pd)v96(k#r zTFPz6HR>siGFzjtq?w8r*w_7ryk?NsqtA}y^<~XVZj)E-0eH;_cny$O7kQ=kicsBzzl<3ExIz z!ne_wIIxXI*;L3FHX6;O{cJQ=Qrl<*JsXYH^=vdUN#oJNA;>GTZ$T$y)r4pJE<^RWMg^ykTrD?Rht{N*{xQo2B0ZW~B5!$La8|B>LYBW$k2&(Pn>{cUg$AL z*8Lkq_LH0ICX>5&ccAWZ(t62W)cPq@q9#k48ey@!S&4AHp)Payiy{K)Y9fRw!g;6y zl3D~VSzhAYdW5$WD@aq1HuMq$^@urn2^P(^t+|r&RZG$PMvW}G1*S^vcnVh?A?z1j z9WL5SNYRRwF4{{-(O!Z@Q>$t!-vh=~QuG2{^i6)PuknkniV*gTt_m0JC8TJ@N*C=V zq-Za}qHPwvgw0v08oWu>Iw-mx_J*o;Wuy<-e$kcTqP>I^tyt-zy@V9)C3=mT+t`q0 zQs^38=v2SHJSAK04pSH~gp8WWq$m}N&iyDp>yeez8pR}>0EC?2N7DOKgXs`6By;yRx~VF<+q6tP4o zZr_jMr#^+kAVq#XrE(*c8hf|Tf2M;b{V|)=6@F+D)xxfB;oe%AAH2JZI96R<`*Z6N z-16?=CBoy#$BvXXs9IS5EVPTIe1!G1{Zh_hC2Y-Ug(}6nyNHav1jK(gaf>2PGJt^# zGq+skFwf>t;umSgo0a%QTKoZ{=9?t8dPe+j%rRg4>C_;Q*O_$Qx$v0m+KCnfx@6%!oc)ej7{X-LlgZo zTlddqQgdRcfES)uxLytaEKdcY52}g&EDzt|D5>?qyW4N%KgfQ3)qJE@NfqetZ1R$7 zz3TIlouyt9Z8Cv^ykf4<#PGD_GKY8ig1q7r%V2(`P!R7f1o;eky=*>GqXY@M?caSt zUe>(&RV}<^FPq0pY&M#9b6$B-a93z`NRcZHG&UT|l^y{{(5RoYOC=S2p<@VlcRhLuzcKJLR$PiQ*z6w6C+ePZ)-NV74$FWuZ zAl$ZTZi{?w&y$;Uk-{K15$6wLU*n8ewv2ZV+<4L#9&vI$o2t1j@VRvtd)%JWmFp+D zm)Oj~p=kMdv}rVX-E4jV^b2#Uo{wYg<7E!dDFH7L{U${GZ;|rQ?Dg`b$V(2O3;nxzn7OrH9#^Q_ zd>~dYk2-GA&9a77@e=*@rw54@b+kOqFX;wYRCgPbU)FRd)?Gx^@{$X&LbLi!53(sP zlpcIMt(t-cI4^VfPQNKG^qRGHT|j^UgDUePeRp$nb5=K}Vqw&!Xnb6u?+>8BWo*fX z(iWA)3i*C4alFjoOJOgowqGbDtiNjeg}Uu=>Vvesm)@h>{&=tLRb!t}*w|iDH@27T zR&9HN*S4xQCu(VXRSUjH-#vvb?kaymPrN$PoSLLpcB1+MT5Z1M{f9d6RKS)rQI zOZKW}YxbJWXzC|>^`zk`Te08iv%l77pYtSE^-%&lqJKk*r) zJqAY2S2$`?Lh-r%D4dMfgsFgn@d`63>23Q_98L;R*QB1IHXEaV#cq0;6X5Q+s@0>u zP*;Iqj1bVgqt!KL)sxUWKVY>OVnpX#mvG=ghF`%1J$RWjc^pare|1uO9YiP23}GBxQ`ZGE{9syAGX= zGO&pNiOGIykuh!!C`~==uoP^x=B*1Vk@fa zL#bY4{8kihzWdP^Rq2nb!cn?gita=kyj$0znqdd?1eJp7uu08%OzzUOJwEN>psjv{ zRh#eOPl&MC>Cfy_7HMMm?U z7v@a+w8nNwY8efOAgZArQ?JIlV~6=yomQNuh{p0mfbBR>c#Sm@z0xS=?FRssEG3CyMNh)bCJyEzW+#)eW(N(B z!g(37F^X>lHbZPI>uSZ9z;=tZFyF>YPZ%GuaX%+nKJG3CS$qQ6#fw=HRq=QUE3PUV zPpJyBvhg(GQmJe_!^&0~R))mcQt$!4(#y$@^^2DW^@~>o^@~>q^@~@j`dNpONA(Kw zNXBb_Ncu??d`@_O?+?8SR>fP zSEbtuw@0;Ef~aW0(rGNHgj$B^6`lscV781|hk}oqhR#MNpUmtS2NYbpQ8=$pTnLK& zcguKBSmdG0U-R<7Yweaf*c$_pqfy)FO{*bBWEa8P?f@9GzlmROXN|!6J%RUtod^$E|Cc4LAU^#XOLBrue zm9aw!+mN9ef8}iL*ffH+oUI+3aSLGQ+r;c%CZ+If?bs|njIbP@tsOgp`L@HewPQyz zKk2j~HW8c6{ItWfwPSM#mpVLKJ2sc^I#wEq_Sp2F0dje^cC2S1L7uH0nD>@Khxs&(@BeMikrO+1jyQ!f9t8 z*)Jtr>F{jr*s^Otns<1%c5FFmTbvWoZm|`F{j;?p^x~Z$QbPCf@v#zmWgzq_5n9gH zj`j0FkA8#W^8md!IQS~a0p8%CHh6Dv5cb~SAnd)tLD+kPgRu7o2Vw6G4#M6W9E7`5 z`V9^ydQ$og4ki|+^cx&ZEJ`iIe2zCbPKJ2BsX1sPyura;ko~Ff8yuTz7~ z-o<$2#cXz<=pw}yU1To1QgSc$a&vfb0xFp0E1G!kg85m#qKWq|1lI3e5XOF3lpOym zz#L!Ej9<^}=CM{Sw96A1h84==#|js$!%=hQH#?0HCOQE4kH zPe5+@mtb$0<=atyr2I-05iS4MC@{*e!h~5=o?k6;)l zYL8*!=fFt2|FoUud z+%seUkYIY%@laofHbT1pIb<6SZJ_k(9|E?VOTaIEI^iN`0E6 z>9u5I8%btyKuC4sMv0xic{>Z($ii+`1zb<20$WDHPTzDH5UK`oNcPR7#3vm@up7Qh zx)ck#@xQ3~f__GVZxgnRYU$saL+fBU zm5&9rSw0iLk@B5Dik3gZRinHZa8dbrfMbSzBK}ln)^7lTa}{o6&g?|d&?b;&HW0R* zM+k3Z%cg5qZ#dJ)49*3dty!^lsgc=4IOjAG=Pbgdcu_XXk^a}-CLGWV&{(uM<2^eJ|7Yn$L2p>NgoZasb`~+Lf zeTWFMiOGGAWJ7ES_a1_mh(xOiep0{>lkCzxAT#W%k=>Hn(gT5UqUJC>ceQ4_oB;Ya5p%<4T6la znH1P|5}d5MmGEiYEt^F+;qb`3vLgt)4!?v_cH|#%H|@|~Et}1mD(~=1C}ne)-{SB~ zC}ndAch>MrC}l^nDm@M+B%`c{`3s$2po(SlIxx6<9exR=Y#z;teurN|DVxUyeV4;8 zp_I)_A^%>7UqVsvgATuhQa0~DA^u(?$(d^t=P?~t)DVA%5jm$FiTb|}?Zv#8E0Rp)k)>KtLq;pZ%>OWC}% zc-i7Pe*d9t=Lex^YF4c+IT;+v#fvXjUVPngm_tl?MQ`^ch=FT|{33VwE5NSjRG<*x z=QW7;bun)sMwR~&i9hiQih*~SKZ}?<9|k$&JTbcz1=l@J6xq?ZccS8dug|{>?W_0; zg3o^)Z}|KN3izKH@aGIrcQXr}vkW{dCn)}RLj!o3!xxkP@t6P=0$%^F{{qFC!yEAO z8sNbSDWq?N2P-Q!{I5pwV0*|EHOZetn&UnxGy|v?XPlVLWv}ifmOhh+`^Kx%^MHAo z!}qatX+1&Umeaak3M2EU=eiB}(l%o()r;qsBFKjn`9Gkc%?uY_5pm@PJl*G-gV<;O z6^bR}gREorSCFs2=l#SqXn}GS7c53p3`*a^tyQ=dLG^h(yAxbq^OVaI$oYo>o@(iZ5#c3@vo2QH9Elz8ZIm~adIITtI z67DSGv=%vP6>xg60~+}~%wK46T8qrP65M(%PHT~Q6Y=Yva`{8RyDUy?k$K&qy4T{g zrr-xHPHT~Q8SvbzoXco4Lpm`Ph>L|j_7;8ne$QL{?4plNhu{&$1dA>vn6Pd8di-_i z%rS5($4r_2*_V7_ub8uStVYi8E9Pt+t2Iem%-I@WM-v>**7!KuAX!KnD!@fptnw&-ie zyIH1T(bta8VmQpQuD}cuKZ5zTMPEC9B=eINeeL*c=BF+C+VMGrOD+1^@wp!c%SyP( z@#(cthZKG7c+U_rQ}ngt^CWlVS(wx!sgQpbCMDxpn7eUDN%%e`A${%msY*in+VRtf zVq5gJzaNE!d5hf>UryQuPprV^Wl(2J?VO6Wd**hvY! zG7x$d`vZIGNZo%Oex*aW<4ojlFw#5il5-%7Ma$k!v0%gE%4(-oQ*vdsGlY{CS5`Yq zIBjudwR40^Ev~F~Dd9?sE2~{b^{Tb@KO2)R=bep7*%w({S?wC)>y_26r+6_H;fYGD z+Ns||5$l=^m`mRSs$nr!?KJ)fFpRR((A|mlJAe~C8Q@;`*-mJq#qGTAa}>+4c*K+Y z0$bF!c*K*tk8s-J5l`-mge$E_q0a7~2ElluzcPK#U6 z-B$^BXBatU4C4o`DT##{#t+c@`4=8O9G>TgK8r zhVcV8e1N7KK0wpWh7Qnlb7n0H{ZNMS1Gm&X7u>dI7(Z|;&5MxOkzxG6Z8X0Dgq<12 z58QDkJ9<}!@dJ0fBz9*QKX4~V;`$8Z2kt~k?8z{G;I^6{1I_Ij#t+;!5%lg1;|Fes zc?rt7$H+2%;9eG$Bc9x0R?^}TPwwRe5&veJUcu_x*4_AZuV&xiM0a~8^K5pY=qJS% z{bVk?QgW~Ma&w3UK;w!TKX4B>nP1HKfjeEnj32mN0?Vhu6W6oMQU(nYHweg}LE=UM z88k>%QxKQa7T=&KGn^Mlz@S00hB@V8=W+BEkCj7e#LlY_JFi0Qyo!*WS3HsLWJKkp zrsCGm0=8)96}NFU!Lc{<0k<>Tws_W0aR;>~ZSkb0;>m<7ExyxQJcUK&EuPd=Je9P~ zXbz49vGa-#nTy-r@~7@p9(JteJZ>p^r`TY z(5J#nn&@GuPlcC^V!XZBqD58Gd@Sw{3jR431H%v)=r zNvY2F0dBG6b7`Ib1i0Ng1KpPDq;7Xwbu6m0ANk#ud?KxrCpq?5-1wC0?8ca0Xe~lx zraIZQiwv=q(+N4{Qf%dPhJ{(QmD5?uV_33vI!D;DXe*~nSr%rXUFfe=z6l@0P#ozze2SGKox(Gxdb(joJ4`gD6C16%?Z1d zhIwQsGpf~TU73m zi-${PO6Q|xZj~O%l(9$lsnLhyT-2D{s?O=kl<$Fz(dn31cV*L$;;ztSGeIwAr99P( z*-X%jS!r0+i`h)ji`h)ji`h)ji`h)ji`h)ji`h)ji`k6yqID<)$>ykci)Bg6mQpQy zt-H}=*)lFa{YHe3WV7WHfLhEDT&^kd0$|(b*ehiSuJkYg8G9ejM;|u5&V|Di!h&qj>GL5;>1)`!=-owNNc00_7Xg)H7E8W z2j5cDFWA-1W#&)Vkr(l82V9I?@-m0lLTdFril4BVWG|K+YX1{z8nM51ltiC<*J9Y#dvW7pB=kL|M1!x}Xj%`!Fq+vb^ zL8M`DkVS+{ClPgGo2q;-T3oe35_5oRgGs6lp4_6o$uUW_!J}JL8?>o5=vQsfuG*kC zziiV=!<@o4=O>5qvJqvf5^<4gphJ|1CpOeihZKjZ)VU3E6xcMC+T8FIE7Pe`gN@TE z@3NQMm8^}|@#eP9$vRohd9j) z=F3b`i6E416SHn6^Yi3!tM&mmQ)FD`@UbW-k9~qoe8B=PWG~fCb>d zRnC0&v=0)AGoO7Jw$lLS%xAxgFb{?zk0fz)Jh$+jrQ%8__XHVyoikq1DEKq$5#8hcqDp+(g$@ ztS4@s*)xuT+=k0YM?!td+GV68p+05pGSZQlMcxUQ0o;W8l(ox9N8-q*@tbxT=}62z z6F7O7k&eV1=C`>qb$VQb_&v;D=rYogn70e1_qvR9Bo2VF)w67y(C>@`ZLBC~-a)i({B0bIA*WJPU;1YGqg zYnvefSAELbW=H`3h2StG0QZ9ZBmr`G7oxn^paGL(b|X6>A%NtRJHgUr2q1X~LBr+a z_T-_28GQUS{z?cSIgMaKLIBAbtsrn20!XS)S-T7YBxijb3@n!+faDQUw#yJe@<`?< zU4{UX>QmNkDORDR`joZH5I}P7x4^#A$h0S?(;Un)1d!}`0GU~a0Fv`0mmz?p`jmCa zFTs?}D{Z7h0Ll53thhaS@+0`GBzzwwFP7MCG_^>hQ>x;f#U*Sa zQTXB%OE6se`o-!S)-HYhV)YGcm%e^6ceX=1`ufE=!lf>K{bKbEYnQ%$aT%MV)}^ms ztiECGGKyYY#U^TT8AUIyrmTxxj;rDt;%i^OxITj$;=h-)-wH4x{(I`#4yqCT_tbN$ z5$V6DUZ8f`F8%k^KEi32{(I_0!j&%l_tc*V=Uw{msh0@1xb)vsFB5Ke>A$C5A>8TG ze^0$ixI0JxJ!P0o^yKKjr%XvK%+Y^OMI^B(NB=!#nX6G!Z;t+ZDrT-nqCZFfJ*AIm z&e4BQ=_8tReEy#*F|Pyb%{e~*Pi4(>k=T~w^Z%4SqB%$ZJymLM0=Mls`tPYq^8zGx zo*e!6RIB-WpxvIM z|DMuEH0S8Qr#j4!p`3e+Qu^*;^xrcb)S9$Q|2;FAaHUKCJu`(xYI&*wBZ zfRp&|nL}pcw)pSa6!&E&#DCA$)^RnUiJn!TN0$X7t3HqJ^7B+#^?CF(KaZYOpGSB3 z%qQE(1;%neI}32rEU+n(buK&VQ^+rN>Az>2k3zoo-?QZ{NF>C6&rTtMEN0oMvY0_w z@{8FNC}w|#($as=Ij559d8B)D)42W!RjyMlf%M;Vo!dcayY%04okU5y^xt!xbh`2` z{r6lab+pB$|DNl-1aP}c|2@}9b?$WOzvnuaBEQ?E|DNmo2;d%<{(G*I%h*DflU=Tp zO{@L)(!`%AoA~dg85ZW!e=p5a9>b;oUYa9px%A&lOIeoo-*b67k1=~Xe&vJc3jtIU zp_&lxT+1e)|DJ0is`&4@<~0Cu1}1)miuJ7K4>C`HFyg=G#we_Xn2KUHCt-*FdtxUu z63+tMRW|8V)J&SPtTkxLvQ~<#nzF1lXv(tIpef5*gQhHN4Vtp7HE7DR)}SfNT7#x6 zYYm#RtW}!QW#!7++4+lQttjiDZuGi$qq)l_i)Dd88M4Zz+yK;?k1m0Y{w^9&_$H?I zUuz#?WXZl!Ig$K@G^&s(4TekJ;i=X$oH7)#DDE)OGoi>;(GBCPbWE^Ox52_ zW@nHLUP}GDPey7Dzn4L?Umho}<=TSxo9g8ZwRJS?=*CKT*k?{7@c@*M^0+Eg^5NWm+ss1)%&eb9rwJVuyCgG#n^_VE7 zvfS_bF^cnMBY!oi%Sr7yF1|-g7wgM|nU?&;YmK zpLMwEkMJ13;Y&{pr9kmjAfu?%|0W0prld;WKwkfu+`5T8BXJ`?rG zUd_qC895Sg(m&RS+@>+SNiaI}uPM0u;FjEq${=~~ zmfW2Z$%kR3LzAxA)wT&Lr_Cz)g-nYIz%hfHHMRvF9KINhHO{tQtV4>^~1Jg)QQ*D$Ua zMu~4iJjB~2UJ&`X5QTV=56(Ezz08sG<*n`FD)M}JYvlK5zDY72?hsf%A5@P*#e*nn ze*#Eq2XXA#<*1YFAdV>yLe7AXy>JIn~KEi4TaqLCHY6o%bPlVMD;@C@s)ehp= z%Y@Yq;@B&M)ehp=tAy2oJ~6{&LLKN6GbN!8^od0zp$_zkS>|UUo;uJc7BjCxLLKN6 z(;kGJ0Uy&Igq#5%E5QqQ-hn=`ta&C9>d?iQ_8{a8_*kiV9k{6jePWg7ZAhpCeelr! zI?$*Ceel%&Uyx7-`rxrW6Y4;p*aS(a1ASr>C7}-ViM7gCV$>P%G3`Of8St?V^DdO5 z5A=!Y9mKI=R#J8l$1W$Rb`Zy|V0G1$67xNX(~%dm*?~!RFU2mV!^2#5rQ|-~<%SRR zi5+e-Uk>z%O;<2Ih*+1vdI#};14W~?0WO<#6s)0Z9E^kq+B zQEJnd?K=}cL;Hv`VIOiXZi_SFq<%+k;!HTTOE3$R(wT6SGa=gt9py|obS6|lEK*8m z!coqILubNK&V)l}!fDz9Hbt_<(iycCg%&$>CY)w|E<-yLPI(^^wm1{c6cWhRMrZ1U z0NIVonV>*1n;R0!jyeUCU34yPj+}wa;U@G%xtN3&K?IU3yF;W`g3u)GB8!OqaF5RxZf(OUPv$4ehav zE4ok{Wj37%L5(gb1g=xy1MrGo37Xei?lBUD&E2S8va<^E*t4s#vC0U)-$6H z1grP>7~K7^qWU)e#JAz+a{RN;#*c~ED14`AwH$`(Fd`SNF|kw2a2Sz`)|xX2Ga?sl zR5*;tMaL-|Ms1_x1xJP9tSJd-zl7neLkOxc93GZu{fFq}0{av6rRj%FQ=I2-A!xGxRUW?0u#ocWZjq}@81Tj`X9?^6;o3}>CH zBxD%QI*ll{%P^ePOIU^Btfhoi7|vS8_a;>s&RR}d6^64`5T0o0wZ;ld73K@}{*AFD#nrQXaz ze)%xVx^J6C4QlW+zpVSb+Lj+m+^^h!gp%u4U#>GS$*S6ZMd2<|a(zX~wXh;ixo*>P zDJgGPsosjGF~yi)(=Ac)brx}l7P8V9(FCl)UFzm$Xu?V&-^3=}p=Fxw%XFPD(@naq z@RxBDd=VVeZSo7mO zF4dnTmx)A7&QP2xeNMk6Cr0nhiMmH}oH)ExKRLCkGH|}wF+|KU=`CB)kzCtj1TLM`9O zYPt%P^~jWSm{YL2T0b}jYhV2(xDmSnKUd>loIfyM^k=M;FJW)9YQBSf zIZWHCBM6dh`1uk32}#PZc$l_TzXv&q*#JAuqNXewPL7i7(adIy*-muVhay1160@F}r>+Co-lMW^mmA0(wvdsk5(I)Uk0c6h zo~pWaMMgG!^pY4Mxs0gi841B0$nMbWyxE5@bFWo|80JZtsFF5mOO9s|^9Y`Ql#<~l zUxxQn2H`xfK!$k*GR)U9WFOWHyg7rVp5&KW@(@d!`d)BIIU85>4Qy;%x^%E#EM>uJr_?t$+R6zP7>TXRn&H zY}4vBD>klKdRAZC+3Po)v2kGOa(!p*(lh!dZRlImw{&A)o1pb=IE{STmabg^UTc;v z>szCkZ0~O#^opFcX7##FnLwM#b+_HAfezHyUr)Uof$&pIKG>}jp-hPlnm;AQXk#G-bM zJ=)F{q4CU&Il3h0MoZEa=z?a$b!Q-f*`nNtmb}Y7+?|L0G?vb{F?3CHUd}{btkIa4 zYlBrEpXy`IteTEzLiSYSs2oWnm4DL$YDzL@HZJuD3m*+C6|Tn^h>u$2%xH=0Qd(9j zUhLPU6IHX3v{fT8>7>v+q)HIL)a12A(rb%i-4;dja;hy#D$Ia;D&P*y%7yM^^c~Q# zpsXi9MnDb{u~kb)Hgj1cTDRO1`R7S{vj!C{z^?_5$})3omFlXhBB^V&)V0W~Yt1yt zt+gOWKwpQVb(OKjOqgL!Z4dzZk`GJ4{%s6*c9Tjle^k&COg6WgGpj_QiYOI3s=M;C zBdRDeVsla?Do@lgpriykIo5@Wa!+xKG%{ou*NQqTgaSU}TUF;3mS7kYJpBDio)}R0 zoUkOd8V8h>Gl5qNcRyZjLCdff?MiIcuY+n59tp2cQ9Y%LDUFRQ-NVNZ!;0$!szn7# z6zY>3=u^_u*%#ru_Z(%a59&a~hA`p?waY{8^bAMTMy-Vy3rse7YDY!Z zax=f#R}QFvU-TRA-9!GGX~^p{$Lq6%(goMkjilEn#i~zA!hOPNC)Dz3r9hdWrBvr; z!(EpPcU`GY=-H_((57-vcPheN#ObP%s!}zwldHW>t_eE1ws2aiQ`3^yk?4+@RnnDV zd6|*-djbPK)Dw;2{7|2xPs4W<#ix&etfRvD9);W~n6~^fWYVHI^Kw%~wlTh%`J#ZF zXk)dK>B+3cN8En`8CR%}<556J?Q0iU*oqqXuKG(&#$fgL;B_Ed>|#4mw;7fJR?;3Kux48N$S(ELzRH zIZG#-$;#8!(P1_PdN8I?SI7D)7Aj9vsU^5mFj}xM2Meb^z9`@L@SPA1?@jQz`Km0X zO!R3&s;o_hN#T11m1r#-MQvf`p@OkMALtI)W4%Umg+|_FZ9eQT#T0Lim>P&vAj}&b zJ4%;ho^Hq0So%9I`Guo6=Z)f0Zxp}AvL7C0`!D*1qnQ?}9oWm^MM4dwgDwt19~E>! z$Xw-^3WkucYFeRSxrY0El-ILw_HzHW>silmIG{0C*zM(Bx6{Xv$-AMioZFP9A ztr=+u)au#IU*7Bd;pi`+G8pT_`Q8AQJArK%nxAxcdbXXO0E2!HGna`|_j_pK)UE~f z0>rL!i;V7Jx=)AfFCTwUS%5vZTv)3P`<_-YyIKDk5H3-wu}*Owz_n6L~5 zbJky>bfIxTB@WEbkT5bv{$VsGtQ3X5NqBuJ8>u0|lvSu9mEqPO(VB>sgokiQnW#H8 zUVpyPrqy<_S_s6MrxVS!J+$(Tbmu)I+4YR%q}FK6TguKYF0`88^0 zOsYW|tN?{Wtv=jW1tX;)V8O1*hY?3~D#BFZQR&&sdR`73z_)k+jqEiisDbLnMB$R_ zdNW+oTXIMCbFj+NJMtooPzxs0fv2AFR4D7IP!L(9t6mla$qL%IT#p95Kze?@P6p#> z5UZCTE%YiP7!QPOW-t-!3 zHmXo}B$mQQC@M@GSOJ_h_kZ^E+8rNEJl-6HCv0AT|21TC3dNVlQM4l5U^(G}nDp9= zkEKF3X(05$LV9mR?7~Ua_JS9Vnn(YaJ~Hz=A*5^v(O0b}p1uZi8oMIU+WlvzhQi() z=|B|r>1(R0*WbZp8!GK@H&y*(bbZk7+KKdaA=Ic^7rfO|&k6;mY-q7Nh#rJzuV88^ zn7;~avLKuhlH{H4eSHtZ58l0@p{{$z>)yXKwnLO!F*vqEb`> zbHr=(jc3m2zVXbN{p^M}wgmrQY~#@A()#bUv1c+C4z^&IK!{S0%l#c1H7*M#U2o>r zrHwQi3rE|i1L=Y;?Va`bP1wB@H228$IMltmt42=Pg^CdvV819h)1 zjnSl#H{or4(nFmdLueWbKEl93Tb9lt0v<-LtTkc|N%7xRdI-oa!th!+)m z@uCthUX=3odhGvks;h5$R9jduU6h< zD6Fqk0+Vd8^YDPfU-wwO?lIlVULeuybic3n*AE5~{qRJvNvKf4!ppbrea-q{p?a?L z2Y*<^)qGr`8U;_(LpGq+;R#wAt$=utt{OWCXy|4rc#Qr!b+J&d-cW??AHxO+D?d9b zh_Z!xX2iUtd*)#A&EU~yh=uOlgRM|+eEv`q$Lri};7t#~6N$p9q&S#LUiSvWkyAjh z-$0bk-@(dRM9-|8y~_Pz8)`M(@D+tqbY*xHSB2>c9IcVhehPWa~`$J}WPWn?ZKfk&2{K)R&t`OORT&5lpVSW!k+o~w+#7ZcN z?nG=D966ZS1N!a(R(;i3dSHxP^Zj1MBwo;~UZ;4IKgKKr*~$Qv`8{}U(d6}UVBUq+ z1g%`&3a=Srg+IuA>uqh;!+)f|R;Z%~^Vhgk6wLkwmD_*r$CfPJf(3|br=Z;N^Z&+k z$OsJ$W{fvslXBRmzxCvQ&A@vg zqxE!55RIUX5|Zv<`&s{Iio{NM+w6AtAIKK5chpjZm#u?IPOB{j{{fZB+v`Gg3bowG zr6oLDg|v%hj-1%^9I0m;PhY&*Om~n@2G+vJSuhA9h9)%K{|GWGw;<4GJ=I|v^zIa> zoVIxJEYGhpWXMI$ z6)I!MJLjB(y#T@H@(|x}3mq(M^(GoHVTaLkR52sLeDRFW&^s)lz1**{3Bq$>v%wfr z`!3iZx_wkescecEY1#z)iNwain^DR=g%KFqgN8Hk{8>X@E2}B&H*Z7uL7G`sfx`as z!pM3;9=WZxus8p*m075(|A&3ILR0jwdfg~A9uCw|fgW)rv7`H__fer@ga(~Nht%AK9Z10z?GkS&ro1pwx=`0M;Za=p{zakrSL#iw zn18%sTFycEKZ^(*q;1)CBe!}Mb{%6vp{@%S(!zD^P4A?_E*QBHu&~YE-1qvzO{G>$ zy_R5axHmacsY?r&ma@WjD=%!fzdRYei7Uoi**YVaf*>eSsPG3|JhffpZKl)HID--) z6$_f`^_U+cV*}oRw7mi8jdFk3Ckj<;8xYr-p>Kn|TBgc2)f)v`%qh{=+XGeN3n)}UNa-f>&=1vukU-Vd5?Ls}r(Vg|0 zZlsNPkOHK6MxH9L8MzSyrzjbg`BF)-Vd5ep{@?#J1;fB`3afFP0#OVnvhDl)iz5iS z%*MvXricl0WIw47?1_HgFhjZe?2YJNC z9l3r(-;~zPZOifZ4c7rm+=jt$fFnj^T#V4|w_@0|En7Xf@wLa!8*HdqYgVn_uzIk6 z?OVc~>N9)8>a+Sbyd~^M_VNlTs!fi7dBeT^mnShEbMrT;54E@VWWeJ$ts7juw(o?# z!A%3LI8-gPBx0HKW;!f|I7bSL<%+(QfN`|n;5h?*8v!ElLV7?z9~kW4(6@9&=-%@0Z^MQ)t2c5f21^d_6F1-lCnT|1k76uby8H~J zAciN@ymdHbX{AC6WiL=%LOHVr1{N$mr*8vhvcdJs*RN4*SjGwH$fZo9kRTmqj5SZ! z4{IP%daz_JT^EobF#`X{!3}GUSvpWyn$Dba7FJzKNF4$boNY>`^9szo1H=W4F4?$x)jDY^JqApRshs3RZ`BNc9b#MjZ%e zjDWEj5$cEelzocCYPKj21olfrDKtfQ>hr~--!{yyXnB7Ag2@Y`&es;qU(gA}g-q@6!`6f;Zm$1Ir@P23bs=5Y*Pq_KPI5nbI=x{m0Y**;??a?IGuSeO1g zOaGlYv+b%Yue|!I-Q8V{ja^sGZ<73-u^Csk3p718xd~59|6ml>#_RTc~I5!m-YHvjcykj@D zVMP$f_h7EpNK5TNc9X0+TylT>l4$Ytt|f~XFIfPft!eRaPY?EkjcyZ^$7RyoMR`1bZ^xnRntSg~Z{D<)lw@0f{y zQFnS+{>$yb+k3Mw>8T0TMs)WV*L4S z<=?%t{Jt5_ul`{I@vq5@_rBS`qjGnQ%6)NE*L^eP)>qeR zoPYBG$!Qx>l+4ZDL0&3-4>;w%*wMB9*E79;!sdF98VCVpV^>qxeE+|hGa3(7g;S6( zhWOcMbizv7@W|$?c;$y6%|q&sc$*$^VYg;4?F~WJY7N z3LQ_6%@;>{dJN6m4y=w%Lqjv$&&N+tw8ogRc<~Hr_eOL~oBT*W`1S2t^=sYqlt>kT zZ%SJc#&|78do6tJ0l!21`38Sr-`KMa z?PPd!UFebi|69=k?^pwxQq!cShWaVrYn<`n zna4D?E$*J%JpSji#*M~*W1{bG<-f7fa|-^oL^rqcUo>IwoH=2X{MS65|Gj_4#HNY& z^GE%+$1V>NO%uN!PBcyYaP;`2qa8<&n$dXdDQ(C0Z(q_Cb&jr`-!%h~=eEYC|Igmr zfJb><=b|4PSr)eJC^2?uf)hz#huFZ31a?TG5fTUti~t46Ho{H@A&o{dqaTk(AZ#~> z7}`ry_XKR(($+Rg>OP0IIH5i6Ehq8Qa&mp{LlbUF+q9vrlhT$X&W(FQYA2yN?&*Ek z-~N7P2FX99Zm!2zGqd))*Is+=wbx$z=i8Hr_rz+OTk7X;T_ywVma3Li?3yRbeYq-_ z@>;&kesb$?#cHe9Ly+Wxib@Qne+_e}@E$}Y_~u#berqUwb=zF<6|@Zb(>IiQcTBd8 z4RvR5V&*5dNp~4NcsX}Wj&05YIAU6{yJl7#OLWQD?m8@zB{@!x(Q%9zMa;1Y`mqyJ!|JeTC$7RwPw;-=!w<(+*Tp`(KDM?l`#|i0W;o4eILYSN?7G;l=GfJz=4WHG zs|V)q4JBUn`C`IGuxyPV{%#T{NGACI*2cX%dt`yIp*5ae5&D;m*T=CkS&xKlPY)6? z4aCQ6mL#uFu1G>n$prpls;B>CCGr1(TdVMPz2)3Or^th=aF-)YeQTb8H5LC{b@3Eog`j;{CCXmX=53k0u{|Af9OKIGD-~Ch8B$YGWTn!J}Sps@2Bnx07@f zzAT+K@I1|{=l|+vcW;ort5y4>?`3>^;thYkr9@}FEHM_8^zU?D_Kj`jQuPQuZSs>U zjvfRGEVfyw=T7ICGsFZ1-pxONQ|?(4;6nZmE=fJ1aIi;B(8cUy(NR@53B~Ckwi=9!|igugMErdGt!Ih{b2|rq*wBY&(Recq_L3$;GyT0QA)lWiuFs zz2ROw_G3N2RN!Pz0L}0ECOWq3oA~TPAAIgBd!o;Jy=I^%(CB06u`~Dy|2P7LLnl|N z(O*AH_j<7`RDmafun&DCd88%YRG+wK>PUUEC7!I0Cywy)5icb1BS7z6c!XDN_)#KG z<3EdTqQ#{t`XlR2^TC0>Rn=9c79>;g>N)%Id%@T~+q!o$6@bs537mNIV^1tq zX1+*;(mHS^t$I#^$=DCTgGlr*)i^DHIDXo%zykXCnZWnY)HhDuv^ANSN+x1Em&C5A z`}E?D#8gKzv7jD*h>9nvuBmg`7SpE=`m^ZflEkUjcp`q}Nc>3R2tFN2_SE0haioW! zs76mcio!<4w$uzstoACLfRA_7w_yFOC)tQSj@VUONVWAH@s=K?Z2@g#ya{DC9$67@ z{akX@Hzraml5Md$&8@5O+*$1Yy4c&+#|m|+2L5jWPsDp+Sry)UU{0^jSxxi&>}3pE zUo-1h7q4CpClZ|Bzp%>2NwGT{?M-G zhI%|!nPit#^>Ee1-VZHHB;{dF`G#{*Er8&WmmocUB>8kAHhByW$RM`Cnz&a6IHEs-$*Y#Vt9sq(9RzAB!8 z%Yy)+VJMZDz**$jY>1Ue;zN81Nz_nZ-;nIti6dXBr*Fb@rLo=XV-t0F614%+B$F)& z-dIzp+C=Ksg-$j2g3St?7DG;OXpy2w0ULVyZbaGQZkaGtpGw9iw=`leIaa%bln_tV zcXZS{W_u@a60Cb3a@EJ?EZGYMVvtPXEfvSBrzO72XWwJASYaUcb{-VC;T(BlAU0YT zd;5}DEhSdS!oxqH4^()w-*U2zZ(R~nc0-|*ll8q82cFY7vp2mH_Ps6n)5@&+)3?E& zI>%$)%=akfNavda+s#f74>TOaWAd#%9TcF|)S>@o#jR4uYsQ}#ySKTDO$3a{!(@W!v~Z|^1jAE7^Yszx{A^s0V@>yPhC zAx`DtD;`f_bmOV>wHVGTym!9kDBp6F<#%37Im)7_Eo93@sYTJMc~<8_WrF|ah+X}z zNZqe}M7v+jtSs*2KmfEX6=!z_e|FW9fMfdLLUMd5#6O9w273=s1lF-%94Nv;>yR>W z_kAv+xW;4;d>+C$igkBrj5s^|_1YzvB0Can))V$z}Ha5OCXn2De`s-dGRM9 zPBqV=Q}bIM;Vq9aGmp?s_d^wWhy5FkLaxAdaJP2jroRCs&d>UD4Rx*7Gl zOCD*MCcf1Ty`p_1>9$3iNw8w;7(Z=&IeKpkIwAGkb31jw|JJv}I{Ldyo#7Ry?AkZS1<{`q(X{=0;2DxMhk5`JTWqz9R9lWMjG2 ztogFygm5C6Na6M|E`+B+@p%iGNUphQ{)%M0 z2{FP1$0m)K5;XcNH1)~k)5!*Z878|SMN36Bbv|h*6?=dVy&}?x4b{aKU@-@=55l8V zqNj22VB^+<6FUwXjaH3%aKse!j)M~$TKF_BuguXDMGogy-^ev-u6l4EPdvfu)n(&p zCrJ>^wv);zSK0%b4QpS4rNExl*4P6BSe~*PAo*9dg0xJAnlwR`*~Vl?&yk*kJ&z(4 z;T;t&sg2=OU$&N>CQ?J0>}(p(a) zJtjMzuD&kOa2ticP^&LyplE!or1j2*+j_{7lWNH_h9-C}`=8(FF?1&9A7@D_6b=YkA{3_7NM$+ZbzAT#&~3rvGmWVIzo8@Q zwYFD|{Sk~YjU7GMEvFHV97M=D!NpC$6&!q&-3Of6iqr~%&;^|MzXkteBVr<+jqghC zO>O$XaDBsl$=Ja9*t_f4?a?z0cp?m*2ZInC5Qa+lHjLeGhhs{ndIotnRvzLy3^Cu( z-PpH$M)21C%i->RDt30I8-=6LpyLRqa4##Kg$8;n;`9HgF6C0*>W#XX0c})h%c0Z3%>U* zYKq6c=q=fqY-~*8>fWAIBHIxA@+>Nb;(I@IqFv2oa`AibP3`Mx=xInbC3+TbohlMI zB0t4L@QYk5d}C`0cL+D8ve{HmBW^NoPDwSkRP{7sbEUB{cFt>tC=`1pds2m``>8i_L?J&865h0t%r->I%@K&AMi&U5_$Hu)K#QEoojg|?_6akGrOYWchuYb z%&csEe22M}r9Fc!9myt*MiTMZJD2R8kOlUKfvKookH3|5SjOLrDG{v@z%Thzxm0ou zdb4;W%>5=fB!Nr%U|>Qv!Tmjv3Yjj37%eOFBIGscT*+Ur%jbG+S&96QIJi4C?E<=e*g7iHVaQeFGz7tJA0erNlH!XJNrwhNn@G$4#T~nWj;X|DL+01vtQgu^xZ; zUr!4bZZQ038yaZ^$`4a|lJgc~%@Uyjovflgz9x4hpfUB!jr&r++1P`;Tc>CS*4Wa) zsN|zGBa6%GAr8VGS^EBmaHa!?*l3{%3q72y3z$fkWX{rof*`}h-k)!}<&$x^%RLSbJ8&Z8(FJcr*>zl@?V9N?R;ani$8JNG8XZcDU&?z1Rfk%+J4qb+~o z>4fC`m*WfS8{+=)zW$|Ku`G&Qi9}N}HT6szjzFUl4SPSkqNm5#b0WSW6`%LM*myIp zC%H-Z(pk9V9n1DYv$_#Wlts(9eEPU{na?0Kn2Pho1$9Zz(Bvm6?-jAJC8e1!GeHVf z^?MiH9QU&t*Q@I8DV8agUlKe}7Zhx1F^d`#%!$89N0&?0q$QbLn%tM=i%Nk(zi4}1?PjY=K1!D;OyQx2RPhITRI$WGe*P?w7ZluDyyn|gC zU;HXP`ddS0*&7+kDEL3bU>CgTKN@n=2xd?4!cN`LhvCVFK7SMgATo*}Ejo(XFbS{? zlf*bQOzQY#=e%{5PzO7R6dCLSloEp-QcH&1pwoyNti9VmpYxYG*j+a()zTQBYV3$N za`fGT!GTu`lP!s!js%WAc z4NbUj=YtEdM{3bmOJgd%x9jO;Pd8>;o^Gsf3h_tc)AX-r>(fss_CB4!kcSV5zhKpR zUSu;me}(rc)aBpPdS_|^uXR=Da+~n<{4Zzkg9Qhz*7`=tCmrRv=5ik2dI-|3hu|Zq zz4@%H2{&(_7|InE4~?|YOk%peqdQI*0$i^FKi6yU+5He3I-dIsI?YlJd_#IutO+*{ zuZX9rlO4R?*@i`o-2({C8gcQ|7ykSv+@p(!U>+#Ek3LlY?9B+slPz15TM==i169Pv zX>o$DB78f4q8(&BjJFk=&V$*(9eY#prfjlhasA>i4{lvCft{o#BGDo!_dkpPi4-2- zqmclsv<-tv30MzQJ=)Mgmv3D?fSdD^Z4>o)La^mv%cgn>`%hJUDVuEAcQE-)E}kwH z{Mz1R>f6~^wmJ6h^$EH(3mN=!`8;NQQ}vM*vfR^LmAD5F{-x;D!4>q&Y*&1l{``>s z(4^;zL-gke{o#bIvCj34OB-YFt6L%Kx_C?piB$8%Jhx~Ajb->Y2mbl7W*hdX*lvN-R^cfaCSJ1_ZQcGwBo&wv$q9sFkG zc!qv%1x_Rqw1QI3_4v+7Kf!3h=Dy)E7dps}dXSFKt5#3;WybV3#jv>PSH*>#h3~27 z`p_&I!)I509)BxoSg)W()GKJIpo(tZ=EdHt9r*ID&?bIQhMb4{5@#`Sr`<_{|dB7np2H)Z^zV z;ZASAE}7cUcwGu>4RM}7*Wq%B3h$4hy|=;<`-$dPA5qW1ad>@nrPLeI`G$K7gXl2m z7QAc%s8z|PxQ4$~srsgt2ARY01^4R}u3rSUzAD>8Pvp;TZtdA6 zl2nPD1}E;7^e1*+@8Re2h)azARFOPaR4=haeJ_Ao!P)qaGW{#2R&6+o<*52rT{NVA zUa`Ka!vsH+mDN(FZ>i$*pzJAP_%c-g9bJhezExHF1FrZi`XuTV>#GL&ydRDFJ#r9p zebr;h>IS;5bMRR}MB}mbRkkq8cOu{-h#u<7NUci!9DiVKvC6rg^yf+{V>Y$G?5d6` zs_1OoCxQD^zLcup8QV$_Vi0@(dTrY(#8E`V>YE57zi4n3t4?fz#b)O8r<(rE9thMT zWz|4}sGEoG zRlK?bzXp-Q4QKUDqI)!2Qp!TBm<`6M^~uvpyt$<+zSjiA@l0G}t%WChnsAvk#f%kF z^MR_C7OUUhM&p7@)*2>6U{Z06`XP@=oT*}}RXV1ZzRaW~jI;T~(xcbEyz5pbkkZc^YW{48d z2v><0>A8u>M$7}DNmNTj~c@ zu}PMv0!k(j=^P2GMtMR`m7C_3*SLrbxq`yK>+F3fQ}aS!p4ZUkj&PXfDpf z%qTnea4z*q`Z{}kp(?(9LZoE&J_Gu6C6!&h9((NTcTsY2DLPzyUL87tM7Z@;|G6P9 zc}g-qP{n!_70_eMq}7t&mWX;atq}V5Wat~h!?IkOt5#4oXUjbf$MBII&=ss~l920q z71aFdVNcGC+a+MF`UB?}iloKx;ZML74iSGVp0sgOzKAOX#2y&%fBfcP4{p0|mpztu zVp>_@{n5X3j5vLa_4-ytr|16@SyEctn_JbZaiXoULjO8r!Y5iX;yXbx)AHw0v}meX zc~ZoSsH1&5G6mx1=1JA>0|&g`m0S>CJpa}Ow=^tz9}e?3wk8`lCQ|(W)&&zSiATv2 z$^XUJ&)MI3pwKAw5!@8Y(}$1oS(AUnded9ehs!yAxZGE^UB-3Z-tpnZ*~~~LKh$?Q zJ5X+DWMcAi7BG@2DEl{dyAs=RMW=x-OF=)eLqM0&n7EbWeZ3>PP2@b>CD-7K?$j!| zY-MZlaAvj)hL6Q-UnsM;zdx^QRxE*hcI#fq=9b*?8SZ*2x3Uf2qFGHvEKd(ZBHZRxdkxHs1>;2YZpKMmf_?K8@D_&RqnAA39Ny6CNu zun=CvzgStFAG(oxiDKs$^&9X~zDF^)h-~H-@iFWc!64{Y;Lu38;v*-14OnKYf&cUx z`#gjSy*bnhZ2a%RteA;7Ukh2Buf=DT8?Kbx)xss}u4-oC7dE!yBng}o{Z?nZp`{w< z(^ByjDg2yHJ$w-!(nw~L8(LT3J-H!%`U{luG%kxtekA_wR5HGx13%mS1^)iEL@Uz% z1fN?{J$sL&VpktaOyDWrt@z$py#T)eo@oDCBKF;n(fGsnSJG(%7sloYkPgO z!Z(47Brk9|_64bLg$_Zzu?{#o>iz_NhLqg}=DWVHu&{85XUuR0Hl-#P7VwhJodDw8 z3Bl#~hVNL^)48|^uF|}icr49uJE3HJxfOIne7wVY$pGj=X7s^u6wypBY1ZfhH@)$ zK&Zc)4Arc?)IlU0yD>P}h)y3vCr71INMAuBji8kuR@<08YwtHFcFCe5EkIUOjZw05dcVJ}j135D;=SrRbB=6`?vCX<* z1ZH#i7&bH*SJ0`!sgl1^rv|4%miJIIvf&l0nRSq!#K22@%gvxycxzveZ;4J0-c*(~ z(~u@O*Dq?E84p9MZ7-?Xz7AI9wjAE#KOj-I{Hr|6}(x$KHv`l?&BFE=GrHS{f*xE8aAA;duJc)BI^z0BFU}((h z>hxV~DZl;ydrP?-(W9Iyqgzw%!hCIDw;OzX{}4Rd6*w^Fj(nkYLPxuF$hmj5n&P#y z_&jOg{wLbXihWPpe^dSKxb7Xh&MmxAK|@o_#-t7OIGQBVT9UB%gl5!4oHFHwrt*nC zU(0%rKA`_GI3}!0;cwAEhu^-0v+K`{jmNboW1TNw7+KOq_x_V-d-)l9hi6-eXlWK6 zVgl{LTCMaVqY(nDaNfV+HOs4%eJwZ5V;);>}3=m^QXUvVl9_$HpHdh!bJy+4H8@>jy>sMc%c zwa4q)p7{C7Cx5OI*y460{hlD~S;;pjZvlPW?f4UJP;rwEXZ5=$ggd9Wu_9bg2-o@7 z0+(Y%x-*rt_k6`DDJT1XZrN*gz9@ialT%xzM>aucfxJ?TVeDR z=@Kv4{S!4$UQO*jzy%ArsNayB%VAruJTHKI73bScx09Q2TfTm29LYntXB798vs;t9 z;#)y^to$v1FMJoe@~uDI5h{O=;!ZnU>l4*aUWs~+g>W7JAb_01S@~NSHwSc*^MvAR z6=(9CQu?L(1?8{&N6A6u=>eTly!I?1)* zJSX!+Q*fQ^24N4mQu;slO~KETw*cREh7+CmzM{CbKCbgxd^Y*ozawIxh&o+QG`%r}RQmet+Df`dpkLF86(5G#$Tl zihHW4Tp7-seE%$fa`iJ@;w8bA(>MD!)Z?7u&bV@G^W@)5Psd-Dgk_p;^z%wjMCfyV zAOvea!*?h>ihrmK{a6|L^JVBYKP+8tdl~veN;i2-AIFqV-{}RvyW07C=Wu=?_`29fUhn9a4=Ct%$7|GwQ^g*Tj z`6bS`{Ld=Rb;Xl{OVe>ADm#O}QJ3b9= zk>XA%?q#f8)2r>;u{K^PsJSuG_E=?Xa@NsMUP;jI1qagT6kW{7LPNy@!cI}^Y2iu1=~)0YTBdL^89v+!H!6 zZbyn62)CzE%B@wL(GMuy^g?z-_@hd%Q@kJFh|wl*6AK+fs|h~ zKb3m{`P+4&zr&Sl`tjF82zNknlMYv`AHr4NCiT8l`w?zZaot7y{Pilrot_3qdLUfg z?NaU`swiG<*P0$;4Y7bCs2vFZjQ&!6HKU976^L)`yFAZ+(LSdQ>CaPQb1MUUNuPx8 z>=HTlD_>uZG@}i7R&l2t&gMU|4o%gF_Kzv>x8Hy6botEwB)*_=op3Mf??hLNIM7F; zq7@StDxcC{xlNUH9$$@rvZ$ z_A%kpT7>iCV8Tr)ZlS;f{i#9*HqCGHol2|T9KN+;0|Yd?sO*)5mtFc8N7dL*cpzvO zhQGL7fOQUU{kcLMqLy#?x%~os(fPqWv!1AZ@@=$%bs|te4e|y170G|`M(o36C4W@^ z)Q*&1Gbrho@>hi0rnqG)pYO;0_=0eU6!(b3ncZ)5_DHz8At~4QCuX<4KOx*v#q~RW zhV$bj!qwa-{I)rq`SClsT+>HRanb%{>Bpx@f4NM$>2vvxs2nD5SdPPrJM835^po93 z+mZO5#NNF9F7QQ%H@!aS^h&se!&3gU4rh9heHi0+UUA!sa3W_ZIo8%;Tpbbqm-07+ zdt7m2Mf@e+A$=3BW>okc@NwI%|1%#=pRT-@6?Z8+CVp$jq&&ay{( z$$wID=Y9Ei1?7M0{+a3P6~#3>K4v$*e=V!+6fa1#WGx<*|F6tjF{j1|rUah?G zc)Jo6wDj`@Nm%6Mu3bm-=P2%w{th7JqZi4~`ISDM{8azJ`Pe5>e6!P+_0tMzNMeo`l|%S> zlLAaIHMoAW&el8BO=)bK_4*`Dz{%ewXS8 zRBo%{bhx5%wc>8I6H0&TA>nh(muraRGCg$utfZfG>83Y{+YDFxalujh(90i(WIx_; zixhV$`yjariYr$?)7w$S^_Lije}!8>>I{m3r}exH`>*H_jlOfR*c6x@sQ zMs{N7FD8S04gbn73h-<(e!LX^tH1Q>@W(zS_)f>a{5*i{<&^^hoGjM+Zv^Ery%Zi3 zyl;orZ+$;Se4kZZIXg6d7Zi8e>Dl=C=X{vop_!Fi`OAVUS1$E4;=1fVszFnFA#jZ-}|G=$?FE!s5$KT|Yc{|w=;m#}0*T26$K7E#>?5spa(n z%fC(2qxnf6l>e}%m+OaydqHvK`~>_Ggo)#sSvasr1P8ovtJ(9&{D-*f+q z0L!(pUj>&Nz9k{`Wh3 zA%1mF3+`Trv-b7R?Go-G#g(&bEBCnKx{LVv>$=3R^0QLzbo`bpZaRLCOv8`tj> zJgIa)UJcAQfO}4HlSMf3@5ZnB4~5@U5l+Talk<7S?Q?QkeJdnT*8IkI+kd+>U(=8G zdBM$f<=3{8ek^@%nRF{Bq3NEJ%i8;AUB4o|CB7hlJ+2(<&$1qC^*pY)dyC`bL&5ei ze9a#TUtLZJj`wn)Qp>aY?D=ECpKx+Wd}Zm&)zA~JK8cF;P>9uc@V`p}eW#c2*X6t6 z9#PywLI%$CBIklk{^~CZzm6IKwq1L2))RA|d?(gvW3_>e8pC&gMeyxTK4-5Ih-i6M zpTmDDz=ckZT3$!7^pl$I*QfT5VEdof^f`Y1Rl)R&WztO#HD{#!oXc-|kYUj3HL187 zS1-d=vQTF!^kDMe`xlb`gp=RwyFvm8 z%~yl>=(sp|8{)ygl#Kfwf6MQ$YZLBq#kCjVr1`ntz@1ZE&f!d-qIa%0a28CZ_AEzbGG&w52Cj1Y${8q1CZq`!zn7kc+Tk~CX`D}ju zAm<~!6Yi0-!hcfU(9h0Pw>|O6Sx^1~J#$vE)lRgKJcO_O8v$NQ&&*eGe!Wb85`S3v z&na$;E8pr@ApyC{Z}@r73s8rhfd8ntFKXu`$C+avqxWPq^y87kfiBN;mvz#XsW4 zBlo;u#Z;idOx`W$qxHA;3fKRr;wT@z{Bb0#_tT0yE3g1gma$CEr@krWzU<^YKI@4a zp1dCQYI|%>#eWMv*GPIe{DR=?B}^o@brTH^Lc#B->K<-JIVN118mffCq4{2RQze?7Hn64osDp<7euZz zML2&xLb%%R&kT2NhPdPZd})4EZz^}sOM=U}_O7e=H7JhsK^zO^Q&@S=DK0wxT6t$Ry{?Flzg|b>T~wU!FU&5)Ul4!7b^J)=TBiJrzDMcw zonBV{A*BcGM4!Wx{e!4IQ2y2=&LnBRTIMGGgXkxfUTh~g)jMjvRmvy)BNs*9e&yr) z3t9gnxd?Ybaelkh4wAi7Jt+O~zX+dls&p}Uc|0UubqnX$F*9HgG^sjntsmlv2taf&2W2kb$A<3D?;l<#{baOf}d%-&b>zPr(;rZ z;Q8tcfo65`oUawU?~j~3hfCo*uM_-vJOe?mwrkz_m$t{Qjr{>^hadE}_FeWa!FLFp z+T|lQPEdR7(ey2TdUvp2oz?VvUAoC9>qf4ecS|_|f5`E+*+;*oPZsg<<2{n+dByE7 z!uj(B!u8LS@}}jdIA1Qa4}U+I_|@Df{FWD$D{-;avt4l)9IozxpuU#9NBEHa(97=! zfphXGZ=2$#tLFe$T|0Ct&iCVHZ~p!um3vrm-L4*n^W$fhPjSBe8?KYPm)Ym?29a;N`sQYc zn^N2{C!gurU!N!WI_68c)8Q^E?r0G|KQ1ADQwxM&IULy~;nv#ASL^J^ori6^l-!j6=vu7n z=hnd7v#D4)@ZHU)$S0A&t3K?iQRo3YUe{ZYcFDf1KKVrFXYUdUQOd z`cr!QN=a|`^Sk|EO5a~5o$Q{{Piy)!F2CtRmbDDGXO)x#mGjH*|Ngi|{7xyZ;BZ!d zS=KkXn{`1Vz>n`wvGjeKKG*T__cy4V$2HxLXZ(F~O8=^+xBB@v2K72euMqRgujTTi zc0=-XrqE7`KkfL{-EaITec>9>&oMup&&yc;uWI^nKmER7{(W~`I)7rVq@VEf^ZAlX zUfkA|?~8BV&>3$V%i|3fD7I$?hDI{+jrg;Dv;f-54PC2-`*Abd9UJegTlK*Y*4@5j z*^1h02&ES>A!oyn(h z!DnH#Z!{;lR0?L8_QreDP<}6dXJV+}uGOTfWQNBIyP?r6m=yX3y#jdj=F+6%Xhryk zBIsu=(jz$*VOJhfu@J$+Hb5PnqdEKxN7n1Zm7UN}K9gq6KuN>+4VFS?d{+h)>rW4j zjB53}#xi}l(j8jw)M{AqTmxddX=HPzFEg|=1C0cJv%(vMy!e$2(idBW-D})7Hr7Fk zaSZ!LM+Q*QfuUT+5xrye#QYZre|U zvZax4;`TIYsPT4}vd(VghwwW$jb!Ks(=`(#eO`VtO>H;~bxa~BQ~_J)+O#T_-rT;y z*$iYxwY-su;q>T08u}gvRusJGA%%Apdh_UKfGuqz>w}48 zc6zzdk!&6R3H7$LiUJ#h`FVMWn=bG#0;f?5+6|o-EOzzo$V`l}TGD7*6jbU4es6RP zneyJMwvFj^?dk5G&eiFz?sjh=H`)t9`X;E`w|47yNyVq|P+1YXi(yG4H?JwXS~uF}+vd;1FL z82uh@lg8&AUdc5J@@f{#|X$%3( zabg7CC%2oV8X6fd^o~HWF|rYRlz1Q3M0Wdv}VzNV7k9 zU~~jo#zx1zLDUH*ML+70rq5%!iL4r*7$Uh$YY|uTF8IG-k0M2qhDo{UJeh0MFQvtV z0=7~FF#@^ouHERTP!9J6G-P^sJPUbHTQa4gk=xlD=0-=ywnOP29FVGUn1+O`jwFr~ z>8dH+m=-UNb~D!?Hj##l-klrD4x)nqDOwLWTGsH+-W-bQL$A}i8TYjKj`mfnI$>?& zFdDMHiKR{W3#U##9iB{#BJx`y=uT)c6gWoe8y7~MZL3nNyUoT|W28YF48X8xWSHQg zoHC3R@>=j6o7*->WA*jsa-qyYR2jJY)0 z4R8=aBSXOWyndD$iSS}3*E;h#7JpEH0S=jwokMvHg#FYWEXSI49jnuD#PH7H04t4X zw|6L~74D-DkH@RL6c_MKfzWN$VDCtldKnp{Zwl}?W-{c+C|+K<8%C+-zIt*|Z zn^tdGy$VW^UK-7H_h_D~F*1QsgiWn~qOUNTce1NvE_jIcMhfDYNGD`2q&H}BG{==E zV}yqu8gW{PmW5yT7_jm(lWMvYOXk*~4v3A@Fstzb28v+~=-Tdf0UgJCuv3h%6XV+l za=m2CJf9dxqhoA9pCng|5J#M-^b$ywW^nIFe|{8001q+Ns%b(8;9yyJKrCvUhR#b) zi8g0)84TVuQA{^ACHQ^qrmpVvcwc^KtPt-TM##4qktc#264CW_8{o9hqu25LgY_nJ z12;N!t^SA(D8A>BS`KC~P%u$@v^W%+@AMWBnpsEZ>6Z3^ahWXeU{4`&xH%z*Ha>NF z`dLXyr{PLQFZ8V2m!S=);Ui;V8odVA08c}PnjS|4V1Wo)46VS8K*2Ry3L5d9!RmY- z_J)9OU;wOrItFGpw^>K=yYp&XexSqZ5WaEK#+4nI2l(EA)JW2^NHWI>#MP^}bfZ|* zsj+Ffn?MH&wRVA#MEWYSA)Ls<(h&xd!BgeNn*yFkoSHQ>_vd0)vd%ms;trlSYQJ&~ zktS;&>n#ihq#{*t=<32JRvots2hVP-MhJ{vO=A-x37RrVsF~h1x+6296A>E?q<10s zg}+;j@LOq|Uwx^ZRQ1PK0LN2Ka6raN5`VvIpDJn#XsQ0f^aZPN|i=p9nyqqU?`L8_Xf*IKHNP# zh61@ooIXh0yE3^Btg{8Q&Z@}tuk0Nk>Jz-#&`JzLY!pS1bSdH4k3>{Pm0C$=RZ31L z7#garug}*ZT4F=*nEP(ls;Zk9A9Oig3j`_z_dJr>B}%t02XB|@cMP|W_U8L}B*JfI zbz%OuIfH3#|0<08n1!LX`GWcVu1sNL@6MqtyM3e-5PDG1g_Qy<@nKzy%m%%N7qE~S zQ`BLo3WQqy)*N|E;s?f>>n{QAQ83Q}>7@5*tyM}0WF$?`@%hD%wwTw0d7H4|%zHQu5 z!WMiDZqAHP{7Cesgi_6-3F?2330%(49!)L zOvS_INCjABh2AhC_U+gOduA~vnHQy`2S)RbOskyRVag-jv`9^|ZSQ6I@}OmzfG~_> zs-2S__uDjeT!j0WKO@Yt!mw_cM?{EqroNDXSV5qUm4u`srJn*?Z?c#J2HhkCfB0gSk2;PJmO((KrMngrw6v{ zGBg$t{aSHx1KW3`cbSryLMp+m)_oq{iS;bvI*5J;OnzyJ7X35GVEgcRP`#Xl1+Q=&xaC6@p=uzJw_|}WjT!C) zmj1-|-%YFdZM0@c4uu9H);T#I_p@;!n+=#U)sUvk+W%4Z6B?7I*v zG@x}Q>mOKv<^B;Ys+>xSMZ^qh=MYw7sSa40;H6~PH92r8kv)icCT%TAp$P)~btXSR ztLChP%-|53H$9x8AyAwTvUt7Q$DMr#bhe9!R9d_nhUZKdd9-mcc4;T7IxQD)HA6xT zL5}S1{OIeC)SZu~>1G=3)t{qZL4+C5!iUCC+`^&O%4f!MyVaabOf@B$hWGWQd(~@^ z(-<~2lFp{ux$+819WR9YQr6@E(`*4jsP6WmX@+9VLjE!KphN5;j0PYDG zmYFb$j>7iELl%?R1&0lX5TNw&?0B4lNu7OhwX9b~EWKEzB|Ro>jld0nD+QuD_F!g% zZm!kvM_Xz^-e%e_wlOehBiK{q;9?jN^dN?DV@(zQ87^Vdz?B^I?G8^%8?16&%)J`6*deDbp%K{b2XNF7+~{Pw zlXW{8deIwX)TNs9+Hxtqt@h(7P7e9#aL@B?Qnr<$GSXN;M~LQ3DcFo90sDu>cX)+i zm>ax0#hy8_&v1k`biYUAtLca$itW48aMRe($+EveC$W~sIKPu)FY}z1AhQv)50x`8 zKFm{gOZ0~-kF6e48tk%S*INW48HdJk$bwSEDN#7Yy_5pjKCHLGpN(RJpB7c=gA~UD zI&HLy1EIAE65nL&+Kp8rTh1HByj^@EK_TEprtXf_5rR>KBzYc zi>TS7LIOH_{li&XKHs}rmU}RY5qoxC%XjWD0ltVhFl@1(r#mN(H6 z1$yG=VQuKK6ggN0H0%IW>Oxs&WPCL5w{3rh z7Uxl^T?8p%%^H0XWH&*=N`ZP=m1eGpqzmcM9jt1aGIX!ou)3?e4U6bqJsVe*vXmy$ z6-PFrnyjcM3)eQB&JGu7Fkdy?FN)>$p)_qRx%dqcSRY1GG^d*%@wW`ro`vv;S7?!r zC8E%lR?sJKqyXG`t36yFtp_VYO;>xh>46$2V7%5oq#j7c8C~1K8CW*$+tT}_&9KLB zoryl~_G}PTx1ug5Qa*V*nhA}NAJ|T_KC-aa--qs)Y#STu#>kEyL>$?u@fAxF98Al) zhx)3CVUM6lYs2iwEgC`7!?GYxE!x)CM-GA3PIM_&^Q@ANCi#elIo8njRkF^o4&D>P zMVl-kZ0Mc53%!^;4li_W+0887_pSVuc-)aGbYOPhB@1mfEpnRjO@<{0dS!26-N*or zTG7YAN&)E`v0lJ$A%J9;M=9L4leTWd6nr14C0jkA=l zCY_^`S}(1LDrj{+-z9+-(V5X^TXsVn1>JZBUgK`m_a=Q`s_)CBm9S2+3ghD{K1qX) z!s9$Cd5x@usFKlSSgv+brQu-UxgJ1OsrY_0CAV(|eNor`h)(u_MVBFMVl?)uQ5?v3n1?`-wgP^RaI$E$N z@9^Bxp49LbR9efU(R6D__Ds-?HZP8joo-?eF@P+%e+PBIp}f%JXjh#IJ1`XI{=oC)U& zDGVbjt#|VW*)e?G)is`|@$2U0VjD1{5MIV(a-iL#q!sLlga&EZM4+%Ik^pdIJP#-} zz=Lgowp!MWJ1UTCur?gbZ>HkQ6UiVuY!HMN+GwOgJdl6=`WVL6FjPTr2uE^bSYD#( zO(!I#;EFogUA&-(54YL4J49;^lZYbTAKk{?rP{s1aQX!5+Y zZ%$?N2O6_+RFMkCOgziGc|$;~;}bYt$i0@tBs`zkGdC$`aG<`O{wAMCrHRk=cIUPP#h6B0|+}7XUmG9d?htAgFIGq&_@;bM)W<-*PN(duHEMOUoJJcqpDO}1bnk{AS zpi`>rc(=}_6y;IxU_8ksM099L!qiogmQ3X=fiIaIWOj9tzEnMOm(%`LZv(1DdBZ?NLce?xmD}q^vNq%<1Cng zq!HXf5(?!UT&l;JB3A1lCPv_JFuV&U&Ai4_B*40H<|gMyqtfwApITYF03UzajuR+$ zU?ZA=Dnd;@WNJ$L&vFDkgp*bkJ);_tAbQ;SjWHr81+1w^F~0r!mBE=}IrUwHh7oBU zd?Rw~xp^%MS>$FOK**P`MAyQxNnZQvM_*&hBzzE#R8Pc-Qprkag@|`=_{0s{4RvKQ z@k{!anRYc2IG`Zw@Nn3C+D%OoZDWBq_qjKu=xAA&5Q7>ZAcNluQ67lJgTR%$5pw7{ z64W2+cHkM!O%n&6-35;G$|f(Fw?G90J$csf2L)H~dwEh)P zO^BHZLByFbg0e#SqveS;OoxJE0rA^Naz%MvvLNXXPI1w^caHS(6Cq^*ZIZkedovW0 zAd$0`$eN0p<(E8lC&)AZiUoo&Q0dv_k^ zv78ERn?M0=eLFS{Z0>i-@<;_1)vhs0sC z<|k269Q6h|%j-XTVg*wjoG>|sajZv+!fvbG255 z;>vnm#uaHqa_uD)7B(T;!PYG(-RIQ3tH9||(LPxurD3XuX&Z+=!;upGuA>R+h0HWa z*+EU1rZ5R9Y9#Iil(9r5?)J}>SPiX+p!K0)oMIJc-%V1E5`sLqScOER=o9t(bWgjAfj6ly8pCtZ-#jxfn>MMs3=eo#Uu z>J|bXfm&N1Dv_d0AJi(^$yi94z6yqA;J6h*C?YGY(P4W}Wgu06iG4NENsS^qXH>8_ zXv3OEf%svY+zv0*ONx|9g-9X2#^lv5n+DW>K+zbR5Mq5SM$qc4T=A#QTe2H|eeoTZ zwwJ;>up-etnvxsowE&Cn3umvp>yOGt>;Bdq`UzfiPHMcV}s*>+|10|ZzvHEikNTN@+^V|lD znxW+2C}n5SgRRdz#LlfGdJpl4xHQ9|WUOXHlqSwdtv8y8wM06chGVFji%SnSpR1BR zw-W@SKwei1(sYb8nOOGM)h1o;!5H%bXbYc66GSc3B5Fj4yxJ88iB1g@PE#xNi2^3x zTmkM&IW&WGC@MglE>7stehxJ<5zEM>(;;Rx>=$D7F*CwLwXUw*2IKOT_rk}l0ep-~ z&BD>l%1?=M4kS^XtiT8vvp!4N&NDurA?M=NKtph40sxJ00~8d*weU&WPQ;9})5HS% zW%OPAqA_2G^LM=3qN$rR?2QyJj*ky&U^Uo}{Egj6-{#DKWtU|HggVN~4(Rjr)1xg0 zbL5sC(qP+dXka%zhE>3xxouEf4MaL)oMzWITH}akh>5Aw6no0-PEFU3*pTq4L zMHZJLfdu5y2PG)1iLjJr4@kz=MHWCv*BlJHb40FRL9Y>pn$0R4XaHS4#)btqGp+UV z0~N3rLz`LRxeF~#pU5c4)fai}q+lb3vXUt38v>GswLuy!s!SNd2l;f@n)wznqj@Jk zXRaw2SIoi(=ovE3h3d;~FV-}xG0qpUvg(PsxhhKKis4upqK9)(S>*)35q``iP(taJ zw-ULUB+~#rE6hi-G_R?i+L-1kZ;;Ig9;8&84^S|inP6PCU=lnrhK_Q{tLVX$a)~xN z=_t@G_j&lPJz5rmAgCXk<9|9(V2mCj!~CvuUD~SLnXE6 zacxN+tGhJI_KWrqc?Q1GM_8gr-HE$VSTLMwkV^Ak2zW`s0?WOA!EwJ3*bKDD6~uXo z;IqLJW??#o6Esl`ZA5p}wP~Lft`orQj~{x2jL!7=kzhV+K;5E%PL5;SI3?4M!wRYa zhR8`qj9qk;k@m@PLJ_Wqyh6{0_U_Rx*?XtteuT@|2=xJXj)&68ZKcz=k*g1Jj0}sf zQAsQrbkvU%8}y(&ZFf@*dHC~d#+S#?b8KF|cNbNWipO~kOuYkAZt$h#2cTG0i2lj3 z(Q-a9XP)gtb2|?gKT2#G;ER zaMK3j8alwk!)GV_%xFKxFMP+t*h~uz;v;x^G@HjJbcio5Dxw-`DLC?lZ|M+iY3Lgc ze+Af&(n&q9Z#5rE-GCc=aI+OL*wu@hK=1@=zlRYhi-8oTgMzU+7|=5gO+sQkCM4xK zRmkX1{YehHVm3AeZ)uGas+>abs3=Zxc#b1i!{aL=aNKP)-+?EaUW?BXHRAXUx+64B zHIh{xElKn_Oe*B|_xk9RP8!V*o4{!`u@nqhqkZXt5d=p(&l&5@W2qhC3kc{tbTt%b z)9KPkflnSQaWkHd!2?3XY2Ao$l~ZDL;slcMtT&i{O>fR|9KhizT4bZ6kwY2WQq;Mr zYuy%X6yPR;EUwH*cdT2PzH9a7E_z^>ZVvNcC4GZ9{)s+8+-dI#o03|Viqt+amK*Bh zK5W%xiM!}V0>O`R^}P{VaOoQz+pT0+HJ*k`cin}H%1YHwDlYmFtkev`^uvDS3&m*A z24*K2%q#jb-J?N$X+P)lPeFE4A8&le5Z!%*i(znCAh&~xI*#K;Lz8L!CMEF*awi6( z{BUo9?o$-9j7+0=sFL&uZmUO6ktiql(<5ourz(hYEw6 z#tH~pm^RFItY0LIAfeafM~6kx0wX`)HyBQ#@xs_hjrjI5%Rmu{Wl-rv6EIz>_bxma zNB1S-5{i((8|m1VC`FON5jy2=-$~Xd^&u;Eq6Y=k^620*E{@4JQ4bhGwa_>3pTLzx zSOdYiXb#`#T0XM@R!~ToF77a*36UmTV@Y`pF+m@lxTBbfYa)v0P+ut+J=3H;3uf}x zF)-04Bb9ujb~8jeR0)UF$NiJ}u4Qa`%cjoN8?A4m&){OlOdl>^2{MtIlA>gG8BAM) zhoH=V;o`vloV!2^&#T#8TKH(!w-wyAK{S{loS@y#*PtXC;&E9JE-HYg_{uI^d+3UB zh4gb=9+ZRbnX_A$coT~VlyeC8Q0Q$;vPl?3;xk5GE(f6$(0)B=tO};!;;;ZtGGZ*D zB>?0a8o(kr#+HfY_?X8DV!DEjKS90JZM+fMh{OgquA$l7c6WOHrgaION!geitd{P1gz$kv1FB`#<2j6ER!Tv(EtLJ{)vNAGZ@PP9dPCP8T>>Ei1I$!~ zCeNDo^cq}8x4KJ|hC6TRZY~sq`zlC$E)b6ram9!YiwczmdHM=wIA00M8E|tas^T|f z8jA;{CIpVXP9+_iHg&GV9eTVChmx?KACOmV3OwlPB*{Lcg9{l5P4l?~)LNnX3YMKRlY<9TAeDhui%QJasA3EP!d^$K3Z+X>5Y5YVf}JM#aIVYd%cmKF zlFZckPTMlUN}yS^sG#CZpcz|3duIDY78jYs?<@@E+?5Gnj;D#}vD+-h5Po_|lzz#o zyo%)$D($tKtUFEGiHRy?r4v~6ksIfdA_f*x+HzSuSW*}qj&DX-jyWQNU+}`%Pv0^5 z!FS%Y$0H~>+>Ga%aojSHfsOPm`H#RuPah;7ZG0Np($*jg1k2Gvtwy#PERKtIgPy_1x_?D z^Yn|mp|>jEhs&sUt=hb*8}|uj+O}iR=3B%jh8rp9UpK;U@D^S>+-e8~wu9EjT`fhyf zy-)@>w+vpi;p@Zd{fgG#>V2_H{jJ1pOBC-c^SF z?lN@x6^-Io%)7Ce2ujR*PZ6EWwbJ{(^BV>j;19*^J_LG2z#isk2EiBGmC%drWGC{K zFL$e`t(f_s#pKpOa%PY1M;d8ZjSpA~$c?ln=UQzlFlzt|HujYPUY$sQP zPJC+Z2T`$M(As` z8~=&o=YCb_%kZ6E^mF6XUTc3%fK5X7=;y16f5%@6p;_tl^SwmhuXHVjh|K2!<)iF9 z`guR%|6qhJ^_>UL7k<&tQYe;!FJ)el^+2lE8f@`+a zCFQxsd!bCZuRI?v_ion1HQr>G$XTz+LrR}g`h2B}JU4h3BlUey@uw7jjpBbv>1UO0 z{_2R*FDPBZ9PN+uJhKmz_V<7N8E1K~f*53nYriAkyEVB^>GNI?!Xjm~Sm}=|KBst*{~E8l8v+Dg z9|V4uca1l9i_ovvw3N~lO2<#+^6R5Y?^HVdZWg^pl|HF-Yxgn4i_|YJXnifb`vl`} z@Lo}RrLggSMfprApBkl${8xM4kChOiS4Zfk&)Nw6sPaFq{B7hm{!G`nzkez0`4|wWF&%Q@Giv7OWLrQ<wvhk*rUafTNeaDqv6T$!AO0SLJ|3T^RP`Y+^?;_|_uY$_o%B7q9(5~W@?EGP? zIY>>o@`}>>6g{B6A2rD(gXwwB0+U4O*MSeo)30>%KMRz8CPKeW>CHC@pQ9?z3Z9ZT^!@F`{gCeOKuJSP9C#!~Xn^G-&lHoMC3 zH$LqaScT-r_%cvR4`@Aew2I$bhQG-_H^RrtJ-IS0|0ltR?Corq&`&G>$3Un4c!TQG zr20*z&yCQf+^fBW@=-S0U#|9+m!Y?op|6e5P5#aZ-P+yc43|64tFwVc6aKJ_-i-fK z-C_NFQT1c=PUZ7=N`G1LB8T~nYrGSarZLIzL)P0h-r#PbTbxi`CF8;#rQ5Q|yOe%d z>2+GJlrzse9;w$N;7i%F)vGcau9xtEoXTI>d#zgT8KvJ8DYrT@W!^kZxrtne%A1TdeOPxtB?+;DGXZb`aKG%D#5kF&kKG6{7f1nJ1!C&vKEy?G4Z%c$e zz-+Jf&h0EE&pdB(ez@GvlquKv^#4X_K6ST*`8+cXpGT%j^O?Fe%;(Ex_?RA!mZ@*Y z@08}hZAqB_xoP+xkMOs0Pekbd3_j%F&iuZV`F1P=h@4*{58B-(KuX^Le5rnI^*tG>ugO1$ zChUQi<9}O#h>z(q{Eg3{ua)9+jdwxiH*Pttm-q3ofBU%7=SJuUl%7z!>C@!gf4gy( z_s>it=YemOmUFH0H*Ti4QxUy=7W~Ohj-D4j3pB$YEB&<6ZJEI2yzl|zEbm__Bd6f6 z@oM*oek_;ix$wPG@?Y;=h{*Xj;7@jVR{7Yx-sEZhuyL067t6@=GV{5?tJ85@w;y!8 z_UXpW4;%hUA=EM2^FF2Y zPNiG?b4ckgRtx@ss%c8;4_zg6n?@c}`k||ZZhAhU^z*es&&iwjKa@WA8X?d;pI(2a z^v>&qe!fcR-%$FpcMILz=!;74SNf#D-8`-{sRVudSKv$eThnv(`&7UvpVeVLS7Cpy z6d$w0PHjiaW&HQQzcl~E8biwayUOr4J`0zW;&Y8R7AaTcndi;DBg{WB4gWpMOYz4% zWo?+xs%iLCez+7Ltfxix#YE2Qy@gSK!ge>$I}s_jYnpN&YA#joJnYkj<^R|;e7t07 zJ`2}{`Rpje$L!&7q`uaU_IvWi&Dv{Q$|&+)Zr?}n#ruqtkY`qj{YSwU?-Ttz*QwyYhk7|ZjKz}>t#om-SB;$WISP=f=j|6D`XP(keMd%AbCq8F%-F~6+ zzg_X27lg1(={-tMd`}3=l|IRI{StWlMa4fdCXU(od=7LfckDAFzsdP|#qa++!5>y$ zXB2E|46EaG)W-n<(?e>>sQglzZT3V zeDQ06^0D>X;|lpO(~I#Nng0!*+h5ah>Yg(A5#_&J_0Xv-_bL6WYs4O`+{cxEPW|B` z#s62On?KiP@cu8QZ_#+t`2VTWYyL|04Ky#V=BN;hfM9DZNeU?Uh2ec=&Fmch-v@)+&CG>G~z`_MqbDObH*e zldqw1*$$r)Ia@W)rxb7dV)rWjxYEykRQT*s`jm zZQ$Z{OcQTV`pLf*LP6;_fll^m^Q>y6uTcEicZnWM&Mu{&*)9B=<;@!fy%ust{oBtf ze(moH(A?Rlls@+7LVr=q{cWW`rE!F+-pTY z$DbBH-I`~a(l1^J4Gbj^ghFo!Vte+r{+upyF-5X7c|hrSDOHvPbzmru0Rs z&!?3BS*0Hx5;^;o{w1Zqe4o(UmHtD}NuIUZFT`3r?~1oceLH?2KE=XZln`Z-D)k$9OrO^UCs68v#3 zcrDZQOWW4zeDg9rV&kbIy?$6qJi5D70Z!i8p_#9Py4HiJiFKzpn z&|8)Mex;vPzisoWl}ew|dD%I|-=*~a-x5CN598>VpF9V8E&OWKAATA1x6?YC#=~{Y z-Sf^WpXYTRw_oZ1r1Z!CNeHITD=@y0K95KIz%5EYr|SmimCpx^{(X`2jM7&ty+g;@ zb4pJueaqhqVWHAauJof!4=7AO{*mGj zX#6=>>3^p5<8&YjuX}}^_jRThpU3-0#h+ayz*EZSM@oO{e&Mr4={G_lq#v8FomTpM z&`F=R-ndZdOF%ExA3vmg24lkigyKKKd~WbMBjf4E6#x7Z!CQSN6mRFyFk|7@FDicj zZwubWwa+O1!mUDIr1;M({i3#ex6=R2_$(IuGNpfq>G~z`_6q1^pS9|TD>dzEY=prS zi(WS}9qWE)g}-(`Z>iF~&kNn^+op8eAKb4T*Mm;w&W-s0t&A@!*4v@@AM3nKO7Xm% z%73076f*rhqIBC=TCOZVqx2fJXVcF~rWcp{7iH+*Q9dXCR3urTSz~C>QhK|d={UEk z@fe07e%-9}NB+C;c}VG1OH1?lP#OLkKqr0HMf91ra(4*-!^(eB=@(Ugm;t|jMd>wL z1ix0^yx(QIf&y<}RQ#Su-1`-!KlP9>IHq~NrSvHsH?3X%m(pK&kMwJ6#~W}yfckH< z_9N@3i?~h~jOZZc6F>pp!l?XurNy>Gvysx$1M9 z(tkzi+cfU7di{aY54rPpbkZ2jWzly2wcCKdlfrB{A7T;J>FihfRfN9gV9 zKi>m7$-hwTp-TC@pXvU-XQ$FvDW9*73m+RVa!OyO`ye)M?pFHgzZd)?TJFP2xAPdb z9d$tI7k^FgC$-$8OxG`gw^NEguk*nLlFj>C8T@xar~00Y#Q*=Qe4ctj80c{5-GFl& zBtvDE)%cm+5*!htgy37CWi=p%9iU zeGb$0OW;*Un=fTN&(wC{olQc!ssmA*~= zy!pKjrLT>Q<9$j$_LRtZLiy}cy6vZIQ~IZrUUyFL)-Rq?x}EFmRQ&HN{o+3g!TS6E zQ2IV~sB;y6R_QgWhiyuKN$Ia>{MoGZci|D2Qu@4==~sJ)21U+C6yL7&=YJpsYp=VM zZs!L~Z}%yEO6R8w|G(O<2TIPXs(*zD=}C@8i4ZmFwzM|XWILN|{z=6oyGeHICRwr@ z8cL6o*_qkdp))(f%xtpDsTfM^iC7`naLDnboCp=`v8RSoA!yKmRU!tBST$gQ2th+z zAxhLhi}iQ!{oU_--?zKs@f`QG`DT7|-+k}hci(;Y-S=j$v5VeGd@=2nxBnsHmon@A zA3A^9`7XBS)5M?nq5-~5eaiXNt-^hze}?#z8Glv2(j)q?j5yRx|9*)0RoWBRpIeA8 z;5~;Uq~AuoH{&PlBfj?wMtF?$2Z=wKnb*Hg{9*bPU8MgY@d^54?$>>o_`>&De_el; z!>^F}m}5MF;*UN_`WK!xgzi-I6!Co@Hr(~(>%`A~#Tw%Hw~3$U{?zsJWw@s$@?1$f z=JYoczjVU*yF524&Q1o89i)HZYX%PRvpn$y+(#TDK1uxaQRDCQ_X8I>_`O{F6z9~$ zPf>B`CPWV@pP(Upd6N9EjTwh7GP(;L7ye5!cJec%e}d<#)8zB_#P@N2xxPI=PrXaJ zOrE)K8H1DL(?k5}<<{~X@m<8P{IxZ(M!cao-vp0mmdsQ@qay!L&>h=CK@q4+R4wKI|#rY<9IFFtR$>;I3xdTu$d11|FPd*D_oigqjgqUcnY)$4j#B;L8-C@H4sKH|N!^Ea`b z?@^p@g2%(8zn$y2>+Q#g`}fOy-u*T4O3tas{~b>vCq_aUB{a_W3OL z5jpZ%?)Wn6*Hs=QbSoY-oG*Wl^vf7{^Ls&~#Gm>#<8y%m-A{bMM-4bbK8K0FaKv!G z27Q$H179%Q*NfjGemBS6@sARp&cuyBL;N7uai15TcmA1u>+{49{hKxLQMU6ZZ#KC- zm(hnD@#P<|cKZHwKyelh9&aN3-oG>O5i1rQAikLEg3pWJAU;7q`2=~LB<}Z%T+ctD zcu*lwPQ~&;v_+{?zT+grjDeLdun@s;{hN4#}&ceatr+|yTUCHR%I`TQl zeac>z86-Z}-=ik*Ijct8F5E9CPa@nbw+cDa3s_~|zpV_$bZN&Mlj8SZxM zv%qEF?e~xulK(TLznA+dpD*7fzLfs3>){XFVsd-oSB<~xe-60FX9e$3_eT-*GKhU)HIR6D`u*l&A<*<+S{xEQ{OILaB;PYq&@qWtR<@{Rm z*~>W6dGh&r(s$@rcM-pfxPPy~+kb$3a+&z#{Z3DN>-uw)_$i)C9wGlnh%bNI`pYn1 z^au`ZF&v`bWs;^Te;+YV*$9|19wpJWpIn`q%WB+z$Su0q2OnK>CYcGhjLK zC9e_s*?%`Ej(ZL_rq{bQ#7|SNmaymu@!|Wd{d7a4Ch>mu>t517Kzt?npn3ZDo5au2 zKk@PXBj7q;c;EO8>CcgVlzb+Lf0_6Ru7f4w-y**6;sUgna+k0`z<8veWy zHc5Xg@5x+adq$02^t1Euc@z1ZKW2noXx219HT_MtlYDFZnw7UE;?Z#%C|-Z$%(l=C6NW z&*k@J}!qE@grQXy*&qsKS?{b*NR2&CBBk;2FU*j;?vIVKIJ)%+Iq7T{g?tQ?e-rF<&f0KMxFz(@e4k=Ei!Q*}8)AjzBD(Z53jC`Ks zdOE~1pCrEUQzn6-#rDBp68G=F^in`yB!1H+qdQIfIpQb(&4Bad{~hA~eZ$%k``|_5 zk1#$zO!}W#WpZBfuW3FjiJ#3Iemm=Z9r0_=8iOJ7*$Z6cxryh_Cy6&ne}R6c>-hu3 z{rhE({|@o1Tz43Th)xq9dbR1>qvZcL#8=*G4Rrl~mU!)u;l97P9{WUT=ZfF7@mfee z%XR;VbI)Hf`a{Gw68GhyF8-e@XG6A$)md9{i=ZnLhYEZI{Cm;wM&_{121Q&A_Go z{yP{}dldC3{p@=C$>$o!@ez{TO?>4Cjl)yKo5T-u-`Y?7mw~IkQEo3Ienjc{CU`tP z5B{g~;9ph#$@ddoPhM2|MbX}WFy;@l!%K1|w=Tw8?q=PuA%65DM%W>~(Q(ET$(M6g-|J{pnT4{~$m6TjHmF!*HK> zUnhR|=L}y;`i1nP{P!Y!d~YVckMq>^YAx}rTn9(VXD{)4Z!!KSO&rla;tRPRHAz23 z{M3}uKTZ5si687SdVrWejN0oR}t3*bW{I6L_UvjeJrs({pz2SD0rMA z{rN9iy*}UnocO@a#^8*79DSbn6I%>$eY-^bDChNZ)^U~im1{=ta$d07+P{JAM>qBF z2Z7J!r`@9XqUcfHTdT1>{lt$?8sKs+5+8jd+e!NU#IG{mzKr!gKz!3fMpz>L0pj;& z&Ots5yo)s9<4;N7|D2)T-!BqhO#L~+LNA@?e#NU4UliT@4QtOa(!U0{jQeH!rHhHb zj`WAN+jzPDzk&F~1tawFtrB1QlSc3R&HIR7dAZf=?SF`Pj`yPuvfjstALO|E{5lI< z+UdU|VceqV67lQUe#f69pM{z8!S53H--q$`{7A3au}xQu!+Eyn7UKOGJA6Cw(SI@e z6|DI6#7}S^HVoJ@nq3~=dJj_dMLe)cQ#&>vSE=hxpb!jq)`IPs-hP5uMKKSMmC z!S?oCBwpiwe3Tf`;>Z4q zawA?Oe(+nQw{Apj#Yq%A-c9f%6JN4= zeI0o{@ecQcKJMen=atdY%)Iy|(m$E8SMMe6zrS>Z^**LJ-vp0OIX%~%75wb0z(xKi zGxGm7>1&zzz~c2Lx2HeGe%T}HBJSVUnF@q+>rlUcw87-C0aQ(~? zfArnPXPE8ZP5dy=TUU~0jrfA&Mu=wU-;dsC?f-V>-sU?&usj_x_a; z9wYrT#E-I_SkCnC`q!Eqjxz3j6Y(zMOX%OapZQwiXPVZYOQgS3alQ#2RniY+{G1yg zsJZm>?V!IA>*mq_F#c|T-bFs6n{6IlVI3a=F5}Y0`%y0cQ>6FbNmxSq&k!HrKEmbj zH1S9O-3YzjXPgfw;xh7i$?Yb$CBJL!^m<=G`~j|~dr5y2aB1g2W?#QX=}8nk-az`p z8GU=pJoN7%{RHn_EFiDcf8_`YE zNL_){HwVgvdn8wk{Zjq^W2KX*6m_>d_%VC@KzTlYN8fH_IT{(w=aCDqRjx>0Y-Bm9 z=Zm$*BvPW>B&knIjeMon7(=F(Qm4^s=L=J4ccb2voI<7U_3PKHnVSf?W+tnaHUX(S zI<1+=@>!Io>h&2E3Em+SsbpT4tV|@`iOi2x57q>=Tx-1;oCI#X(WZhbDP1!0x4mwU)_^szPe{)hWTpM%|OKKSNCQGx_aH(Y^n9@ zvdD&PU2E24o4uwtJ9ul>^GFJmMTkohY>=m1Ekj+D;GMR5XLeVlqZp4ViZzE zwjCsg68TCB$O_b^cXc#gL*9sdsoK6r-uE&`pN>LIwFVjCkX_fNNw+$8dh+jXV3I?bDl^)loD74MnE>Xu&qk`lmNZO0n^+Ht>O-(co zXzH!zfff>PibT5C_V%ttBAhxjQ1WLuwqEmo^fg+-st=P~URqMF9o5N33%Nc9OPU4J zKipg@0n`r%ktaK)Uu%1^6K!qJnvABb?ZFgwW^pLkugdLw%+uC)Q2~7T0_7rTha47ew|dx6zGCvI?Hd}*$hrl1B4;x9#EEmVy2gBCL0UQS=TbSSr3lR3Ze22vj0mrFO-bi=3Nj?Qbyfcm z1>69;U4^q5iz#V+kO^9(>x!URp^>!F6I%x9Ig#WRxpPy(@TzIpC2v?%XtrdGG$)_> z14xqlX86|bvByd>h@MOOuOzt=RMeDhSE*6oDtVCizR`PuysD!+;C470%q4OAEjK&c zfhBSaGTVy_8RUDqvj7RtpZeXV7WBuGVXCaj&zBrXaGR#0w1syJUWn!u#I#RVEa{F& zpW`Qd_DEKxGPqPQqdfEGuvoWP2-zuO@)oi9nCYZ32O=f=aMU<`YshPyuf7H8#_Q;E z&@{Bg7-JWr{KCSR7qxP`*({gR<#ne4KfBXv)NI<-b*V3xwn>si$*>H|qf;w!*qDkj z?E>uPW)1#%-0|2V??$q%a$BS~$7d|K2U#RrwHa76PfZOD2Ve)n z?h9{h1!pT}ge`C>CDp;U_7R=4oM=9=vst$$FiZ1rBJ*ZmsJF0@+h>yPi`Wv`h$Pwj za?yCFT&tz3M83}Hg6uzGT;Ezwebm-vaXf`JnwVwPIp?9;L@2B4ZDb9|EFw;gG zokA_17D%@a%aW>C-1w}8Z^OB^jTZKDYT~i~t;>d_2%~PP7Gn)EJDagCoYiho2HP05 z$x1qhZ=B>fLmVWEghAd4J9o!qRpq^{Rfo2SZyz=B59-98U=UfNM;pM$Gfff;fr{%T zqXWe@$y%H*!%`H|+2YJF!KR5R@hr|VB)*W@hSMgyue`~$;?xOqIT}Z%3=R{$ukkg* zH3z$=@oELlY-78IXa~)JO?FXz9|Hz7L?Fd+Se1r0Dm9qiG#L$Xs!)gIB#b&mbOwpE z(?hQltB6djA`mPZ*<_Z&#j|8mqf|cXHk+Bp0LA@)GKzoD&Sro26@yzEtQot;?+juF z^p!+$Wy=y~kQLj>EV3Ccwnzj^PbzC7T%JNr_QomcU}XTm)FzYN8j@95<5FSmn)p+4 z54%`>=EYrB7ugNHWg)B&mErO1l+?EQyewZZAy~YmW}n}(=F6(qDcc^XQL&&D#z?srXmrB&;{aNnJ(FYV7OIXT z)F?@~gIGW`jzC{KExp*r+@&UFyp6F+iC1Kas?7urBOmW@0f|9faVCpM8y}6pvJ8}K z%}BlJHrCB@N!b-TjcSTp1*+w3w>}La^rr=ebj^+T!=f~?C8V182*H029SU@}Sxv7( zg<2Di5L%n6-CHf@K-FDp8-{ltjmx5tq6O0tWOX(x17+|orvz<##Z);F=o`v4>DFE| z+pcG^WkKRlS+bpDGW%kWMHJVISxaSAZDA2Ecf|E=G}9e3yEH6&Lsub}70jPnS;t+k zM#`N*_fgZy=b6(yr9_$pR;HdBu<~RPn$^l9cq}`oup>I>I9xvW;dsN_s5fEo)$vh! z?_Mkwbri%nF|0%;@sixAA@C0O1u<)Eg>~w=9p{E57FoE_9gismxSKG1`lbo%wjmS%2BIW$S zq?TJ?;3I~NtE#lJmcY_fEAV$xs>jyJf&~L2d#_2Pnop6a7e9>1x3|dE!pF+vk)^0U zQk*E4WDg+?NVz;U_%YZv=eM?6dCq2E%y&-dV%}(40mO23J&T>naM8@U;xKivw?&8C z+->i>Hi7+<(TjH}=~1MQ&NWL5!8yWYO9>$!EO-WSW@$*PSV+^+T!;g~Eu`4{30b{$ zCl`;pRAk#tQKc<2gOamdlkdtT0xj1C>AVV9q-`d@CpYj`7lRbGX`b}Tr*S-92pXUj zss2c-ijXu`C>Nm*r??eJAFRo(>rxIn@M)fznv2!=DQz%Zzplw4ifhD<8Z{-}r#;#j2||WY2HOaueN;~Djf&+OT<|0a z5NBBSv56&NKDc<${!!LmxkS0k#rmDzJ9)X7rLiZxJ%_mIpmQBaeH9^%*uk#*A#Q`NN~Q@0%P zLXfW0m*X9>;T4OL-AO0y$d4STc8U`&^eu&sZ0dX}xCNJ?QQZ(TIbJJNGP%jyIvY~< z&PR2Y7D*5j0XmsFJCZdy)>XGj;(YOJNFCyA7etrctDiG4G@tdb;pWT~xu-Q2`c@sE ziI;JU<5n?&QoZw))MG@jO{uw)ow8V-poVSLS$Ih0ylmIP-G+Wr)WEa%3O-G~GSh0P z=GdayUu^|SLs3Z|%xps>F<-TajFFjUC8jJIdn@K`szV+&D$7|F+M)Z&bVRcSdypy< zyE?iTOMR5jSL*PT+M=}Bg2`Y_$dYWWl64S=L8(o*#omN)43T{76g5j8>j*GI zP+sz1ZdTpq zijf)z7-~Ht8OCXDez;L9Z)=sy7IR9Sw(OMfjCU)H7VJ(UUC{ZFPQ8g>j>eh`MTu{u zYD@alS5RACl=u;vSV!13J5{P}5iU&nE<{<}{@jW9n^>)yMm|d@9h>fO!jIM4pg6}mU3d6sq9o0r5{eZ3UZ88sURQi>85nQY*gOt#V%P1gp~vU#Ib z3W;(JP8N0fl-)q4D@puY4HPII|C-lipS|IA$731z*r6>4rp7FeBn zUIXrW!4*i21G%_6q5X}^X>g~3t6b=pgr!B#w@g)QC83aQaj5t`F;*2AeSCeV;O3r>8DosKdhY@9l}}`#D-@Kex0!YPzD|FBEj4G=OjTKsB&f5H~SbXCl!+7Z=;L7aWTysTB)Y7R| zh{prdgk!^ra`B##sd~?r8F;^w`q(v<92sWa%I#%6TXr#TnSrKb%~8%+r)|AKBonR$ z-oi=cai5KYH-^SaOR1@q@%8Xwjp4(rUTcJzl5lqc=ZWYPMqie5!**G>uA z9<-%rX&W5ruaBk(MRumL;7p_sa{MeG`ntJT6hd8P!^z0t0IlIH(}>nYqAeJsa?7@S zVf?LEuid%+n1o}Ul)7}p!V;?!i`E{J(-?%1!v&WX3*DB}3BNCs8OoT4)fn4GtF9w3F%*ap*QtFca+5`t`Ki8zQJ0`k5(cU#*;$JHgvSaaxgw!m(Qtj6?d z<8RYI8!Fo4+Nm0pjvtNdPJb>#0o9GIgetqcwz1HZKPBpgl&C_h8vbLK4MB9p|#J92kdjy^)$?5ROBCV+w1nEfj32_C?A{i;~GXjLi+Y zjQC50Eh)5IR{7YZ+6K9VPvN$vYLnTLxjE(g6t%-u)RZcq;WW&Tbu~;>rldEG49jj-k@jPbxC*UQ|ZmcPIZ4dC^OosRxnY+#c2*Vaw`_Aap+UV zSU}^T#&+Zf?>|;tSz}!ALHpB;&4&`Loil>(A-Jh#t%_JaL>pfv$exsvRO%dP zG;oAf3FG>mBAPtwV4V$+u8DE9A;&mtA6*=7S-e-Amj1Dcy)9#it}@0K9t*P);VDis zi;GwgBe5v|bdhFj2*9?W&1k z(&i;X>WA7?YpL)DmN)AoY!?1YStZ$^U|1#OjPACgsdlYgP9NAwd+E34;RvKJkcRG; z-hv6|NFp&;KAWoH#*y@HA1Y2Mi@JyVf(UdF{We~1MD65dmU*%H*9WoNa1A36&?sRK z1ox`wQNIF=O<6A{~ucoT& za7z4%oi~>dE1RkZ4}SDc7tNmUQ}lE|tq(VJD{4DmR)U-i6akZ^6 zTQyPVHoI~c8UitzbLpiW>t+@|AGhoz-!oaTMaBh)F3XYB9Ihn&;b079TeP!0Z9>rt z0Q!{^yGPoh`AOX(#lfE3e{ue<9Vw}{;Dpa)g0-RZu&q$TB?dp4D0il?buoodE!C^3 zMh`ubaf=V_QXaruUIY1f^G3?tC;4zC!O3*IWB>RZw+Ll?>{4l7Zmo$uF;^G?Xv8lg zaGw=D#s;s|(x4QUC!Bhvw2_i`tL$@9U^^wmY>Lk>JB^wwq$vhKODn_^{UNcXW_~QHJ7Vjp<|phI`;0ll2O*l`Ubn# zz_;`?&MyHhaqM}6s$3})XVi0KVISe-27IciQfus1$m*F=Jnq!eH}n%%RD%k!uf~0A z+?>5#&mP+b4-NpH-M7c*P&(c4J*u+-=7dM>zU^+oO!1EIW;Mlx>7w= z3#5{f4vd9|iO@@06B=&6V2BVxN*=h!pS{Ep3(u@tA0u=eGuKQT46Qwu7v`d?gOf$| zd$REq${-AC>AXRa3T{MW%3!v~Lo$M38nk@4(X^`+dUGIHf|3ZVn*U)epdv*R3(b@E z*gdBMk<1X4o#>x+a<#s4F%|ILFW%yHR(0rrs%x;fZfv=ySqfO*T5^ZhS4dTW$5K zYANc*N;VO7mu4nW%AOFC(m2ELO&*`M%C&+N;HxIO-d&YFUpKyVf`8>(zWA(Bf&ioL z@`Qb_*J$i3y+-4&-&_P!@GI1D)4jXW01N!nt$d9KZc|3xMSKMpQ5=w#$MCh>LJNlx zaBBIsD(A-j(b!n4yx-r+3hA%M_lZf9|ulv)WHMlFy|I=eOdJed5pD57>LJKimH|v-}n#i}pTfFZ_ArhNQgw z_D{Ba2bjpje^2l76Grb(DHHxt95K|utFV0Z`}~N{gRhK9^@aaVgFoMzDSz-UjNYFU z{M}XO;_dhM2k|1T|MGxI(w|J0g0>+|>id>Ca#MZEl3mOuNyEPoPZMSfoXJj&F{8=&8aVg;K_Hp?mU}629fBx(tljC7$EQRss<^B05z{2vwEHHf7$`6Qf z3I4pCKhNQ_u>7$Ht-@muT6u53v+#2M{&RRCm^agZclPjmt^5YgU#HKO|9gBO_2-;` zPcM(3HBJ2qt^E1(V(?mU|2xC_)wnx|r_0@;Z{mgXa!j6Qj$8ZR`Q`Md>331|{5<9F zxYsm&Vv}%7{<7t-2av^t`tj3N{_7u1%F3%O?GMjW{=`06mGC!Y5C1nS{~K98EB_OZ zTKQ*x!AsiH>-VSpe5St+DUU2Ni#nY7Ff0EbL?PFmu>9YA(8|9yQ$F)n>$Z^!OGnYg l#a4dcF2irY;|>(|{`>lQJ@C2eUs190zbgxD@RzOszX6IY2lxO0 literal 0 HcmV?d00001 diff --git a/src/segwayrmp/lib/libctrl_x86_64.so b/src/segwayrmp/lib/libctrl_x86_64.so new file mode 100755 index 0000000000000000000000000000000000000000..5d6c3a33a95547a29d3923194e700d63659e125b GIT binary patch literal 426104 zcmeFac|era_douCps1+0<36J1mWn%B>WHGFxr~T=1_KO>vWx>Lnk8-p5{X;6WTB;* zm7?Xok$YB3wy9Z>Y0ju6Y9*QF_ndRjGaN?f{rmm@x$pP&d0wx3?z!h~=icW&57XR` z;e$OrJTyI2()wwL44){*$O$DgEAySE8MPp-3j7DOYeihlLs>|Suic#6~AudP{5zoIM# z^VQU7yf=m_JKe9TwMb0UuX?`Gkgv4Gl+1tq>&JL9_DHueg^)N?z)rpv(1^6s8B+T>hY2NAO`JNHgytQf>b%Hd5 zq2OSMmZ2HLA`<-TG#S{Y+KNH#Jbcz4yR%@Bm*#28@G<*(`j7Sut*uSbw9#SvUWQQ= zpm}OW&p|$^tLtT~(cbpzFfZ3!{k(^kWz?|Ill=Ermu;a|x=x&CB)9 zxV)fs#<}3;)qFhb|Ab=!!z6Xlp5ZIBpY|-@hr>03@9|=R7{%BM*BHLXODx1`5ECFK zLQH~~3=xA3;&i&xv{b&P!F2}2bjGvb`W)Zu7aF(#USMJ_T<1Yt0C6F6FYy&Gnc_Yh z?q7zO191t&T!_mcE{BL=rMhUZ@f9y?Ag*QnI$!a!4&oaS*F$^@;{VsM5d_~6!tcWU zdl27eE+4KtA?}8_7vg@12Ou7Th~Y5A0=(hyF85xpXciZxL$;KiShS*#mkT4z6kCw3w#CcuR{CP#ZpAhdsEP?nJL_OSxo4+Cc1My#-#H)vS!|Lp_(lMwqt?8h?w;cA390OCN1ArJ>cd>Y~ih-QeP5W^sj zgXkV6F*muKv}b^O7NP}WB*bWlF%V^lV;m3HsSu|@On{gK(FV~DF%{wrh%+JTVK&@n zFrLTP`EXqb@kNN45VIg+$mT2FzYO;|5MP0~1maSN7?$%D?^p2sO1QoX@ioS);kpLm zT8OVhTnF(@h#2zts!-{_>jl37?%!hkHeWZvbu+{*jNgar2Yjz<$p^dx;ztm7LEH@y z!(P5BRQm5e<`2O2u#owf?~lOsD8%CsPeR1K%qI{}L&WeoT+cu}%eWA(UqCzu@hj%O z=Ib|bg~d?20PzxYKf<*L;$_A^^Ysc`uR(M`ybkeKh`&M9!!2=-TruO@e7ytL-}(Me zxZa2OH^c|bJ;W<4R2V$q>ItzDL@(yN;aVAD6~;br#r;eT#x>#U2eCH9y3C=jdT`$W zVne|p?+>^s#1;?@5L-gT5Wv?~aBU5-E#vlZeH>zEh+QBCLd4LGuig3DgRi~d8U*nP zh<%tt`6tDFU${3y42C!mVhF?`5HUOr*AWoS5JyAAE$CQ?7{MH|KWE zr4IuS9RKN+$XC8h*wAy_v(5f4^8V}nhEr~>AK>+l#j?X#P;&CEkaufTnfO?bV{uEUefVH@ZjR;UuQxAx{lnxJyH(rXpwoe?k*(VNr z-_5%6g!z#1L}XUAwnHb5?w@ext6sl8+oRFYgLP6S|J7+iz|#I9oqB%Q`jhUXI_|kS zq#%E$L2F#K*4JHbPrBx94{+W;dTQJ5{U3ChHvImHKi;h0@BWY5u1-0-Y3mF9TfcW~ z@6|hBIBqxERwMTPi}Q~++WF1LBemD9RY%TjUvupJ?L(d}sXBM;s7j_vrl0zRK7S#y z?ScEBAHOl-T&=S^8jSsB;(^ykRciX&f|g$f)x7!4>n%DQ27CzOuRH5qDuC;c3rGI* zF|Jy$;o9dXpFZ$1EZ|$Dff7kFo&-CB8 z%xn1L+Z~H9ITmcRRlWIYiMy;MH{kP)cYgS)g|kvv`fGJRZS`R_``d|w zs~qtY}m7j9DUzsy>Y`x@8#eH&4EW6q6)&8A5y#7A0 zF7U(gwdcGw=6LS@FE?IX{(b(S+JWJFS2WqU;-`@5m3|6-y+=XJ51X1LXI3}lT!_1p z?cL?Y^qteyK2du3& z{N`s?!}&=UhMnd#6QAM#Jzrc(Hs8;JxqQ(`@xU* z5;NL7S?$=WzkREc`UQ~rZ+A&+ZVL*!*(NsJVQc@YHaMX*4TcFy>I@UZwj_g*)sju zyt)Hkarl1z*C?L`cWZ<%E57{Js;;A-y!HDQuc2Q|sMO7W|0kFFpIY~AtwyGWzxIj< zd*agQuSU;bIwNUF;~%b_Yd^79OlEPHtxaPKTK@C#-YZRK9@+S*$JmC4ea{>XoB3sK zaorjvt7qlj3wdwQ{YI63JU_B}ySFx1dLgoE-F=sKZOOm(Ufj46Yo!}MG`yQwf7KgJ z!s^fU{H@!%-b>#qygc~D;FAn(b>#@JTvTpEm zm7;#BWOlw$vqii2*8e@T-T0Hmo$6lNy<_;>_vYt)l>B_->VJ1%u<7r$Et&`A-@10U z+L>if$1Xhc;eq%k+s|3&{mGk4U+9}OJ1pds(;Co6Tk3m_VSJos?S^E*tz)M z8B;fB%x*iha*ltOU*2r8d`Qo3A3G{r`erSB>Qv9_*@rC6YaNISYS6srOta-emx+Pf zzkU4Bkl}qtuSscYYLsNz@c41l+a&>qhiurq?NvucZcXjggY6rHbqATv&m~X!XV}`6 zy;^==rJt=)?sv^>`|XiiQfoJy)nVrRxjp*cn4g&OaQ3b)pT2N-O}8I^==9*T-E&)B z&gpIq$olTs&A58i8~%2`-Jh>^syTab{|6l_{k?cm(tvH*?W2BA>~ihprad;*`Eqfk zott|f^*Yq8cT$k=rmy_Bez&k!toL2>v1Pw_R~ueft@)52uFT!MB=o)C9=rE^`0!QF z9`5qN9LKFD?|z>1?tt~ZOp#6AJN(qe`uC1&8_j>c`AVbFg#VTY8bzB@^#PiZND6|_N)CrFPrnBAuJ@RSNE8i z-zVIyvSwAyvs!>;F#pU|7`?Z`AtymwSVo zj$Rcudq(IiTi@kZ`t)zQ>cHKGbKZM$@5nV{pX&4d?GMHW{T%Vei@x68OS(+Bx3c38 zLBV(KJG!O!Zg6k=gat{3cQ=08>Uzq;N*R-v9ACLNG<&t9VYm7(IBs9>{C(A_XV?9@ za_!3Y-|xF~^JLJ@ZR3NpD=(Y1xaIALkFGZw@rT#lHFtJ3&G_o`vHp7+p1(b9--YQD zns)6nIOJm9BJ=kj9o=^Q%Ud-Mw`lP4fYFIjeX7nd8&nnt9~s>CNgsc4d3#HqX_K+xB?7j|$Sy4Yl}v*S~@O_^mc5 z;@>5WGz|`Q9tlUh%ICK>ET2z=gTeCjEUZA@uYLLQE!vgO_pdmEU(cjkK z8YjNmmw4C*VJ7p>`l@md-cW?Tu{uEQ>8s7ZtoSx8-;(;pS2N-vGlb6SqW!@3{5Vn( zGg$u9no9qkyNZ~`{8L~U)^}$kB|nz=v2_*SvbN%zF<%GVdbZ+WFob7W&taMuRkb}knBa@8it5KxZv9x3{Ex3T z>s_S>-wR>b&Est%w|@^sYfHI*x8795tIRLwdJP|=^x!)r3T*$3zZBnv>HBO?-p8uG zDiz+BbXImcK36<6I|Vb%FJJ8l9!5jJ^GOW%X}$Kb;#P2NsJI|wUJr%#6`8UbG`D!*kcm{Vt zA(+SQsyhlp_fZ&EU+JISQ0dXz`6T%zU(Iwu$)<af6cYoTlU>nSTcy3)-KC2i*{K zf6|}rJo-=x=BtbLDO_=0XB<-Pqw`ol;twl6h~1l2$8ueD8)KfZJz&1H~JNg)@5Ae?wDx zGMOI_V%QGXS%E$u{on@qH}Rz&1l|9<#_fEV9j#3zYiD^pf5Y?iOXhpAzk260Md1Yz z#uEXAVL70%83eGt=lNyU6U^IqUhl#eb`XX$pThM@;un29OtpnHAO9M!j~`D`{9Kmz00FdrAuGJhNT9qW7E z&5uonbZUpAsvQbgz6?fe(NG}6amJzfWM*bj#)aqVp=7u)A3 zzKnygiTN0?ANhW~-uW^=x3c0-^NXqj%vb0673ns=cCh|HhOR zR1nLZ$^D+j@@H87GdKAQ)s?){sRUs=LE#e1FZxuKtLr}t4U7F7!RrMq(-gjEzuF2N z7lasf(eCm*n#SWt*FO`~qMZfoH}v_k4Fr(?+iiaB<8ix%$F1J}nap=7QU%`Qa^vBO zc527ec+lIwBkLc3M%62uuWG6tmM1F>-kvHUg2&;4C*n{o4f?t;2V1qWnJVHL^YbAJq`KGNDznItGeypbxG$6_^zOINh%!hHmA7V%K z81sfYO1`d_Qmor^o$Yyx+j$7fSLSm2WGMNS%%?&ZVtX1+tM-KMrqG-F@z7Z%UxWE? z!6BfX2f5tmc*6hDMDf+bl>A7RpWa#Vzu-n4LKgD|@bg%1JGXt{4ug{Kl%n+L<7Y^H z#h38>ozHq2R#E)^3yPS?e51z||IA&b2c{c^K-if1fxlXHK-HIN?PvD$d-=KJB~GXY zVp!iBbCez&_ZYr0C_b0>CoqgD{Lbz6Bfi9kFq-~_?-bbY&8?-{A)WaaAcpOb?&fb# z^1OS%^HI0WtC^q2{Zf@T=26T?@i_6~aRP3HLKPklemov@ z{~uaa*;(M`mx9?3-|$oQ)%Q8$!Es@`UEQJhJ?f$@fq{hlKKxJ#fzs~G`*?_-5;*tetgz#KTw~?$#kx7Th=p^*X1T|>vB(n zvS$y^iw@kLlX-l4y`TtCOQA9FSYHFL*U;S*YV$Ze@UN1;$$WFL6XhMe-_YB06xXZx ziW1cItZc39>9<(v;pIoOH)Eck$6K=g(~uGMhr0Rg8SM8aup#4E{wHpSVz>QICXa`w zcweoLlO(QJ3Vz@MAs@yQh9dSG1^&v;>WbE$f$@y}oAZ+*AUlOWAUpE&KT}wr7k|P~ zL;fJIN4kGo3SwBVeD){c)+qSE1`OrD`(5Fl%%{RYLjD|o#G{X^&X5uL%WS8W<)hfo z|JhjC56wlPKI`}ULt$P2HeOHnKC9&WvwRHmZ!!<=j>2TwbrN5rKXq$OIa1TGcgD{l&3vfky*6_TG zrc_Ncalh1Bp#-^EwPmcQ$NP#O!19gRj~RJ=DP(>GETE`=q}x7O0*j#GSdmLFtLcCMOUwp?Fsw>SP(g3DPxnf*`gtBTO) zZzt}r5;y;V-@Rcw{KEUdKCI^m&!bBG9I=r3U%9@|-B$#6kM<$g%jwphm7yZ2|FIZl z|4DVx5_rE_o%fA;JAVXfab6T144?vXx!e`J&-^)9Dd@_2TCiVw>?b8Sp5?!Wd53y7 zyVZ9)v^UK=Ua$G_UVBZ~b6F|S`|B#q3$#Ci{h03eD)Trzd`ZcVh5o~^7tBWa*I!Tu zIuxz#tEu=6cNL-gz5T3zn_0?$;4CQ@M7nVQE z^U?QRrTAIqe|ucXU*>a5eV#6a@rinJ*x`M_@=hMl1w5Yh{&E_W{5IZC&SLqWp}w`X znwo+CP6os%ByoGbJ44y?GV@b;9xdZ@Z+&0-d^@Fo%uXc_+ZYP_c%CNl1IjSwKZkLJ z_P1j@_4a>>=h4f}m7XM)-&#Y-4=+}PzAp4-JD=x)qwlMab30s4ReFZA9{e^E%dOi) z@%lOy=A-zF%@p64<;^_aM&L#o!Wib)^E#Er<5{oQb38Bh{iFo-@jsLMy*>9k3>ymZ ztyH-e7ApNmm=EQ4JL%@%rt`e0#`8k=|7*D2>f*=65ZGO6O?f=uBh>ULW;(JuoP~9gm+#mQUdJdFQes_*g`X z;(A@Vqjv^}M(w}-;*$LI8Fqp?-Egpx1n76f5@=wfC^7_6dkjqWr za-mr$tmSswTi=uLSmu9XzkP9)(zAm31fGvEJRhN1C}bE^x%+uN)$OSa6~T7);r%%b zV+#FvpEjhC(x1e936Jx-*A)TPq>#bmu%p{JJjL_$UEU|GWcj4Zs@&1+7H;Hr|YS&^lWXY_?MW!4jIwkM(}=BxARFDpUB6#`Qf@e@9y)wc$@W% zV|&*9sfb<7_W}ot?Uv)V4)%ueiTvh=${t)7G0bHq!``+9V--X}Djrua>)e*pLmw5Q$D_ z)=qjUe%S*h7{&5`LH`Co`&>SwplXjBl^;5h* z9LoCVfPS=p75f=5gF+zt&trcptdHA*x=P;1ZC`BxJy`B)UYB9`QJ4k>BR_@rz4|)q z{loW}eR=vK7<9rn+8#mkDvRJo>4p>(`a?7s&XH!QT!dS149w_`y%dl z-QSLc4#Iln@jBaq<^5VJelf2j`hKGq+n>Sq>+@(uO(j3hZGAk<^{RbO+4G*dXieCD z<77qf@s@_$Ftn#LpVwt8^R?0JH`efc9M8OFQ1W(O$77k_!}VReNa-(NK9&9I0N$Tl zb$RyBT`njB#3;PO^_t^Wue&_2XWv$G8(4k;%Lls2cVl~gov-ZC{Y(=cZ#iL#AIW;Y z@2KiE`;OvsnSZ>lns-&*&XK&l6>mHV0~Laa}Sc=O-BO*e`GM`R9|&f5H2-%KTjLF7uCrS{&zQ9w*R!6rN=NwsyNJ7yT555@-i3 z*TCiK_WN)U|A%c7gAA>!N494^+Y`t9U%YQw&g&FZlfq!0@BMk-GLrdwyg&KW?cAm(bOeqc4}Q=1 z3Ck~niGchS-rwr$MQ=~V*JA_uI9nTAPx1BZDEsyAJ#ZMKo`5G6|26C1&GR(F?R-0y z`8>CI{SM^A_Ak=kcPMq*5pIW0e<{WKdNhdl376uO;EP=Dz$73uXm!#x7 zvi^%zmHqQyQ^W-3|AGfPtk-S!&$@rRS5xsj+~(J7ypH6te=xH>ukd{Tr&uYT$^0!`zL)!P1@~i1mS4jDs_2r^^Ck0Vm``9o7R3BLF1H%bYkiz=ZmaC?_kq&WmF3sN z1i|`_;f4BD=2Lk5TX_8I^DzVrL;0CAm7diszZ%>%@-{w)(d8{%ZW=$|MYFtx?SJVD zrRQVj=kfeq?ou}l^*?^tvd5p$0=U#mwjBXqg*f8MpDS;aenol z!umL00u6}u{gU^G8(6*r`}2l;zM;?G?yM*24<)GUZ>ihK100%#!bX-~TcYqX<{NXn z{muKd>C8tpQ1i5z+j^bA?YZtFRbM;HZw1GN_77tJ+==p^^A$gz`QNyI9}8FfK-SZS=jpGpioeD3o~-BA zR>j{}7ws_Hv)xM(`gr&ks{~LeRFwZeR zm*qS0zTyLJx7WBGHoCRLYPR!>_R7veSf4O#=6R8HSz%bdDMY|H!E)(GIe^jkEt5Jb zz8+SHFzv4IX^GILTbB4!5$+JqnGxLkvt8tsb z@8h`Jv_HUL)F0eH$s1UH72F{Ikk7$%J-wj5xPMshHvYY!Jy5>s9i;%KGlhQKUzL7W z`Uf$8p65kRUsX{azM2E(9qRcRe_#MYU6oDS%=I;lQ3R-^aDw;G9rr4JAYcr+>{k<( zD*jbPYd`b2YQ0DCRn$du@IG_tK}GCfJsa8oJnQ!U?ipwhv~w4K$D;R3M=rN8N9obm ziz&><^Egaod$#j>5pPlQP1&AX?BAy1gDr$wEI)+Xe}h~5hp`|2gZ;2B@5Ali-EDu; zANn2pQR8zMaMu)qdH;~i`R(-2UrNsQU6_nD!R;*Th|lFJO5Gm%GQU+;y!~zhu0m-}$`4^ZGQ; zYfww!d!84~*-qG=QFw>#PjT~m(EKnSYG`4)BWL+2ZvWLh{$FSQE3WT--dBuaKF&+o z{}ubU=TtScAw1q*bQ^ESd7t(jcSsM`Gdn=(>CF4XVCIKIN8`9n=5z94%>T~z4E$IX zIG4+92jc<#zmMDb=NGKMC7<(mXFX5D{KfH*;kIsGgL0A2ck8bWyiOfSPzCDeqHWj@ zcjEnk?l=0eU)^~{75F5Vi_;wI^^B(cMl|z%q2ICGK=ymsPZ%1rzZ!f;VVG_zgono_ zCMSibq+0B$;o(|%Ong$j7Ctm=M0m8-ZjFskNwwO;Mhr|yPO^qsA``4Ct^AbmsB{Y| zuq4FKwrZgx%)ukZ3{15rjIh|sqOrDUOR6rVg|u=@!7PC_XeTDK$RPI>wrsX47J=so_z{ ziD}{Sx_#kbGFl%VWl8F)l~%{4VUQJCKDE4*p~w#eZ3C0-R+l`o0}>J_gS15Gk+ho< zp;52waOi6#rMgTnfO|%7J`zDN(2|f4Y>Api1XgIM#ir}h^HTejHZ+M2Ne`!14@U)& zpn$3%x&xZfl~md%T(4NYA+*vYy)@7@-X5Q7<$(a>hYAeG(H%7{JSuKlc#I`JLDRbm z$Gody2iR=GEwik4y$S=OQsZY>UCCi_cB>^iWenwE1tCc=gxzZH%HXbVY?7s1ji^M| zm(Bw~GzM2&ueE~M?}Mxf)>Nw+nIo+;d5Ch=)v&gurKV`fHfvIJyj@F4wZs4Ml3-2J z60M0*wplbzQxb9NM_KGVL^Z4^=7>swd4@M2oMKJYQfzh@&M{ibEN}{m8n$ieI1Zj= zwxq^sWQG~#v^Yxw4tAIVP%9mP9`FzeFln{O*;acpT40Nh)>4wAra=)ltKFUqMp{#m zNVcVFk@3(zaWJ~rx^TR=C8WiMr&5oAwNW!L10{s3{E5&_i8gEWV7n#J8k`oRC59#1 zh9$)l*2Y+qQj+aqFj-+-B*J7J7-vaIiBEw6WsSyJU`+z^bT%wLYFf%8?5ODEL^Cwc zgo))Qg`_1|?f;cFsoZSitO>*8lgd*%G%;<+Ec+vwfF2MP<)WdAZZ(gw+G!5J2nmf( ziiNfSW^fvKL0xvRJrP)QT1uQ|Q%xG4n3ify4^My|&`L86vRZ8@MVZS=rX{(_hS}p| zW1$U);(ST8f&P$0Tk0%TW}=OYOomlKw`mLvkc8x!=42b`ck%Y|78pHxaZ$-h(cv?Z zA?ryq2@H(0Mopu#sEaXsBvn;STP-ErVzWoV&<}@&$3oo>%g+#N>X_7MC4ydVaDpXv zoFyU6strj8WvN!ZVO{QseWA`%(=ta>4hfu`%;~-aX*DHF4YAV7Q;u2TQFSeBB;Dl3TLVrrj3h%aLiPFJo z@d?p5OSG`K_!QMj&?@%Su}P8C-%unKqR%pYtib{rY6ab{>8B^Sx)D4~D!5kcG}7=$ ze}!36rcp93G-?yjHPAF0EJ5dFhNUz)dO&ovR*qaZl7sxPZYwi-B4Y*L>Z&5FR8$i- zh!!B=h9_I1^?OPOSCKl>G9y0Lk{X|!ghL`N1xL*zT&&WF$?+DOnm~BR?l?HvVvp8P z1_q|pt{^0jfGvuSQn1ZIWYi3FK2~zA07I=QX$i1HaSA?Z3soi|IoTE-Kb;#vCPSSQtSL6wfmAHRrj-?tomx&AGP$BM zq)fSG46&vTNjE_sj^j~DITH0QCNK!-C4 z!GhMtVvPe;<)hPl&cICN>m)UOxJwDbxXMpeY#-*R+uq3eBtqpMk(wg zli?AN@1eu(vEY+kMB)s5V&v3BIea25so~&1`Pq&q_{?PcG?-k`R(1whW4=#-jhx;{ z;fa=XN{^ODR(R8vR5_dUZ0c>+{0I}=Q*KOApNVZD? zY!i4)ky0KD70^k^u#<*;g%piROGqeX?X*OP+hB8zbB4^)`vAw5B5?DHy^vy8oj1c8 z7Y|-5JQ1D(>50kJZ*kD|G$_kxDrMOcbnJ=ADW&~LlcAK8wn$lhHAqN~4Y%SZHk_t2 zo(*9Y)M7t0DJD5A86P*u2$)GMo0JSsY-m9lYGCP>k)B52(E#@^r8^E2Z2R1(LDp1! zm@g}bJD;H`E_JRa5166h$jB|n;gYTb`cR0lv7b&`T2YDdjScN%RB)T1r#r4^=UT7t>+9GgC2mJ6vzS2sM# zm8?IaDgjuw!B$FyTX+K;K9ry?3z{j6X3`+ zeb(xXI8^|Zw8olYu7#VE6Rd;nR;wDvRR5_daQ=+rLW{w(DlI0(YMrLVq*~!QI%?RM zQ6s|#(u5rqIn^2kJ2gQCC&Oy32zVOA$D6R^GGgi^DrP303TiPi33$p8L+4srB6I}o z1Y+=k5)OMx9S|QGxlx*sa2=QoO({L7P$wK^ea~R<^U!FeLPVhBfejIkYw)FZ4a~5B z^MDno)OUh;@k!bkd=$4P;L}=kavFG^GgiHvaYfN>bs0&g5vY@W zy#8Q1H5vLzmsagrUUNY6F`eR)#z#{(D`7O29yw#08741`Ydal4aM5~cdO9pcQTW`h z^FvdH( zT7Fe@A*^u4LfFJ9WlF({sgoFVQo*x^f|==b(y4cvdry?f?w-gk0-aN)#VQb!J^G*W zsxSVRR_-w|O#V~p&=ma?RE{O3#NFVsilU?4(_Ovho&ZA(w3iOAa?)ihzypYDkEdIw zxftB_;S9iq(~V7rmwd3>PISrYx%C;7qVbLl=FKBQ)Tb_19RLkvm3Te{Yq1S?-6>ik z9}+#Po)h#6hDN(AbxRq5CtVdKj)baJoC;Y-#r&t{Q85+g4vh|mWl3+p@~rxgbY<9o z2(WGcOJcme90^xzCMU(jJf3h z6qSv(QhF(Rf2uq>t7m}WT}E2x)hwbUHFe5b!EWM_bRuX$(+k4f_||J^N*JBX!1f&+ zr_xrM20J-8zJ>)sC7=_8R@Nc(jFsL{Dc7ZBT%^8^GYxZF9@T;xm!!-t`A0P9iMj!p zv5Z#rinI&`XT;@YbLUh}cb1)&UQcW=+3Zvhbd}y&kOO3BbbcVY0GQ_3hI%3whHXEf z^d+92rR@0AStvmF{kj^F1bZ-i(+;PGTwNGadNMU=B0OojeRQI$OA%i<=nbu>i6l}} zszr@a++|=nLXI1;oD`(+;h8smk+kV6)riSTD|k#drI^Nw%TMHttolE4S1jRHK~*I7 zk@_qk-nC}pz8y|t+}q0aLJM=k9M#`%A;eKW(weS5yMesO!RbMK%q%GdZy(^>1XhnC zWRk%0#UZBa8+CdsotD@&cvdQWxYGkKqu?=4rsPx6& z(4?qPYmA;D6kh*XQmi^uV-*K6=Z7i6)zcZak<+O#{l%^*Q%T{T#SE{s^t`2Y)CbMb zXgElFB%hvIe*5UDSgS`Ws|wad)H}Nh^;0rBu?i&~?bNabJkrH#cLrlgy%SAD&Em5h z-7wW8A_3D#ZtClH4eGaGGnwA;`=RTHHI9rH< z)0EWs6g=fp_sQx$H41o=z|vv%tNi94uvW97Aeha0UaXuQ+L7keNn|2}>T6YR6YHmK6A23bK`^P8>1F zm0HSr_qN^!>#bThKz#~7Cev(#}`I)WFJM3+?pl9 z2Iu?GELsYD%!HZX@FkvJpIcJlC>!6dYcpc_)2J9cp-~?}h0t3Pbw4ORg}$An^K4i# zs8}sgod`hHapouDw+zI(U1hJluv44?17qmfEc z{hthPdK6asDGgqdYccS~6Wci+-oridM0g4|D|}N1FLC1Z+-8eC#X3GdHExs*K44QC zh|}+3e85*I@J=!jhA@n58m6$wy3872w_9e7!LLxuQs}r!DRopRIP{V@5|b%E3o;4L z7CwlD1BL&UTIK)}Us6QHq0+(jC`k;qB*4-l894Bbbal4M#j{pQNh_2P?EW4l2gCcZa_B+H zY4A?zQE^p}c}%zK-FWK^VRxU=-u0 zgQYBNLg>w0DPxAi`%wweaKI|WkOXaIN!Wbbz|X@6ckumZsRF|25KAeRL`PIg4usG6 z+^nHh5v#+8vskG>ZRWtxfnk<}Nb7(|c;2^1b?v3T!x`h+n9=?WH)iSyD=m?BYGT6% zDx*{jg^VBNSzv^D;(q-Yl za|&q+DJ`Cw4@)c7i*)OnRc@sZIs8wlD!saP5BOWf|NGznwZQ+i!2h+t|GyT%|IE6F z<^_N2g@31HfSA@e9{%F5vNj3+jtPSYc$+UdJrJC4;#fA|Ff{yd99@h9q<>&E9ZZ*=>; zA06wz@1pC8(Eo1E?eEOm@ZV8pzOTv!W3_iwk@Rn_;Pt=t!-Q3WKgxg0hJ2pj`wD)u z;GYqEzTo*!$5D;8NAN;i%VqnKlYD`Yzb+C^3H}~wR{susQZl>UC3jMi)*Z;;Dv#k<5|AZ)M%M<)Mp?|aBw+lXB@cMr%9h3J6o_~Uh zauo=Eim2Bq!Dk5j3kBax$e$PdLt#&m;7@DY4~u+vZQ-wS*E1;2$fs(%cE*MFk`Q`!kWRp<{CJgx(J2ok)vDAy?X^|~-z zO@i0|_8gPVf}bGDogn!0LQjO?&k83cgtI-wD1%@cM58Q1Z3_y5PK+DC+AY_-(>YKf(VZcz?nF zDathn{#U`b6Z~Dl2MT_w;DZFuKaoJGM!_Ez_Lv0!jnHEjd_N&SLGZr|`3S-DPa9Bb zoZ#OR@;1R22>t1THw*a;!T%umOu<(bdU6HdU-Z{1!8?U~p5PA){hI|JEcE0HzLU_i zNAUV@9iX}b!9OPCPYFI-lv^nHj-uT2f`3ZzMS`~pJr2S1PaaTevEWw;drAa9Ug*(( z&k{v_M7jF!lOb;w{AS({Bmb$;pD*|-LVl0ngM@s6;M)uNQ-Z%KDQKix>RI4}4m zLcU1wHlg1k_}_$lvEZK-^7`*apy)Wk>%TXQ{0_22{Sznr{4T-U1ixGG>4M)Y_zc1C z7rcLd03rOHkK4k2gWx|Gd^^GOPy12+K*0|Y^$L=_&|?(55Z6qC&lh%@1%Yx{3HgH8pCOUoBly|E&H};11G6if68uURt7(OT_Z9qk!NY^J zD-;QShbY$}_#Brs>^}vcCioJ;>%SF4$=gfEE&OzeEBFYWf4Yd$`~=@o*yAsF{wX4o zHwb>COFQg81z$_>fr6hQ_#naaPxer%QSg33-X!?91aB6+{@YoYJVEgAlQpgoA^6H- zg2f5m>5_*3KAhld2>Eou*A?;^g0CgoGgI*OgnX{xa|ORj@Ueo=6FmIHkSlB!{4o~` z<6rQ7h5dU3KTpUP2>wrD|0%&23i(38XAAlBg5MzcBEj=dN0By%;Q6Q4h%XlWCqhq& z;2Q{gv>m16KT7aEg6E?mO7#=`L!sYa@bJ@5u3!+nr)bZ1f?p@}1PUI0n#>h~1V2#7 z8wLNGOB$ZP1kXR|OQ~kT!%s50!UVxjcd?olA$a}?PD+gvyne)n2{yrB5_YBw{)pf+ z1TPP^G6jD@*pn-G_-Q*=SS9!@7YqJh@YO`Qn+0zX{gN;E>4M)Q_$ESsf#4Sj{*>T5 z2t9>@4;1`)!A}%=iUi+Q*zXX$r{IeP-&E)+5j^}fTxs|)fbMY(j45R`AHl;Fu=@DGIkOu_#n^yCVDnUG&4_^LvGp5W7k{AR(c z5uggm7ks?Xvq$jLgq{Mye<%1;f}bnwFBE*LkUuYY{t08sRV4U>LXSi6Lxr8if`^~% zbA=MYw|22`^O34Oj{i1-_YwRo!TSmR2~n=U;Nt{u5d338PdmX+5bY2s_^E;q5hZGXxK>MqMFO@Zmx}SMWuGUnTgug3l9trrk`cDadkKhXhe_H4{FZfwPzDV%hguFxWPYOGW1^=$lQzH0Jg&u8J03jUz z`frUQ;UjqZScs(H{khCI;Qto#?F1hz_&~wG$z|dtNbt`Id86PP2;L<4 zrotYx;QtZw69nH=lp7)VUV@Jkd^4fnCipm^KV9&BgnWkJV}*RC;1>!$SMW~@J*x!Y zTiBT=_$LIvS@3-XpD*|X!S4}#O;K)v;O7fFPYK>n$QKH}hmb!n_zj}mBEioWyhHG} z1Ya!p&jnv1_>rPqZFc}k;rNdi@;-t;B6vT+ZxVX^1;1Lz8w9^x@a+WORp<#6{Ba>4 zB={!yA&M+iPb=#LY8Z6R+H{29Tg3%;LcsiF+QpA_<$ zg0Cm|T*32yN`aKE68vDHKTq)A3O$f`3Es z=LOF{Elu?*5_}CI?-2a;(&p5P1s@~qED?N~(4*}MpxikArwHCh@J|W-euBRyRBlut; zUm*B_fK)|M&@hu;Bd#KSb~b!Cw~o+X>zzfgUo806 zf-e#LeNnEqFMtq^^D#o+NAM$syr1Al3Ep4uZG;|!;1>wKo#3McA1L?*LVu9plLT)R z{29TU1plhgZx;MZLVkkayNh;?5PYKG;{+cr^wn+}N4QfDFI z0K{mCvw(18#FY@|6Rv~U3vnLdYKXlN=MwfrjGq!XGYH>*02rIYX(N0Gu@B-1!q*X3 zMQkQ~8F4klM#2{nS4SL3_#9$i#0J8r5!XQMNB9Whnus;R`w-VcT>LK(ZFV5WSKH1a z!dnp6MqEgE1L8V}3ka`4jIWrT`Gl7tu7@~}@M6UHD%hDzcs^o$CF;x|JR32-!gSgQ z+Y#fdNM{7$sfZgPHWQ9SjIZLHM#7U2H$faoI219yigFqV4@2Axu^-`J#Q2KIsS)mj zxCP?kf3W`D5E~E|5$=GvCE`ND0f++-7Z7fY7?1v)`Go5r#v^}c9^q<;+aS&*?1>nU z=A9XY@57LcYm3-M_zvQBh$9GJN8BEAkHJa z7%?94ICBZlM~p{1&J4n{5#tex(?-~iI0$hB;i-u6D8*?e9Eli@P@G1>lMp|NIFN8C zVtj;h8VCHX<$}+yU_b#D# zV%$nPjf5{E#x0vOknlOgxFvHM2%kobTP3F-;UkDgBGw4+LyTJsXYqaNf5c|QMTEB? z#wE^KNO%KcT*90Mgx4S*gE*h?GQ_w> zBQ7qX{zq&>Tts*a;^~MB32#7bM_fR74dN8U`Gl7tPDPwYcroHM#JPm$Bc6dcgYay` z_^9Bt5w;^vM;t+TD&kp)&4eQn&qiz{JPGl0hyw|SBA$cTKzJD9=Mno64o3U}VvTSg z#B&iB-=qFVoPoHAa0kTm5El{-Ks+CD0pZ4o7a-0jTnF(&#Ce3PAzp+ym#`<|7ZGO= zzFz|PCB!zucMxYHjv#y;aTa1T;me2@BQ_Ggh&UT@AmMX}Uq);od>U~MVn4!15Wj+0 zBfJms62!%SQvV~)MO;L93*x1S3kh#PybN&x;WdbtBhDwh4DkxYd4v}uUWquD@O;Ft zBF-Q@8}Vz1ZG`QJS0RodJQeY3#Ad>gh}R%C5}t&3E#g4Jp@?5cY#=-g@jAqQgo6>k zfmkEl2l1PTi~pehN1TVah;RqQ>k$_c4nVvCaRK4Rh~Gk-Pq+@^w-M(Nu7-Fc;#|U> zh&Lh5AbkHG;CB$)2;V`x8F2*R>xkb)Y$kje@fO5J!WR+0hd7Y%ImGWHHV{6I_yfd# zgpVNJidZAO5Aim{#lKVkBhE)$M0gA0?T8BrZ$P{QaRK2qh(AP}Pk0&Pj}Ye(UW|Ar z;#|V>5${5rL3lRe-H2_3?TGgvjvzc0@m|Dc!jXvgAvO}8gm^#VK*FJj4VL!qh>Hk!K>RV{Lc#%vk034}+!*mu#QB8lAU=jTk8m}_ z#}Vfe_C$OFaR%Z0e*!*<*hcsc;!}tt2wzA131Tzh%ZN`SHWI#w_*2AzgwG-V46%Xm zX~dr+_9J`*@fpM#;eCkDA}+o|{g1d1aS`Dyh`&HwNO%L{bBGHFuR;7J;(Wr(5PyX@ zkMLr|Un9;XJRk8lh%*S!M*J;e8(}-*^N1q|PeptIv6*lr;){rlgeM{X4sjsiP{fxI z8wd|W{5@hn!oi4tK&%n&gZM|p#kZ;d5f>pYBHRJ-PlyW%2Oz$TxPWkD#6Kg>CtL^d z6~uXjt0BIMIG3;|;$IMF5WfEh;A@C&gzq4BAdVn>9kCO!neb)A*AW{DUqpNZaUkJy zh;Je`5I&9gSHymVk0AaHu|{|w;#-J|i>dz+7b7kryan-X#D#=6AijgRfbbf`cM<0k zUWWL0#Ce1lBmM(%F5&rz|3sWYcsAmDh;4-Jh)WPh5T1(oFT`fTk%;djHWHqM_;194 zghLTOKx`m94DmmR{Rjsm{ui-ExDVooh>LGg|0BjvL!Cv0J0SKzTu3+oF@6H+EFjz% zF&+sz^9k2M?1eawa5cohBF0ZXoEe1g{|>kcVjJN*i1E`WX9VHvh^rzt6TXZX zKP`0{313899dRJxbBKKr8wj69jIXkseuR%8u8CM9ybm#c3hpfajrt$4AL1gyTM*+b zM`t174T$kog0q0|8pQYsh%=w?GQ{-|=Mi3vxIW@s!t)U~K%7B%HsXeeZG`QJ{SikH zo{G2;Vl&}L#ElUf2~R@Y1aTnYP{d6U8wd|W+zhcF;b6pg#OKrq_d(nOaq+Lz|A-BU ziwJi>+!Api;Q+(|hzkfeM%)TZ&3du#!qdWMT9#b#!vj5g@gkT2O};Z+!*md#QB8lARdG`k8m}_A&7GcdmFM|d&fv50dC z&qq8CaR%Yph{q$g5w;_qfH;EiRKybzn+ZoEo`l#)coO2thyw|SB7O$3f$%WIQxN+R z4o3VeVvTSg#Q4dZv)D=fk2nHx5#bJqEr<&V@A$c;7L)t1&D5*vdW5fQenD)?={p@d zc&sVMJ07m4CrV6NS5q6o(eoC_heyvfraUZ)>0GM?J|e<507voExfDbGu9z>UCyu+Z zruP3re$&VQRx)K3n?82*H+h^eeerLqKPYrU!Kly|6;`A#qpuU}*V4L}7WBOb89*i2 z<7>+9Yrox6bA&*R9VYnag!jiF=Yi&Apj~&5g33Wke2Oy$BrqeKq6bEsvc1~00})eJ zNJ-ZM$GA%H*J_x>Q3%gd3k%Zhj!s^hwy+?z+8)UE(Am>d(@uo^7I-4$R*)$tbvOb2pK3J`+BXF0FEtYix?sie?Nk?bcvB0^#A5d=*6>{E* zkIt%md_H{2BW;$$>?6zH34I6U2SNE@LvgngA-B7q2)Wb4%@%K$E$LTuTfX^8w`I7? zmH@V81MD8ymRf8JXgoh)4-|)0!ABJJ6AOm};m)xPp0*GB;hhgWcY#43V2~#mR0$07 z0)xCygxvK#5%PPD6Cr=pJQ4C|trH>l{7!^8g0R7+dVq3=d8&tMv;lkY2@sm$cd`)M ztqxgu&My1!fw6GPvrniE^EE^n)iLM?4sIBE(t!M9B3jCqi!coCvvD z^+d?8)f{JGr30pPkKy=y+?gfFpcvc2CX7*Yh*77f^oO#%J8x3W_5 z8YN=adea?tZ8n?I%JJ}_>P9EHWx6wEk1dHdb+1RGE!EqR2mb1lqcje)y~l9AzoFAX z%}3lTPeJC~DZ0=PEHoG!A=|qJ!`=#Ja2^LVKxv-K%$`$1lNm06$qy=qBg}^WJ?XIg z^6=rJg0z~z_Cgk);i#>AuyK@3-%^=7KT4TFXo`|)R4UUMS*3>!qEQ6izzH56e8Vlc zIQ*fGYKHuVIIq!TF<`+(Iv|0o1(Ks2fenB-V8$ zS|Cvro72}=+){HqNApm%X7)<#byJr2V~}FXs^1nb*^99MP1!54?;)+RN^7Fha1=lq zjsQrjsnTk}rPgj53o%*VRgui;y9M@Kjv7}$E@vgaX(fyIR;3pB_O9tYQ`Y^MEKk#d zBc7S~FZkz`I2@reC=J8qT~GjBqiVVke7>Fp-8B~5?BpVR150gsa*RWOc=Anz)j9YDm$YD+c2m8=dj7uN0e%$7SJk> zXv*ok2LzSCNGR%t2{iRAqv?xBG<{v3O*wrJxioo!z+qgT9Mzz8NV_R}iUXFLruuTz z6()pf-ZAt^lX*p1aMK{&6KsEApsWU^jw?T5gY-R!_vhgr7E&BUPv9VmLq$1#`{VsH z>V7ERo7H_N-VajuR=f{V_nCPAxVm47_Xc&3=wi6f zc>abq%NI%yM5Z5FneF}BcdBc`!69UZ+#nfnQGMIE=H6AvdZRW_om|v8)O<1oPnNWk zA$Y(87eIk&_+xFFh ze-7ckQ|-l?!a&Xnxw7E-D-YAK2_|AAUV|a4ijIKUQj{HXWxyUN0W^QH54M)tA=Ct= z^e@7W9dQ!`_NkK30J|FeT~>%=!SfDnRx?mp168g7l^_PmTcEd;@=8FsH_3s^dXvC% z7zo=%Q`W)rkk@V4srI@7lQe6Q1CmcJx(WY+RnQD8i{X|8_TtaFnzG1S&FbD(SSgrAdhc zm9f`&4NbdIP1(^42*=y-c|#Vp%YuW{I;qW}kj|iPL4il6cN@3?+#GRHEf{UbSS+nA zc_pPO0fs0v%W)^wC<&g^Rns5CIqv-<(3%oF3M0-r7diy@r-x2K6%KcVe;n_@L#En? zef%}HA3nS6#yi;j!S1mYz>;qj%&FfQ^p|yszR+^|-gLoDKU3E8C6Hr=OF`;*fUyi0 z6tu&>D*;o09nCE4qIv&t_(w_zDl5Jk*P?9i0A@kKZtx4aywiq4Pln)eDp>6O?^nuF zE@+7=$f4M5b3G9Gj)Bqti6d!MAS-!Oj&7$^;Ems&EjLtT$n{_lYl6yMeKPUz8ncfDU!s80Wb9 z9X(5!9G9>&R9)6{CTND9s5%=yV8cq9y`Z8mLvLk$V#=y_3cyU3q@MovVc`vL#|oH< zj$6==3yM9!rM{ut;u=GwDG)NB#>`o$6e(knDI16AM~bCZ$Ts?B;X_*`K8uoTc24O_Q*v8b4j*#&q3|KAlKX(m9iil2WI23} zRr+F;+&Y$PqvW1txhg1!!iUBxxvO8Oa{o~?uouf=lPI|fN-mLG_G=~gFTs#}Xrk}b z?H;&|ph80m;C2M*4Z%ThUkMb#Z51VO9&QtqKoQ*5Rss%Kr}GEw!J_e$f~Th!CE^45 zmO^D}fN~3K35INjT${z}{uMXmQ?Q!l;?RM0T^$R-gZe!f&E?EB8d#tHKla`QJgOr3 z8%}_MfZ#*~MMVjU3c4bQCJ=8_I&TS^Xb+9|C&Sn1Sd(D@Pqx3hsLBRg=$ zh?H0BSP~E2XLS1a_dOPe1MFssP)NUp6>6y9kqpvtl0NDmPILJ#A`mSX@g7BdA_MVs zAUf>aCaQATIrHzR7QOnoGz&iP{c$A;%h*3 z*t!30*6*@o8+PWe4N7OCOZCN3BAu%P$}@iKIQ*tj|xFRF#>+2$;((nIAKIpm^B zJpS-Eii%61M@xaLR|l^CUCi~QmKQl-$1EET%Z_14vl<4hj@8Aib*Q$4)$WUGSI~PS z<2qz$u=gPh}FRlo)13*rS(GjJEX?tPSjSZYWVD>KOu|shfk7dqdsHBsu zdIx7}@zD7WfT9;VkBVO4JcddrmLtq#cu{paojtYaBow(zyX}$34)PZ^1?%8{)yH*p zUSrEQAW&1gi^htUWZE8Pt~@A`g=qu3qTRxYbUZZwO&JYFW*5UyLWh`&9@oNqP>3!7 z+o^_}zdaV>1{bfRe;}IgNP|vcF@M_;0D#5ApySpO{MwlRZWEP{!4S?O8q=xAIVM&N zSEwKy%MW5}(2wIK04}OMIku@F29$T8;NJozXdI0|#Vi!#dQn4qSNRy+lD~gJN*qtd zg7{fRRFA%cX4*VG`o1PR8^)#?!-f3x36OgV|#<7;h^L>)sNAjSV6c^11bUp*ZO{{l~x!4y9T{p z%j}Q9p@WBDJI&~{jzs>@kNalX^D(z`GA?GuX|STviO`vFuV#u4<6JRJ-O=ak0P!&@ z!q(ykNJp`#0d+U|g0kblCAEDtoM{!TED)4k2ruY*rbz6ESW~QMP3+CeqPHro+B7z6 ztWVp)Jnv$a&w|VFqA|7bUvEKlAED)N3D=-6#!J=|fC^pm>&RuzrEpZX#P~G*SP_Fw z{H{h- zy6VSHOs#4@E;?X!6yAAqwZINo#q7z|k>kTz(d;HD0sXb40W@l(OJBM7gM;i{2JYt4 z*gHrAd$%0Yezq>5i_zhi(41VI_2z>kqRLmyLdFwLo>WyuWacbekyh)Xc}=!2}Am=!OKAUOrecw`**$Fu9gi?dQa>|06UP)vZz zn=iU~sd!+OihU%yhwGh=_GtV@XHFR|9a!GAiLw2HM=QAYZ zh2vs%fXl8UWG%RIAy*5eFus_Ok#Uo&AD|q_zFRL`Vyt-*rb$p2BcpQw3U!@`vIty0W~06+o7I(KCC-0L+sV)2D^q1DFRJ%ug|-*vI~4v~c_iLIFL;6xU%O zf)+UE`u;Vy*LyH6o6Edjl(0B0`%8Ex`$)+4}Kg7u(H7CC!@ z#AqJ{D+mQPt}?|(DQ5$abvCn9A%#d9&e~-|EA1SefUyaF#^z@-)&saf#(D-A+p=02 zdmg^h-o;_;gcXDW7w?sJ|h zz>T262O;YnW@&?KkTeYr4RE^#)bP%azP7&NZ)-esw}*dQCjKNI186&t2nc3RphGaj zR4~0=!JJ0lohF#G-%Jxs7a#`(vu{8!Usr3(ABRu0v)LXB=9m?Pf)xI0itm8~f?)PX z))Ho^3wr@cc!Ddc_jNoAgtF`hpHLPDg)-g4y(Wm8E|7p5=?Pd!AWtQLjSXWOW6-a{ zi{WinVo(g-CB)5S>xkjmjQkECn(q7`fP{ShB~Z@`E2Ww^A z)o>MAK`5{=-xN=Se}bI)BkK`nDOZ0$(r_i?iqCmJL{iQ$|FXY> zBtq+s$VQ!3GaUe~(7mN}YfHze-7qJpH3g|lB{L+ME1b;JC9{KME^spQC9}O`KI>%m zm&|sOIoHYDT{5$$?t+T$GnxJ*<{EAw@ai(RjV~hUwb5yz3wf77O2{yikaQH+I#%OC zP4?)W=h4H6mtCDfG2f$jghTPV42pYtP+c9Uk_@O#e_=a>yDyOx?xtoy{ndl2cA&1$ zfO^t{deDKImH{=xgDQ5Qrer{!Zb{&Dat}az}Xa82m3{){j_%h`kfzRPKdAu)#z=*GmJfl2Wj@tAys)u6%G<#gv{Xm zQV;MP1-znqWExcYhREjdZdN`1jHyeDqBe(f$DklLv~@^!*5>e8s|eY^+&bpkzFZp_ zEc#6~)W3xf$dQMw@lbm#R$}iw7WxruV)3Fa5bMKBuqRm99jVnw!G&x1&b>4_E9E)M z$5Bpa`MX-!3TR22z)h~sS0{!0V}+}zmKj*_?Y0lSOrq!Lfxcmr6D<43)fmn&M+_`( zRIKtvHG@PDZOLFW2s<)pVr}>%4g3~{{w+9rW3i0!2kF?$If90n*$62st#1Hv5}U%c zGEB2$MU)}hkmy!6SXf?ln2%*{uh}PoWlSf58k|nPUG3wV!{E)RIyemO0enw}=b@Z3 z+#`trr=-aYILE9Y6wr?|#hoxsH3Rc+n59mvFOuTK_HaxGu^8W(a)+A5OA1f)O<;B| z$7j*noyzf+MIy)kDo4&}RF1Er8><{!0MUvZCy0CL`M__|<=6swwI;{gSEkAFC=d?H zanFDp_h7}45w5K$=q5!LW zkfgi-C}5Ql&&?rKl)iL{&Zxd_Z?s2@6WK_pPZIpV#j&Ttq*QaBvu_NM`WbBLzcyi?`R*}`0$%~MT<(8E;XB8iq1}vZ_2xw=5 z4iivk4jvEnmm*il@4W0bp$185LTOOQ@zC=EBf zkS#e^NKST&=f6+upN;e1i_zz>KckQ)jEjd(z_YjW0kUc1>S%1vMiZr5u>I%4AmRm%Z#Rn!9Cmeb1R+R^q3Wd0{R7}cmM`}Gb)|R zEFG0jKoTansv+d|q8|3?B;xqd#o))sk=y;@fDF;kpFF_l^MH_L z@2;ZvNwCIh$K}A;r+jp264Xw{CBG1T`6j{Q*hw86zBpxt`^E59&$>>X;0uu^!Zk4%AIS z|3fceR@<%Zlc3!2z18SYFn`YI%&OQ8LdQ7thoM&Jo=Lxea{7Qv;IDmaYQVflF?}oJLCot6=Apo}@8I4$J43+=LIHi8DejHP z1D$~@;|0vp(Bdd0y>*A+%J{LQ<@Aa9OIkqB?WO1wmDYwdQ-M-9$SF#kM+Yz+EzL}P zi0(Pv|C|Wq6t$lNQK$z0HpXq;bLuI)(csTMNCdnfFWr9jhn=)$KhG|3?FZ^aJI_LG zK{vu0J(&+jIc2^He$p=FiEK*lgcXDW`rfAab4*GgIWFCIVwOs7`?G113oMwmBQ-~M zF9u~t)>Z&J$l5^x)*eMUSsPE*7V_+!dN@J>eTFIKe93sYE19Jp?gAvG!yM#v1w@Kd zNW|d?9u9<5oAw>pEOz$iM|O161!oqFFDNP)cLv6Z{xwz&UJXrV*|T598HCWGSSXbF z?fzUb4E4s}{KHGKvZn5C_kcS}hB_jL|A3PnUL0z{5+303&d~QrA>&*8Ov?W#GPY9;?AJJ_l++u*=v)sMetf*!HK=pxroE_;p)je|piG7+X+y=J-+ZG0QB3MTw!$VE}O(G!>2l z4JtIWr~5d$(W_>f$H`P5-^EBf?YY+DWQua~*C&M&N|g*)JZLubLVx8yAXImx8DCNf zn#7 z(r(p$7tSrK10B8vw z==MS{A%W+4_!+tH)Zr^Q;A-sm(Mx>s=1vssm+FfkW(U0Q3_R6@Zp2^pNDBEfApJ3i zdBH?CPV6CYZ&8dskP{=Mtsu1(M}mi;BDCgvwgxT#I1sl?NsA0{x`_6R*N-h)7lwCh z?$Sag;@wh0L0~S+A483h+950%qhXDunNsl7dy+Cb974v_2700?&T$x@)`;01X@Tyqy z%d7b4F{c%s)2pc8FTE9ecvV#Y@+zjeRXm0E=)$5A)WVD^UU}XXRP8UXqNiKM3F%e* zA)|^yuZp@~Ud5m1I)Z9IWr0>)ol(U%&$+Fr|K(Mj=2lUfUd6bKD(>*AX!zw-Z1|(o zioMgT7@SeX!BRzN32Q+k`N@BlC5I{58m2#c zVrOJ^eJhdw9zhoY6nrj(*um!(CHOr{)}hJvR}_9Ce^lk;+%#5J`^_nca+1H?4m9h=dY-*#q@Frt131@EgMUq6% zJS?cVM;@(ZIW?*=H5gpgp6d0t8r|~Q- z^M+?G0{`6k?ZQ>1-i`gRK2YA=DLk_qEWf-tCpZZMa%lT_3Vcf zqW6vxi-mIase=TQp?3PzPU6zgmIn#x1ZK^n;}K3lnuXpRVLyu@@R{SsN{4?EHsUBw z<@~3oAXVIx(^v|og8WoH;I#WTq~e_1gr+k!OyJ^Eys8fKsv3*H_+%W9=Ar%DGO9aL ztIKWN)u}E~$c5U`Xh*zDEGNA9^bXioU{%AVX%W-xL-oltdtbNN)ym5>kC(?N#(38F zv51(l6f2D6XE5>{`!?dw#tLXlXecAQ13Qh8tbqJC2N+qu6GnQq!pN51=?d82FjD2& z-PMBFa}H>$-JQn_*xh}9^xIv=i>Hau+aMo}S#xnHp+S@Lkld!p`ACl5O8}N2`I#oG z5yjQ9%i*`){5F_h+x#}kZzA+JC4{L|XtgHmkzA(91|*-?B#yrq0SJ8P1ui$Ezu29j z`izlb4V;HrhQeETy}(>zXbFiV@~7g*UV~V|e%t3c5j!=&h>KP9TA@p)g zoyu*5)C-Wn^9%B$Ywy1Uj#~fss2+t?D8!+AUW9N4>Fo+R+b6$Bzvg(azoH3PcMvai znv1^>_y$5F{84bQ0z*1l$K4)`{XS^w67x8>oc`0P#hUAspYE2A^_7RfnBo_@<%7L) z@P9V)?Nc9hTzWr_0Dpw!mA#&P%)~Xd6A*a?W z-CFp7VQYHv~~!wlU$qwiKF(UgUbR4M_^8HVX^_E#O`+rk9G^!Ljfyg^YKQfaG+b5 zWMK#N1^Zm5@KCq#SrkHohakiLyH9wVF_78I5dfjE8w+3d3gMb_xveXs2l{Ojw?v!l z8L$#}ZMHRl6|l0M0wlnU0@$0;H_Qlp5^UHcM?dH$F9;51-mM4Cv-{GKI(G#;0JDKx z{#_=M9?S4G&Eiuq-!`D;)`RjOW(9D7nKm>4(EPElo7p$Az`khxWqgrdS0=2x}&}!;CwZ%!~XHT zDkQMaD=F5PM{~czCD0^tUo^Sil@z~$9iw1&5WJ(bAT-0|qP6|dF`R(`x9~9ZP5sXP z7V-qg$7#HT39gecqK1Z1-vgSBK~(RuRBZvY5xPJhiqxXH}H2(`W@H_!5gck zC1^T+T@l)wHJIMV<>BBA9u8L?Ad%{9*7P(y5Sm&KswR&Ot#`Cy&k*<$8*^GRT93)= zQiscX*lfe)(d5jrh7Yr zrr-$Cb|ttCHT_f==!Y&xytghDBpzBk>b+V+B#|$Nk{wAb5n$G~=W_>K;C0U##0Pf^QJfEym_V zfe1RiKnDgkwillB@Z2BId3c6XKXDM!gTT<=W~o+m$8e=S$)=%mt{jv?A0}kKb~KU? z2N3S`AvnjziSU#noQmWX0fcjX2*qYwk_aV=P>AF)0fgW95S*jkL>Q$Arz6=pfbj3Q zv`E_Eobo2Z?usxD$$ABeYNOxuAvlNHiSRkdVn#V0$)^Jd5BLzA^X)`TA znGeA^>Q00*Mfe?(Rsi8>AA)o0od~BX!Z}Fx2q1LyA>7~->wb!G9uU5`!>{T0^+}|3 zqYvR55JICT0^!dAgeQCm&Y=nMc7FjzjNK=6O90_IAA&jM#U{)W@XL@o-2s=wUZV_n z+IcUcoFypOv<&reP~;_p-F!6+_qAbwwqXhozK!`C-Jnm>Xy1#;#z7L%E;2|wALYE`N`$`)LRA?CJUmr7 zI8xEA!HV2-5Ym3F=w=|D?I1}-W88||H*N_(3GlJ1nOe<&0LDHphW~Y0A`KQK-H#1z zx!te%FZBtU54`O_tbc>vq*xXAPVuxnfcBCP&G&W!(I_vVaRU}lw*}Cq`OtiCLJ%#X zXjO`KS^%xUhvs{&foS6ujeEg(>J>oi;zOGQ0H0CxQ8aES+pi%uln&bknK9YjwGT%O zBzapwBUYt*zoA!e^Na2|eUeV&9Ela2)q*ouS*i%&T<^mv^6_&QP$0A?6lZJz=L8?l zcpuK$io<~xZjO>ZVBLA=fnA(4=1iT+%X5vm;lakKAf`!2h%d1pa>lpfZNjtcdiRp4Y;3X z`rEoupQNo9xNvI#_kI8_>4Uq-g{uYJ3jw%4`rs~c;obsVMF8%4AKaxbTpi%f4Zxk| zgPZKat&JD4$rqxLv8wryQ@n^xJ6)c+Js&S(6ONZ>&bN5w5$?m0XKwGu<>HO~<+)m( zS#@`LUL((I@!U?Hd3*p5-;@^ZAU55*r>dH&kwJ*-Y z-wwrl<8P?Ahpr!u0}i&TaL45Xj0SQ3a~CY(e0v8&KF%krb2u?b3|)w9R=nU3GBfY0 z(caeku&#D&5HevP?{FYFld<0-WDmvq5H)F?2O?z;Mv*deG*Il*;~Ft0@-0x3d8$1S zT$)4Q5l0eYfPrYIe2lhbKAp(l8~JuOHZYNY6w}#AujH8} z`$NvdaES|ZQ!((e6}T&L-Ym;rh9c#De-s33+SAlD=WdbB{`P5{v*CUd()km>mBbAo zVLt(isg14UPf&bZgqq)tsF#t2A)G6pSA{=k%>pG6Cg+!_uY*Lg3=_L6k=^VcfuqZS zSp-k3^ZhO=zx9B^Rjn0>`?KsM08x1@%Is7nEX=k*4GYKH%(chas6;jLFqnZoE-ZsR zLfp{AvxxMSy(-K-%dAv3ZkNIJ!0(v1>hLB=c3q+ew+p(VPHc7c*X`YR?r@at z&6)3(bXnO&#FkG;<5KLb|rjG*C!e8TG zaX1bb2?rn7`QzRj!gL2rYHyTX<4}|ByxA<4hGRG`wAGgTJAUICf^_Ch???q9K!YJUuD)e6!1N_v--e$!59;pipL>AwwEQX>7*mEE&ZNy<{1R%0R7C*3Tx?8rJmf?h| zkp*v}O60e9WzpB|4%Lhy1_lc&~~%Op+BmH{m2n0%?qYbHAVLcx}|`> z&fbU>+ARC8t$?pK;4dk7*!}?2wMA!Vu<}O(e5(RavL|z#k)Gay7L+$+V~a`za5DvP z6NIOvazP3Q=qjG~vw(~3W1|{(gxJrE#Br(yDcn5t=gf$Jupd`k-B-o#o#IvoCINy-CQ%Q7H z$gjXTVjnT9^|W(|w+0}03C*Fg4^oB|6W#PSbWRjH;flNI-U89h7wyz?`)N&G?2o`~ zV;wf{f^Z+g+tI?e!{pGYF7^RPG|tO_d(yzIRk*Nndl)!tya~Yic(BX-l^y}ZaszcAlDq&HszgwSaCs*K3{eK^+WdF*t_+XVIN=_JEF9 zTx4#O5r%UW3F z=1u%TW41_Riip(TZOn2q5I~=v-X_M-Pj>{?=ILnD?Lbi4L(o;lVWn;gHuAa-s!wA@A2kA%2;DuuDq zWf^-Qq5Fg&uWXdp~JfhZ`kP!jngFG zZ(heED}(W8Mn`OO?V7rd1MCQ1t5TS{6nr!&e;2uY^a3BLF(|RM|tWV#yQo2`=oAR2Ps-l zvhMckQn)`O5NzsW4Wc1d2ceXeuFERvqS40F5VKG(=CSw&=C|Nq<6X@6)nh(OL-O*K z1pH(TUwv&4$$(8+%{Wmf14Sx7Zf%KPREIpMyK6g^VgCe+7{H0h%~h+zi?Z=$C(V$< zzlu(k!^wrq@j)4C16`>!l!{lSva3K-&j(^V{n*bM6iilr8K@$y!sg7A0|zBZ+F0R}W{n0?{yJ5qjR_6?0^e zTYyqS_?AR8(c^V;4vO`-k5R@~(wJ`GFNRhLhn;A=4S^RktR2Ixwb!o^1-SMak&_J4 zd6M?a;2h*?5mgV1@~lD9vRQ?@@oY6vl&FtFjz@B^Z(JNHx9YMHp^UKVXVCDZfZN#@ zy&GNidHZPj*EtS*upj8w-L-5-D_+I^R7;<5k<5^#_CnO&n(B0Uyx%^}q(ia{4&V==5aF}D`ZDtR z)lFu!a0LnLD6Kd0f=SoACXLQ7I;tt-F1)Hsp z$g$gD5LdLrnH6n`6-NE=j>|3yI_$#%%|j>b%F=im?hYsfh9vivqcez)L3SrN7gsrX zJc|WRJ>TD}HBzsDR1l}_L8HH)hZ}*IF=$j^BneV$m4g7G!5#JPJ)e|{Tm|ivn zZI9Kg(Xf#65i%+A;aGAW$lSbi7W~*F}OE4^lVX98E?hg1$y=u2uQQ zI*w8@QcZ+m+8Ak?2=0wI>-bn>{S*H`Vt;RdrCi4TbCtRS2qbBrju93wweKtCiNed| z*9;l*bqg>ZkcN%$U#kR27E^ki1Tc#l_@vMv>^b95J`!lhhHf zf#XgUDqf_EhBFP7g}9Nws7cWEfcm-01F|9^GTluZ;5O*@sJwA+dg#U;_zTQhBQShu zfgKthWvw1c4qO3~m6U0!T90S^Q8sAN2UAGauz)*8cMy>N&;1j_y_A2Y zgSg#365M^U-80CHO}!df;1$4#^_UbLV!nN_14|08+0iwWid6EJO# zSxd@Gmt>V70Ggj2jfZZ(l-oYW4TNsM6FmXg`*eqg>bh8)0_E_ zD7TW`FL-vF;*G;=%Fq+$#A-*!tg=zDw_}?s$J|?4R8?us;w-l^eKwA_p1}k3>&)hE zD^Tu3VS5iU4Z$dt#26l#4TJONb z?ya=m#SeIY4?nXiEo`t`XrA>x?5z^%>UbnNeDzegPf4PAfUB%zuOuySr7BqBsG#wF z4eV?AZXCMx-@sYYnuou_peUcc&r|*+Ae3A4p!|6wtOen_PB#Q-9ek&?l}@t++}%qK zv^Qiyf9TXpk@MeeTM?`yX>l#iYYa@q*BE{Xpxk;Mjd^~AH9ve8y_y3MFM7V!#{AdW zzJf-LX}d9};OA$Cz(cr08~h+9^Z#+QCGTNj9RFR^Dz!JLPdkfC<+?nSq=KG%VhB*!LS93F%mW11fR+oe0)s3Ldum33*qHO zt#}6pTJ~7UOJ_xzP~1~F*%d!t_-{hcQ_{HD>na95Xo!p|!o*XPB^F{N8HKQ5+7eZv z%~Jd!#u?$pm59qmtPU4WDGyxRLa=9Q9f-cn*{f;hz1PSr2svY#eC_-jS|6mWdZDaI zjo<0=$u_m0;KF$^#NN$)kR$kx>|q86L3@6(j{0O+4f1J-puM<$UvRv6si^#CaQgoW zoMC<(GoM9UU|LqQeTt|@zTG+j!2@@4VO$uMyG{HNno0B=jvr@87DD#Zmy7yrx4+jj zl%>z-0s|y!H9Ijsh>5S>Vr1vUs7-KfO(U!={us51Zp{}-Zp0X|@fd5Z6Qia_l7nEI z^|6w*xKbF(tIsO#US7I3OTI+QsA{-XcdapwQnH3Dd?tx0{d%iLUbu4`AGEV&y%#;A zFb8r8zl0S-+^$-Ome6{T&oRWtSL?$s6|IfEt3_BWU_XMi*cGK8b%QX=-Bpw6&xyQT zD~4n+iQ9xP=;1R`Tdv>Bv}riLnFV8*E~1G6NnaX&{}Y)`fN@?MJ{GmSk9@uHni_%uoS| zuQ>an^eRNk(v?IwNqZXRay#wa!~DG)eDDL%zTREycq=f}HBDAnQjm2S_q{~Rjz@aq zzCf^y)*-fp;}~9UHN)PUM_Aiu{KhF@EkS$7wVBqoW32Thb%4b?$SD{+ov}N0qVSyR zwo?~SEH?+tq@)_o4K?GAf)=Qa<*8n#w%j;wA~X?@tY)X#q*)MiwC#*>h19_S>cBt7 z6=ICb0dLMk2^r~ai$mvdmGG^E0S$Nrhs#9s8BteAqIk73Za zny6t#(tg#8v>ac~QP|O)s+=cxe55V`DOcEPMs2KT=J?SD202ir<9m6(jDrBFFVJya z6=LN1HSwV|>3>XoXjT)`!d&i2!;rnG$k-+4^iV7pMMWqL!9-He~k z(F}cUG~VqSV40!*!b^fhdrQ?41>AoDi$aCML1Y)R9iWQ^BLpmIpMjYJh6dwHdH{T^ z(8lQj2ErTFsX2qVh~7nSUIcE8O5mBDoiNW z#jU*9X2c?~Hz9e%aP<_2+}5*{$Awq$4<)_O83N-y|9J*QAY*U%JZXcm@HYU9@1Hcq zaWY=!Atf@r^YTGZ_~L9o>?5R$s^UetvBGo8OLMb|8Kt25G4x-+5J3(EQVbi*R{ikR zj;JnSG@~$Fd`T6Nouu7fC+|j{RQ5Y4iASSIC7D7D4}ToLcHC0bowaRitd1w6Nhnr0 zLFwWCy4H=;DZUd8cG9={(o->(`BmolW%h+ue1UA7&=i)ayGg+EC?p*>-Uo| zIHCWb@h#4p7xm$v#PDh%*y~QtM_~F=2beaTbN0`lk7zRIBbvPP5l!x(oy)m{NZlFe z;o8uw@@h0MY0o_0H@y0G7BIB|m>rLtgJrZ5ynrYpkVvG)`ViX*@1vFVXe))KQ#D4E z5SOl&V+ph#p=yy4Cp)VqY@dW89NRHmPKb-S zn(^~;OnA&)E4UiP-??FWjO}R`Xt8+c-~Y}(%HRync8GI3H%HsybVizSQSC6LM!1b& ziL+nsFq8+s<1TsKLFqa1J!S-ZgTEkpz-qfwZqX2tSlL?`U|ndKrEhB}hSlNn(s}Mt zk6yaoEyilL13;@TF1N<&MZ;*lTri7CS9sr& zH1$|gZvb-y^oca3&+G=jN$a3lL{i!=26Z2AAyGm~8E#vPc9J+yfV+ ziU}f5FLDg@_A}5$arWmel%qE3d*PYK!s6Wh4D178my&D=KpT4+4cH&zHH(O6|=5Z+3+}30$lGB{41_qbp#b5avI@GB=n%!Y{;Z!CX{k z4ceRrd>BFUJqZv*WoE>kM^XSon?Dh;eU7KkNvsv5srzezh)qdRY(TL-pLD3zKz;~; z#y|*^e9J$x_Lb8Enw{{!PqW?r?`Zbg3IDe>3uRY}Eok2}8aEXF ze@u`@m-`^W17~KKLYg&jc%t@ZA*r&ked?~XA(wNr zdJHRwbr3Nz)+@_~l4!#7K}DJyoS(MoX@c0|EmH{*J*W zkia&9;xzS#O=g6f2-|iC{`A3(z8xbP2Yxf8VQ`ZX4VmDF6F~Gv;Rn99h(JawOU4AW za)!FTb!HI3A#EMZKGDGp14$7F7mQTSa88iGV3rFKWu+grD>j20C&oZQy^_kI0#r;IdA`0c9-HI29DZc=3d7Hrv8HWx{D>Qt zIC4`L`QY&xv_7rEcXpsT&2gxYY}W?#UJ?_Y^e#-_YES z-v%^y-2b}fxXt3%+y>J{cdogb|F>xl{a?nWhNyPQC(r!3vFU%Ie@!^$|JTy5>R;(v zYQYR;=YgP4OCO*|(;>q5eaNKG_p!+MzGcyXZvO5VvN?EbHF>K=Iu_B7I%83Irk-0e zD@NWZm0_z(o?sRjms13ghI!C2 z3%1+VnAM2=!}OVAA!kFeS}bNR;nBM_l||K+=4(ZPV|I1wt2tq6#@rU8z(3(+m*H2| z5S`IrosI_U;G`wr8x6eapz-TB(=7oE6M%op)W#V?TAdN@FJf4nHX{Uz^$Dgn9F;h9 zQ7RY$W# z;0(quQIf`hmknT(-h0nv&EI(MaS>+8wrmLnm-s@#zI9k#>sVuL%T9H`U-WW$@ed*PGPfi1yR>MCv)wB8w-ok= z7c%h{Ao@8EGmkv5Ke#Lo*^v`mrD;!Umcz^q6xEhWZYSzVJ!jdt59-1VJVglQao!|e z+JL&6%|~zhVY$IIfS;i=oOqzKg&&r|JqMBYlo@ky6eHUtH&n{N0l&!g%vN8gAtd|g zgfr5IQQG{^Ffn>%E~H@h1Fm}xOW0Y;eD`eCcE~8$Y`SXjTiRe+{-Y1hLkKQiL&7w+B)9`> z`ps0~!BC+c?8J{io%k3ff&Qa+y*RGQVIjfSW3_J6200^vb9%&V{9F;(_&GPQ@so{~ z{o;+EBMbZ+KRwbme*8LbYp>c!s>FG7WaS_<#6A*ZAN);lCvq%>vy|no-FHC!()FZ| z$uvLvBn>Th7g3_$HDHL)9YS^-7z~d~S~r0Bh4Nk3yXT;YxAEane}BmQ$YVmOqN})*8&sdB^J>=TPNIM2900 z-9#{93dx~cC~`i590p_=VZaP)XkxBo6~M2hKhtHOCN#D`%|mx~8w3(!Rm>*gl9eulE~8F8#M<2Ftb6$9039)HCZjG z--Bv)39owy6meQ%eONpaBoRv^WR2q;@RzX8pTw@Sd|17RlO--bT^n3{dhK{#k@rDX zs!uviROfD*+ohq#-(=1`#Ipep{>f@yX}3qmdS$dx2CU=$d`+X)UT`6w=mm*)W1w)p zvBmKT_!#?osR<{hf(Vo%Cfug43A(;&}NQ zG?Zu~yTL3>^@i=iRhhww!2n8<_E5{8-BrYy{wm8L-5CG`VZSH#p-nAf|2%&M;WZ)&;YE$Fw;(i#Z2QWqft4zYcG3u9s68!n~^;a*cBc zyz;_Sd;@BAPA0hL3cNYHF3Zr&Vf?yMGNRmlC1D1;wG>dUZEX=yq_+;mNt&7}sSJ7hv_UoYGWl=#zZh<+3`p}FnYKqbNR+7^Lp^I5XfcPxLB?6g4sScZ%uj>ijr%%k?ANGT!azCJ;SuThn{Ui%c7Da;?fSY_lTg7cH$f5%@py`1^1~l!8V=zIbCc93ov(yNue=eZNgM+z=-n5KV)e+u zCXT{L4h|jQ?A^LH$Uo|mH!jMFeBJIT1cm#9G?_cxYPy-Wi)G1PxQl7J!8}aaG*H6d z-Y&)#^fPINQ;jRyyq$XjUVl$2@C3vcf*eiJL`=(3VBC7e!1Vqxo%+UkxET`kB;Q7FY|^4#4PpL81zo&OL*pSsvi$>&xSvSXhaW< zW|iRRtLLCE#>>pI2JAnKI|L4m%xPY{+Zp{CqsfqS8QO}eJW*_%QxA+QT`^LdN}NG2 z?a~fvKwXmK4B=cgvJ_#!k99)bf%Zz+#G~M{V8d5S8?Xcl9@g^{H}Mj73&14pbDH*FyjB`we|9~?PWOLAca=j){C`W;?>4?MzJ)>X@wg_ z)mUF(J#;-LYFJ^hDN~fT5=f2o1yUT)n^f}>Ncmn|{Q{GiFOK1ht1u1*v)205>s6*g z@PoJeO4qj(i+@!L?mc7javmaA@(^^goasoH9mBl}bNC){NH?CkPg~hI2O8ncEYPmn zopp%6ALpkR-*&hZ??D8LYZ1Er5=x`7J3yHmFYJmrhtuVA(BQHFh=E|O0@wFdiyx&rA}vkn$yXX>hJ=l zIh9RrAT{CU8kZZ7kTb7?#0@un91i|`n8(dQ4mUHu$CCbrMkoAY@jPN-W3RlS9ReNB5un4Q{rADZp-i>joDvyYP;X}k z;v7l_yk(_^F$+bz;FoLh+bRoB;*UT|gvEO?N8ycqjHW z=Qz)&&f3#Xk42s4I~H|3kWE+J*|Dg|5T1)l!XZ}!0UbeB2`)$MfEOD4>SJ^T7ZO}5 zm_Qsf828N$VX`K2L>7OOkzC40lU==JFDHph5b~Tf!X0)y#UGsZe%&A$>1i`DOg&rK zLi|8Gt0)T{3vcm;y5=FwK&YGO`7UM|EBG266ssC&fK$*u_J|^42p^gR7*+oYrhgi1 z!4eAdz!8TzzRp~7BaqjY6=g`e!cCxiSgF8O0Yeq~lQF2VgCBZNm)ED%)tlPbNT zR)N}|JlJ6k_iG0@i%m%aY{!lM8IOPcZgfvk{&99(9}Q4S@x@B;GU zt8*~wlxJsIOB~>>B;@;pfqHY@uj05fZA*yo#u9RX?S3Bz6l2<9=zYM1zi;Y$jz2G=rkcn}RIG|B+b61a zC0vuI7PP9~Xq1L4vyLHI-Z}*%H-8qEXU!Zl)h`;==zrx6M<_&P&H9V?x%&zqP-D_QVLvZ@(m`H2PKQoB4r<+ASOo8! z=s5+q!a3uD)M|GC-@*DLfzeaee{taJt+LX$+zU?x$mZ1+HpM4rzh=N4OC6& zleFid$xt)_!B}L|1)= z@DKa0*>5sP{?L9N&WtZT@q7+Os}nnDfWViZ#72GbwprIU*+F$G7dYxBCYMfFMsfxhdRY-}$+CggMEDdWvbFcVYSj!5}%GKbB zRQ2kDG z73OPDYXfWx0J%syfjm1q=5ih6rc*%Q$V z%9}&s+gAY)BZ2vV8onGbX+BK7LpyevMCdF$V3cTSFslQN`~;_=-guj)FUC)*bf@bE z`Q?^-llCCAoT`N?+uncyhew20RO1k2Y7Gu7!j6iX;-_>#jE$=cHeo#hlm3fu?gUO) zJ0Sv#1u!iLT*E@K39hf|F7j{TOwxCeDG$67a3FPpXmo=7N;I0kJAI1TNv`f?j0rlV zF-?Ja!1<1SDczWEhwpY?F1}?0L!J`~=xVt8=s00a3WCjoS4;HlngO_ZU$Jn+eJ8eKU1+q?w zXvNChgK-YvIgKWD!rciM?Lm`Zb@0etN6OUZy`$GLVsRO2s zsRdQ8F-=Raw85dumQ60NAOI@m4{tvh?-a*pGpo%?#Z-BXGQ&iOGa;pq)yqArz>Si406vT_l+GMrWF7y?G)zm^? z7n<^Hy7-UWt5xwYhrHSPP#+eD4(jF;{{@ogb9Ca;rubZ%H8aq%1x^FlGMpKhiI&a8 zUAl5+KrOy#W}7V|8+U?BoEcD0_8CmxQNL9gsA-A6CTyovqNd6b))LuHF*Q}TS(Dg! zr&ery5y(0={;X%?;T5y#Em5t$RWE-VxTC8Am$>aa^d}N<6Cro!=pThq)fy zuWKN40u|Ld^k|AOkU6Mm4zHEqew#6nIc-+drW0(#KwMMUsKLJ($i7B|9~{VD?AfY< zj)q1kwHc5adg0v8J_UV*yrlJTpmp<{MwpKFFk1KU2y32SKM%LrI@WaH9!5WN1B9RV z6NY}~g7DlC*7JV-%x#;nUq5H)@aXF2i9kj3{S`q!PoSbFa8tEkKTot-(XZ4`36*bj zbLx}ny6N7dRoy%UWl&;Yhyx9E$nojsIB!hjMv5Wbm87M$PK>#DchPI1AvH%yz1qn~ zY76pqGS}P&dZ`vPJ#qmfn*CD+!q15`LbJ&r70eb#-E|&=gPn9UmX|xGeS~|iOBu1S`egm5!@9hSD zF%q=2zQt##KcdvbxBXR>)(lggHZn9dpRGx&?QXZWa7JyHIJLf7Fjwd73_A_e&Qd92nW&k>C2az{zzK+XVCldNpmKhXr9;4JK}Id%XqB}SWORIUOy(qT;E9IO~ z_XJkZC(QM*xhK6BYbR5~;4T@{^E*(D@DCC{ki(H3N;sbtpo`$HA^zVtG6pq#b61)R zj{JYbdmy%wo-h7HjrkH*fE1c5! z%nrm)jeo*lmKiw*dqW->Hbq zb0}Z@is*;m5@&$1S)ex=bWxEod_m02)p8^@#ROL;e16F7QKcuiPq~?U_7nh$fB5g zWAeab47?0Q#GBe(y;@iON&8;H#8~O`v66Z4B^~57N%r8u)%aG-{G}uPl3c$FRFEi| zAGe;zIRmKj41|`j7PB_}C}8=~65#1B?I;9%fsF5RctCnddF`N>wFFn(l{f5&S@V+? z&R1~GiVYF&2qy8r2C>=vvh|;%7zo|Upix0tQnr4(CdwODY65G6Ei;fboQdAS+gI9G zjl%SB5|{M-U$z<2*$seh*-+Sljnhu=k?OIECP0Fo8;Ueb1w@d{GK0f(;% z%Xl#+bWx>{cXoL8W|i^T%!?)}SRKz5v|#4!jGXqk5O&R_&S+d|faJ!G7%GL5Vu1oG4x7P|7xwDyf*4F+1Zo;$T7tkJDVVY!qZ3B)S^Zz{w`Ok{;yb8JB1)Cy`xA;z+T2d+wncp?Y5;F7pZXnGPb< zK2yy*woa=qPzGjYFwoy&pwVpMHBdJfDw*Tb$?UCUF3KSD8I-9K#plpfqKQhbcR&tJ zOY@k}{mNlkMmC8`x>Xc6ERA@@d%49`rWl(j4j~wObq}-6J_sDb#Y;emOGu5zZveU$1^rmqFyNBCA%r(SFqlx)O zBGPwW#Hf{7V?C-u3npjOIAiBE8aE(w1PMa0cayZ2vX6n8pifvpQjobhX`#L%9(uhw zk6pz69=^SaKsdJfIS~ z+&pk1imz(m+FV#eBELOaDU8^g(AAOaI+8(fef1dw9KTC565}}HwxoR?dzne!`qK`2 z!zNmr*e^Xtj1HpSIRCsIJLst>4F4C=-^lj)+li<&Bii7tx#5}Rkd}@SUvV^$VI4y| z*ytox<7_O>qK(Z#Ni|Ls)<)w65Y5A6^6-+2 zoxB>&Le~|tuBdO&PW~Gw{~O^eX@B5-T(ZbA)h?CG%|Vw=%DdT9%_hup&nQTZC72$mKZu7XF#Z!yML~lJ$%HrAOe+IQkIh&pRIPoBgDomXVcs< z4~8F>oSG~Ok&2B=ACQCC1~xeTT7b^!y1869RX56(;Zweb8&d&G}y zw1&o~IZV2g@<0iWUq`P7^bj2hedUSJ?7JxsUg)qMa)O`~x;qKG2R$Z2(zO6oNiPDo zDvhh8?(%9lm7z<85YD^7m4QthUk6)S^q471NKr|d1WdO@C`dhkg zcarg#lf4$Y#VHxr%ghC*=^iB!dK3F-K&}ce4&8_vaktvjN$VN53im7FSVN8V5{_3) zfk>I>J38RpM{mAXi}NehgurjD`K>d*_2#$1{M!7j!KE776-Uww#jMI`0{@|&bG{cT z&WR>U%Fvc7oDY3qV;-2qId}Xc$jNZSF*ztuzI+;4yI~Iq`)o8tg?%y<(fAlVm3J_t zu~;0JRTez(Auk^pi617SNZR|rH$xdTpq)Tx8|ZH!X1G4Sh}y{1?B`wqYN#r zgQ{-B6;Fr{Yn@sm+6QuaTGpscOgw7~v+yab8>M$ z0t>%#AQ=E%aY39M^UxC|C>$=2;XC&O7k181EiL(+s)z5~m0WRArvQ)c5E7=zBR85{ z#a;&=BpSddwE0B|9&n@#EBb_hs8<|*-NhGOaP7s1M^|2V$)(p{aKqu3MPrDtrsYIm zMfUXQ9)t4S#6X{K^TNP`f5d8;KH8NPj2wEPK_N?z{96UXt$123- zjmOHY+Qwnp}hmn%Zzu&@%dQzNj!7B8_nkzH`Bm03QP<=Rq5F| z7!`HAqZlxJa731*I{cEpwuQEt@os-$DGP%jUjKwJePL%Je2?oe2hn51mfKKSY~gw; zE;hSfeiE0#x<+e98y!o~1!0*rFFe313lA7m6&_GDH$33n`QZVVREG!rzAikVq#-<@ zw8`gvE26-`Dk)aDKoL`yMbsd)s!xn>%9pdw_EWngDJ` zcV}V?VroXtC0>qo6TZJCI^K*lMZ^E|{p&-7FMSt^S#77|zHwC==%|0T;1_3-H%x z5VB^DbztPe8hDK}sPW0D^)Td=FDH^%ge2HZ1rm#3Uij8d8K_%5I9LDM{Q74#t>_=E zGvtl_6;AZ;piuuf$mZ!Eelb3qoM4q9sQ<6>jQ)MNd4Aj>^r?vo4G5wCZ+!KOvZMt1 zuk=;8L)GHagj%kE9XSdKt|Qz6pWtevfntd*?=PmYFi(DFPn4hko&B5ip;4}iqkpp+ zJgridu*~RJk3>}Xavt?y9JQVGyAtHQ= zORZ8zVm1-cAygc)Xg*#2fKwYsuFlP7nI^;D`(QR|B z!t&``oW}9JNbW+VIi%N6t5brxr*_MM=wM!E(!L5tOkq1M zR7wo}6m7giT}vJBB}DclB{baHKK-9~JX5NW4as8c>4r`+&k*)3OaPGc!WVgbA1S-M zDI2eDJQ7^Z$Al%+Lr@AQBH3ApBeqg5J1Lict#G&;KrV|MF82Y(hyQZ9EMJY6SA3i< zV^QQXa{2-Jz$0`sk<%)2`iOZ3r=KHmMo#+xrw?Rudbyxf%@G3+okRL%bNOKSJqwIN zs{6S7-taB>JXh+6;VE8L?_>P&nZo#m_)&AHh7Sueeie}%#=(hC&}X>x9L5WzzA~xL zFh0=B0^?JpZ-(yv>}MEnhDxIGsvH>`LSN%4UY5%TBk>egP9gDU@S}`(%3ypUksQWx ztiZ?kgDyRX@k*($OzJa?mv~uVd@)>A%l;qs-UU3W>g?m)GNz|MjlRyWVwQd+!zhw910GU7*}}REGU93fF30snvF}a#trQ61#IP5BVgv zV>4?l^~MX@kluI8t$zBfQ&QHea|eg`VxDcuqmh`WB=}TyYbUvGt*H4`(%xjJ&L80Dne4PlvK7pUE621PEG}_Xp z%<6=9@U`;mLSj)pbM3{mqk7}1ncB4Kr^7qyJ{Jo)OOl2%KVSY7 z{R&Girh8j|>WixgYW>CiZWFltQ|@%#d8@hI*_olcG5tx?eRRyPU`bZf2S?0WkdrH( zjy(=T$`W7ylT-=m9eXw1L+7TaE1UpH{25H$*lyx!i@J=XT~ImI7f_4miFdnQFNqvy!8m{5eFD6vu;JGy)^(hN@q~=@8zv)7dy( z`kMMAo`gZ@`0MHMr<}f^M>y}b>IUYMedjo8^tspWGCrn>VL>C45=9fAw)oJToVk&2 z{5Z>HCW-WcP~PqL3)KMB-)0KjSz!Dgq1}xZGpiFfsX!B7{iC}3A$R(8mNYrEd-Bc@ z1|U`oJ!;}yEfQ2BdVC{(X0(=n>Y(NNX{Uzb|o)xfg0<)5?9}#dF!wW&h5Fs@htDf z;A^;R6E}aN6pPF>BGVsGk^n~A9&U+v7;QWxF0|c@KpV;8c}d|N5+nt! zQsGI^W43Fs%t@v{ROnH~1tE@vpsJQ}w&$UtQRtSUp;8Gkgy(Xr>zUzqtM68;*3vpF zN4^Pq$PU1hhCPzrRv;n+?*l1HMG;!T>)}T{{?8h?Da36nd(@0t<5!r7m zyFuI~fU%T=x=O7lI$pFeM1W<)c%yJ{eSnmb6{(Z#+Au`NJ=fp%&y-txe^*6511bF$L zrg7WNxY+ArYnhcc>oYfrS4jY4I|d;2lmMiX9Fj;6HC@L%>mMm5u{Yi#n$n3aRM#X{ z*{|d!@fsJs(9q=^6Xh9rwSzEIhe@&mCRtL0nm#8A^}sJNPEi5HxdIw&0$O^eLw|&{ zBttZk0xe(m>>Nj;JB|&+(ZU(e&fY#;rZuFJl8-k@t5b^7C}0>NIl=5Xb;v7|Oq+iw z@|k5iDQnCCwYyTAS)ItlPWRN!n=lW;J!ERNbVFn2szyQeRO)_!dYn!!>5_ZO*O}F4 zi)jrKA5@c&gM6P}p8GKUiuWzffUC9_HT8jeQiGFjd>tRA(hO zPtno4+`mbwyiok>g*&4dnnwVbR{caoqxFVLxY^-#}2*6|d+ z_6#*h&O`R7Pqe6yJPVD1CFs;uwyj*+gIi>*mVqj{-7QNwp)0H9B;^#wiRaf3N}I&H z*5w`V{w6NuCAV|H~ki=+}fif_5nJ1ksF$6!63^e_nHL~U;ZK9MspF&FIO(GwuU7){(@X+tiG$xE)l4K9HrRS;@ADz8a z_ETjnz$lfYKZ4+Fu6UBy4Tg46;h*}@$E2dMa!_ z_GDkcV%0zvH*Wp_N{E|VIDee>sdzQkz96}`bbq}+ki4(W!v1c?v-u5%Whya?@8|5 zW|mteORl&Ev@G>HEKrXuxP0WP6MQa*!j=rLNJ-0uUWc-l0h~JjNIPD9O&O8eJ!JkT z6j`OeHE{#1D5#1vAiLD6wI^BL0983ST}B^FMmjwHjrGYQ<};Y3VPRUN_*oKAtCebC zt)fvQB%UU*#`wzRlb3DIs9a2tS#IbM-!oy;yA>r_O;@vqNs03|hs4uagOi^M(VoAv z!!D^pj<=1=P>PmG8H;{hzp!FAY69v!E^*5r?4tuSrRyn^^ZTt5f?B=Rc7|C<|HRZp zOmAP)Rmf;>iTBY)oKQib$q-z~h3)fu1QPD0*xHG4i)8MLk5kJz{Ies4C zuCuDW;eK-w~i&2j`m0BRp84X9%xSV!W+ADLoziUq4*(NrC3tY)ZTzZ%B9thP_*N+x^iA+MyAJ9psZ8C|?p zOy6a{D&}Qw^yp&!<&SaQ6l&Gx-*OAB@qOZwYrEv*vPN9KZ@XMaMpQ*uU@DEA6Vfh| z*q)ba)N&y`%v#?5io4#Odr%5nnA1BlXVBvcvjNW?roU24ah3jP%p5(O%dAdZ{#Sb# zI6(p>3M@<6kW>!_7-A5AQV%AmF_{vd7wRn`3EkWav8LHNJ5v5M(-fC}a*=B_owh6f zA+6g(5@xjuQz|~bmBlov{O)TivSU;0DJxa2ZGHmLroVq?8WwX-A2-YX#2|4qepas> zqH$A6NG5Qch`^PXlRCv)Y~uamOBFiVqJ6MeZPG+mRF+z{%D$WzlI04OePw9mC-I^W zI~rORhE`J@dbWBd=R*7ql2%Ry8P(P(&Co0E^B>Smy@vM$T2dpybZSjwa!Z=W@1UftL@DawZC2h<24@ryr5kA1*?F1yPy zdLdronY)|Ei9Xy4h7tr)s^=^zf_jjvjR9o%e-@>@@Jv66Sv_9zYnpzhwEd_+N{EZHM*)WX&h&8rD!}&5_d4wM*A3MujFJ z%|9W7U8kiFQrMcREXUuLb8TIxnA$bvUCN8^2U4P}%3tcQFO#ELOia||=TM!Ms&uUe zs1Zk>_)!DY!~?(o#@S6-H$^(}wTYXMakA`0}!DeB*-4DxiB zJL;4>z93-TI`$`srguM4x%7_2^+5<}0>4q~_)q2y-fVABZSKCNKPaX{w(TLn*JoQE z(Uo?x*FjUDEyc>kUXKtWrR`uU*qCut7eg3UlPKtD6eBrlgJhsE4w`RsPsQci*%oA0G?d_S1-H5d#fUB{uv`q zD)PQ}rSk9S&|lP(NcA>M(MaPM7EQ$1Znz0=j~ zsh5_`%QiUdR#;N*l!m;EMwF6L^;=R!ZoB!nHk&aVMIs+~+1GSH4^L|N67p25bHPE?3xf!9hp~<(_GRtFmRKOjM>CQfOqm=sU7z<{rcDTrjEq_ z3U}*IiC2Y}tV|#d0}wSz|F+fiZ(F5*dzP9kW#KWW6nTvwJ=?RoXB+ZcDIWEj71Na) z`?2N4XG#?fxoy9uyY^;++}FE0xDVcuP@nX6aQJaLxQ^OG32ylZyOPI`Bd^WzN!}Kd zvaVS77OPgk$@Btrsr(Jx=ie^c z?xKclr-p35%zxkV!yU7y)ze2sq5Ir5oZIi(msI4YKfI;-+*)s<(z{A&kB-4;UAiMX zvx~@VjT2dciHw?}>$h5Law&rjo(3n1hNzbUk-hIJ>kz7YXU4$<$le8~d6o@qMwtxdaHpQ~i0>yH1u$zEdN$}5 zrAc3+o-6Rkuu{eX*h-m&MV3E&_VR~EUX~WTvTUr13$2l?aBFLN;zRYc(7QrKR$v$g zwQA2Yg%N|`R=V!2` z{@flflj&>dWSgc(PgZVvM%Cq54TWoE>ozb`>y}M=HOeBNS$$fhr}pYXy~{?oJ0bcc z^dUa9PB_NsI=80Jp249Kc@9xEu~T&Lk&V>>zg7lEVy2BY?Fc%fihO#=9?Q^9%WzB{ zWptuysbkZ{^*A_I!^)V}z7pS{j&DjcZ>O#Xk;s;;lzk*^sx#QvG{+Y5d@5`zvnN}y zD|=IMX!}&Ar{+esy(xn=rMpb~LdLiky}#76gq7 zC^L@wsP`%3S!6^%T2^{aZ6BH;gW3+96+fjXjta_Q5@OTk_KV+OV5t24*CQFVPY$x| zU>{$yqnD+NE-PkPR~2RXpH)S9TbWnc$vWaD9r49PY`Rj%L|r9G9f}m+18?X=j_@Qh zO{y^KL0DLWqaT$(B^s+#QmWQ_l-1yrfYKSa1_^``k+zs9OzYU8G&sGdYK;i>QD3yf zt14P2)O};4)lO0UoV{LqR{6r7sfIJzB#@Y%#-QVE4X_cg8mlU=_g z(W5c626_26ap)n`vfsLmp-m}vLDyH28a$dHnXO|w$z{u_KLzMzdUR4;? z>=L5MX~d(idd1PE=RAH-s$6l@QU`bHNwD1jIws^(d+SZNd1THLpMvlQ0EnB*;xr!v&cvoeVUFbwqsV!YLeUIuelWKFGC^y66zJV5%J)MI<9$dU=1S0*oiNMs$2MNQkCGU#!oZFW~_ z`)5iY>z^q%)Ha>>%~N-4TddSQ;7Q%sXqs!*@j05CYp2d$PO}HxEM~FeLwMcT* z?rZgTP?i9q>hFF}3Zv@pstzf1%C=JqX-~ASze(E0#!Oq(vX$)zi>lk;Onh&XWsF`Q zNIk$(+*=|GVaQ{Hj9MDotEE@wYqEWnld5mrNwt%+FdR&WRp(*Eg=SQp(vt6{>KiKC zI}H+v3I=oaiGcB^KA?q}a=!l+v*XmO7Yn)M)Xx+7r}h6O{Oi1oiUEc2JKH zlv<*cQ*o{431gM6K4kik`jpop=WRoyOl4FJTu8cfm9io`xRz-!%sczT(6YOic%)BH z#<@*uT+1m+R1YNk*skCqJuEhhS(W0;sfJk?dQHH4w8Sh|(`wYK(zCypXnz19^6ttS z9Wol{HC22fPNFhbGKQ|<^yMjQNc4Jn>BPRKR5miJ{Rd>B0FtE3T6Bk3P3S>HAbyCC!q*$sQ=F_u%w)2le&dhfz_TnA7ag+4D3Vs~lv|=dO9m zi&?Qe@`r|m#H@|Wgf0`D{3XJIINi{5f za;>HJVa12NqyEJU5}Um9`AN*NFI&ewZVT=X)10+*zirBHi}99leAHy-?w6&nwgq2C zP#85tV`wLv(cDnslsT&&?}i%fhXLREne{JU$f+G$d?nT=pEOBrF*flaVY4;(@eC5a z$B{z;Pe@G{vuU}RC(&!q!VC^o`}gWp@wwUBU42AU>24C!6P1qjYA{c-$JM9-2G5L3 zu3rwS95g*+B4Aljngx$P@o)R9#-CcG>R1oQzUZnAeX3WecjWAA`rns~f2X));3d_N z$(yMt(prTEuJs=sr$SZ-&vnU}#GOK<&C663X=2zRC-lV*OvkU=L8G+kj<3j$Rpetk zw_r(j{rQkwMKy3$0mdd!it6Oiyk>a_Ew*nC9kt4s$ocjSwQT=wZ-!YhuC_U66Ai9@ z-`E5pTdw=B!X-VcqK0c(S6UmKs@0UTj+by!XHcG#Jl<}K!g)sxhJenT0)BF*r?O3A zbl|RRW2;vjp!7POF6`LW+kL?LDTipZT?W|~gP`|mpwt?yTW`j62a&e3FBesmf5*O6 zm9)0HPYasEgXmDIEiN2{k*=b4O;!SjcpBM`r;DrQOGtgGQM5WG$ zkWOm4=Q)>}R(5#V;tDzbHO4;vRrkCr&AQuCvj^S7Wv)H7_tQRF1J(XKNRNtA7#5uR z^v@mFfs{F}ygT!HY1^1O)ka^$&L;ESh^}52vQNGL zKq*Bc-Zyr>eU16dmXo!5h;SfLsbUST*YlX;4J31ebR$!CsQRm$`(3K@T2;AXRX6qF zR>??O%Fe80PU5b~O2!g*jJZLbR9Hh{cWc=snU!L1xy!k#k}HX2OgCO9B!$&gOj)j& zrmAqCP&=#=T72{6s&46^?cmhwr$x2;qddc}rO}a=2g_0R)ijS1Yv%1kQurzX9VGre zrK7|J+Hh44ni-Bcl4Igi?$}A#TH$Dpt1?37!qTsNU=PoZL~Pf8YUi@htghUixnyH;JfA1(-QMips8}8Ttk)+hIaaY(AaPJEyBFRn6#> z%#p5SN*H#vY2JH066hGdh50P^+6dS(>dFXoZYpaN#Tq)lcw4S8-;sb zh44i~-UaGQQk6|{UkE23W`YyQyG;AML*7cGRI#>VKH)se2Q2r4zXIuq{J+$<&rqkh z!w497%w^iZr3f}6m93lBh zpfvML>-Ok3)<^-#OiElLp=NR@JHKA{73PH&S#t16S+Qzc)X8yiq4nYIl;>RC(e6Kd zCSv!>pJ|7iOXUCY-2D&az%> z(c`0!`)JYB=yC22RY_3Bsc-z)aXmt+h_~y}V~@`BzYcLYqsMkq;vHztmzh1aU`vNu zU}pD33d;yzM)`WcwqK^z-0wFjzM4wKWWI96ZpV5yQVz6$?@1dbo@M4hW5V_X&k;W+ zx#Ionzf@Tw)KfPpC)J&Dn>C-pk(L#}`lW4ESADqPL6hoN)!k|4Zl8{)l>}`Ghn}2P z{iOtcL|RPU%GTQbmMI$VYy3V%u};wxql-=GVnZigY$rn&QNU6Qq$X%x)G&CBy&$*V zU+c__YN-(jZ=jvy`AfQ^(@=`O=iwpl`}DByJZFc1?S7B88@xMK~QEasGlvxJ&ikMI+}-5Nbt-)h|hhoLT+cd96ze_x9|bWm89Ql$>N)Uaz%%_cJk{a+kaH82T47^MsKGsGHyJ>_>!|` zYwr-Ptm≥M?6wo}+qe)WxcoB)AjGe^w z66Y6eXHmLwmcwySkJywHghM3>RcTXFIBWWBp!_{=N&fMZPEoT!T)jV|`t9n!ubJ}s znwhP=~!nyh$p*~mhKTw>!4N@S3v zt}*DWQV)nWul6_-O!9|>8|IxnWJcIcPki6YJi{+Ch!aG_mb(dYpWC30tsPg1GhMKv4 zL$wJkQ=b@EJ2rX!29<=hiGhcGy#7+D1ZUkzlZMDMF6TU@8jr|soha#HseVuPAM9ww0#d4!CS(aT zrRoDML;osmiIj5F+Od7KzMIx&%EGKTq&)p&W-j@*3Rowox|8 z+bUa}V>Pl3L-_7Y+ToM6Ju<|%^Zx(Be2{ees8{EV(0TS#D>hR4&GsX0`t|vuGjI0P zRwd4-T)L;sl*)gi)wM49P_n4hRBS2TJ8Ex@6toyBwjc!^J?&km@*DU+#hokLf926M z?7e{ji*)r3y0BZ-CABYioAlvFjUyamJ2c)iyEQtoI5Wy+4}3^Zs^5 zD9E-W(VoZmty6AaMy5sH$zBsDz3Tj5u?5eGi)4x9i~5$UbtyTNSAdJR!Vj(|5x%3Dx8UF`G?2I8KHS1LJ?oeZoi7^dHc(Lh4(xJr z=GC@1sXYx}%xq=TY~E|q2viTWa)TD{O12h?%k*GL zeojG}l@nNCEu2uaBs8I@B&euhiRLC1mIX`l5K7Y$lX8l)N{Y&ga*GO(2o{!=WJWsL+>h3;J>bf&9XSzUlsHlg3TXo^!vn!`tE_C< z%<1DLqxpsTWxl+e{DNShzwg>2UrssKISUGczEYJ;UvW_h9*RPR@WlneoYJ5#cTq5R zasU3Zy=2YgzHAY`i-WoOdHKPBTW*d-HhfU&yxu*! zL8Ym_1v#NW`k(+AcZXIQ%FPXymJ*)Pt_s3-jSCyERi>V zpX&?cmjrVui)E?4{5&5a`bvTeDIm&Af+{R3)4}By73SqH3eXlbDYlBP;rm7$v!##gqiSViPpkS~T4^o>YU zKOKeJd#G54rNYT6E*rX#DDn$S%W?_|eCTS~f}#qENb%<0hgB~LF7c&Rq~%_ib|E4A zE*vR${3cwKrV~6Qn=Eh+{M8%Ye9Ztz$ytYDJl=zbt+;_p~B*V&_c?;Cks^aRxeAN_AvyD*6 zPfj`}~6b44j~i|G8ab;Fk}*J2>qCX>kOI%5r8F z2QZ_NX_+^FtzN>qG`vu%xWNMKA56JEoJQ!Rc>}FXCefzH38E76ePueS-o%401*h z?TT*(#-m(HgSp~5sML3DPI>-9)rS*US*Vn*Lzk1&AC^*8NO?|~YMgWRAYd3(Q0%?9 zfWbllTU6w^!+qup4tA?O+|_LNw?+<28)2Cctd0%*a97aSX_WYvFd8ZO?_yV?ouhR^ zlv-<9lg4HFv|fGm@nwtXRDC{QegM7A_W8<#B{BxU(Nu?T>VLM||KuVnnZKl@sHA_) zNDvZpvPD(;a*9iG%SsBeF{+$W-DYLqSeTz}_l3$+j6b$~P=;~RxJaASMF{S;$Q>Mw zPe+?^(~K|5rstFgbvs0Z&uqS z4V9FTgU&t*Lj?uaRkMfsXU!OT$*?s0a@4SkB9|lW%Zno(E{a@UIP79;+LSC6#E4;O z5Q754)c?9b7!m|4vMbUD4I7!4>dPry7%Ipq$-Y_L+odH1C;lMvib@#41hSXp*g}-3 zilom1hH zQM`N7>~QT4-`hrbg_XZ0f$Z{NfhPoU zm&)X+wJuK%@2RyB55n7ZPU@}A*zr+iJH=<}qf{P?X+ZWOT8*;o1q?q`GvCR-v4w0Y zjBGlAvS7rE#G{AC*~OvKMcKI>nqZXw+bv9RzR;1Q&!B&KVRUApH-w{3W3d9*G6_qCnA-IfL?io&KM9o*24hSM|FRfB)18 zMwK$s%bqS-^hJCGf{eP-2Ng&Q8*%L{HzPlHap`{{HPG6J_V1Biilk!Kh6U zUQweE&FJQxNk+Ck^N<-wwsahU{+9IW_K$HgQxPVxg^VGj^0I>Gvq?AVnZUvd<5l$8 zX*%GrGTOId#1kw;*Y42mYYDb1Inx8jO5ef?+7VW83QJiGP~miuK9?7r#@O-wr|B#y z3NfFHol51Wv+k6$N>is~8D8|4#5zy@)bQl?xhKzrDhtw!q5^m%xB7xzra^a zysT~LF}%;%6(b6(D_U8aVHPecDJson_0lEe>%?gZRc%Xc~M|l*JiS?B4R_)?B8u8OzqR8R;Q_pZ#2jM+WGk5JAQR! z^RC0Ie%SPj$3A=IO1fv1(Dd~4AOF1i@XL36{Hqr~e(_QKKn=5hmKr~qgk_s#Fb31J zc9u#RrOZ}SG#O{v{`@5++0*s%hw?I7yod*T=BDgKj~~+qT^um1J-K!4&WbKhHj~%{q_2FIjfBev@B=z`mes-M z;jPa!J^RFGyKmF~cjAw%*>Ly=k4AXO%>u@gtf2Pj!K81H+9I%BNoxt48frGkJp z^64YWf)%XJ75O4!-q_V@Zgf%_Ig8=Lut8~~3hV_NyGCiGcF>oz$QWXIIoRJz${ia^ zR<3pUrF#!ouRrqK+NP)PXKmo)>NQ6;Z^u$fsWC&q(AK(gWlp$f`b6rZj)svOp8 z+_kpx#ho8NbkE@p+ih2?locj+e`Kj!yGakARud2msFF6;cv*_eEnswodEj5#ICtYJPvzRKzFoUpMC z8O<_0Ftc}7QCu6OEE_Qiv8VGAhWxq?C(`rwkK#kG5A-+LHMO7cy3ViR|C`*ZRI;yZ z#svRuZo86q=dvr_$)l{P`wYGH3VYl@u*upIEI2Nv}UAnp~=H+NqJn_eYS{IsDa z5~Vq1q|yj5!H>i)vwgMXlb$v#die7Qp{K~X6UXw7O0*MUsD* zkyRUuo~o$CQmcnjRF<<4rY^Es5_9scIpyT7)Kocb8hV9B`ZZI#e6nOi_p9d=Vww`4hLioF^o`L!Kn ztU+d}N^CSai&mHUiioO&b#h6Un;}DLM5C6lOadYfYQ>D5E&}zjbRW??KbbOtpofhV4464|^$Ww)&%}N$jeWgqD%W@YPT5p?nW=;9ou^A7t zK1{VE3_VD~cC4YwO!42Nba<{$jj?><S|Soem=KEr2Y%<`)(-B%%U`mPo9UQkxI4VaGu+InL3gFWP$@ z(6y{aE}%K##E|?A<`fK-GG$TAecX-CD0i_M90p5tG}a8}<-P&Kltz4G>_l8KKrFZ< z#I8!jjle=I)-4F8OA47+$j@7R?jq`~sICf6GhG#3Z?`=tZKn6=VcUTk)Y=2)bYBN| zRL3d5bT+-e9||&xbc|3FK0PotQ)*9;jEY4}ep(a#SY1guV>@pe?d%m64V8h68azv*tnbt=q}pGk z-H`UV)RPo5cu*nY!LIA7adAW$Cra1ZAwX|H5~CV55mfAe#HSi7xdx)1G)0CX>82Qh zIk}5`r6itdhAutjN9N=nNi}N09&9lg#9*t8HJDtHgFw)mXlHywqIH2w$45;m<|L;& z7OJWaL&VN0kYGKL+e0MLrP9FCqM;1GgB*m)mlIi7ABR^RYb;$9Dw6|wo-j;VssR(> zFof47VoxbdvoFIZkDRppGVpNn(bc%0@sAl}h}ZvQFk+ftRqb2@Ey<~0225%mAgXi5 zRi4zD)}Mx7B{V-b(~ zID<1_uu~w>*n^V)CLUYXH5mH(2tA{kj`{Lri?gU4F+lxlVB$`+ZDGDSWWiPo<5|g& z-2yq|kIQ5N$(e;*jK34<4mDyK9mCb5k0`?n6@KjTNu+#LIlK0KzxR`-%wgfrt}NMm z!}6Y1>y@@0*eK^#WSvOPma8*xoCGS5a;{KLaM#2`Z-`)H0V0 z<D7mQI(2F1Lpcyq}Y&F@Lsy$#xc_1Sb(X0(I_3xDM%c z!j$tgb{Nia{0@qAJafU?njBe^;W87No|d1Z9qJ6*jBzvkzDb<$V;nPyvp6WFWC2fS z7+x({PLy-lA{t2btRO8b3h6W2_PQuqEiFsMnUk? zCyj=b|1!0JCJ~DwC*>5Y0>u^()0f8JytF3l6F8zSQ`4LUjCb*27n4edZwA9kmhf!*w+k_KDnlzDjT`!6@XVerk3ir{c-y5= zpO~{neAlT}U?)JweHN`z-m*wccl}Q|?Ed#O_Z|N|j+^}3#6Qvdq(C~mCZ3~@N|_u9 zTgdR9a~~IS7)WVdPLGa6agInA9_{Q((CTNjtPO|CY`fcNcx^B6sF*6X#HKx^G_!C4 z6U@c#a68r45-VNVQkJav&nPPLO)e^2Xo_#DJa~~M&z)oh%Y9DeFs!6RA0eBdo-nY@ zK`c`VUCU84caSO_x?Phe5_EuF#VaAxuj{}iDCNmmo5`t!Gl{wtNyYeOZf{-jDnZ_0 ztggavl*vU$Uczwm(^L(Qq{8NA$g@UNQJE}dgiO18xva5-kE2+&B|H8mXG?Wof!t+3$s2a?6&NvK`5d%8P6g@ZT`Au%;Un6;2>14I@=1kX?vs)fq?$RUI-M#MwILFs>U_ z)%A{=PRAUj=y|?Dr94TL?z4u{0a%>Bn&;EJemaHqBp#Lu$k84-365{w`VCWO)0LBy z%`jgUO$5&=aU-XcMpz@Q3$2SJq?qSHr*qzuHhxJ_;c&5pjFNmBt>LwP+ za_H5Jf9`2)Y|fp${?q5Sd{MXK3ULqq`q$(9YSzUBgt4$RM~nmMav90UV|koVRp!N^ zRkr=qez@m8)mMOscH)etc<8{(v2nG_X*a|jc#&syh$hg;tD#3JCZs&l6gm#reW%#2 z<{7Jr!3EZooDz%k!Qe8BcXIHrz#11?$SP;CH8r=)y0)m?$_RQ-LfX3OcA#5>bxOBZ zYm7CdTVuB^R)JN~?O7|U+vaX-tc-4F#$Q&JVp*T^!mJJRc`}*n+HziR0`6Mc9cZuOM5sAJZ*VyM16&B!gK0lR9`u8K zPO+>ImoZ03HN)fK6aMxawZy!P)mA&-dzA-j6)E7t8`L--x{2gB!r< zKSCb-AFv**1Y5zUz&@v0*1KRD_!XE1UcCuubNQm<67`8F_F#xB>hrxC8vo!^nd-gRNk%N08?Y43C3pVEUuTg9pK4Flh_&U@Eu+ zoDJ54w}P$UR2DXA(;AxK`4~_vhfD6DKUt^iRPw za2J>b{tvJCC3LnEC$=2Zx3$<XuAP?>WH-Wu>jXXFXYyf}od*s1;z`lbm zE9VIEVE2!a2j2uMz`jk$gMS5Uz~`Hh2dx(5!C^;{Ki9H+pCS)V0cV3NzzXm!a1$5? zYlQzB^5AV?8<_bS@_DhXM<-aArEGNo4}j9 zBM&|UHh{M!BM(|VkROKq_e35X2F?brI01R^4R8~f-3xhe8Q1{UfNkIruE-Ut2+ zd=@kT3*!LpZd2lrNH*hwXmP-8KTyPVZF_iehFTn=zZoWd$23|cJ`HL-U z4LBP7c^dNIhhPPG$_V7aE5I6X7Y%r=-)5Ob>@I0{6}chi8Bvfn{JAybnBaCglg71-=K~0)7q_&O-h& z%Q^sF1fG8#^5CUl8TdEwK5+T<#1DQBHh>r3K>EQ4z`kS1Cpa2x2WNxB=a7EzDR2|` z^jzfSo;9Ba@PcgQ!8u^x%V`hhBM;77fIRp%SOK1#i##|CtO2)z4dCekC0izs1Od@0K7B=9D21z7|3rys8{| z@OrQTTnx5>m0;ho)T5=ygYSZ~!F3hLgZ^d6gY94q_}%5mgO7u4;C`_0IOM?5;HThh zaKsAa!P(#@FdwV|Zv`8`wO|`~(XHWdzwwrJFE|G5xiTD{3tj~-2a{KY!<)hDZV!id zgJ)HR!v_V|gu}`=ZKk{JeL*eiiFaXwqkAjE5R?zY@&fOdi`@nm^v0xaS58n82IJ^pc2;2g` z2iAf=d<1#$CD58k{vSmiTmX&*)3+cGz6q`Z{|RmZ`#pv{=m!shOF`=@$`|y3-5*CD zOateG*MqCTe}P-Tdw+~Pc=1-`!FNC_lX|fYdGL&%APcCbO{RSXePHjs$b;j+`QT09D)1-Z7BK5|yLp<` zt)fr2GkbMU-q4M)0q*_y*OtW?{WLC4>@)GizE`K5urzs$hCoqyrL0U|2$m=>K= zd)Oyvej+=Ue}Bb&O&k~FPVBQfZbI**_{un2}`RW_n!-GJFpD(PAdowr{o-QlG z7e)BpIOoFO$qkHdGbK)>-W`S`4O2|(iShx?dY+QVnM!=Dw&-x&By;J#%Z$k1 z9Fac`UkFdr7~$h4IO*$0z1Rq^+6cRTOpVBof&T$~wE8<2{%-g;urnw9@q3-RvmAc( zt?l7c-SKPl*7grS6rLe_L|&Vp;&;Pe4$qJ%!k0(VcMyIyd^G(YhtGsR$t^!QBHu5O zF&X>`Zhm5f9|J!SzL%T7D#Fi&?*qTd&BxuVJcxZQhhGEV;NjnO_|5QRSGI@G_2_Sa zqrctoSFLIf`#thw9r=Us1@Ox}e3`=^hkqUZP7i;(!}m*KEOA?V_-+sX1BV|2{}6mM z{mg}54L`^&?`q$d!>@%O?B;V+@Vflr?}0zx%?Bg=Zg`1*h?~!i@CV_43_sP)$6f8D z|2X__;UDzy_d9&Q?yQO2-X4Cy!{6udW8hzhf5^jcbojaOV=LRkvpoFw9ez1{Is8Ts ze~-g&hCd1)wf@8ZZ;bE{!Vj-%5C6~;{(2|;KOcH_;oS(-S9t*!5@U*6oWqw|40nJUr*+K zG59g?KZTd!q0_!=^Va!?-vYnb&Bx_A`sbjL)dHXA;kANQ{|`T6O?3O*4WAx^KL|eo zo+XP&`t==AM8nz`d!XE=)4j;`v=E5(B@8M~`6P)&YIef6XJ-pMMzPM)` z{cMK+3O-u>*bTqr2hrsZ!pEQbIZHN{&V5e;aReb*x!vRdKLb1_(|{s-2A)XCockv|SEdz1Hi_`4jw--)tU9^HP%z`q5*!z2GQM}98+oDJ>a zv)%j+iq`puzaa*{S>lJk(=8tt8K3NiuZ53R{|>^}#o&*_AApZmzWp$aci`{$#J|DG z-x&Cb_e38b%!Pji{xOgIW=DQG{Ma8xA3tn{e-S=v{f8gQo-Sq_u`k#7^C0}`QTQQ< z9EVSYza`NnKjrTDyAswXu1l)y9-p7+q;&{JHe*wJ_-1!paUqA#g#QJ6hMQlhXv>G& zBKY6JU(1-==_}$V>4`Q@(%!Gb&+*Oe;jvshes0lW2)`Y^-^0=8QwQLu$Ka2`{{Vio zJN&pGsR(2)-iwJq(j)ERv)nw_!VQ7z4mYX;C+W(7>)%msb|l>a`0v3-E2k>>p77D? z=~no=;Lml(y&w|)Uikarzt4Qu(OdlFIPoFrYlN?3k2{)t!gnm|*YNMS!;d?lA`tn3 z@V7n|y`E*jSH<81@IQc`<_Uj_6Mhx^Zun^J;8ysT;Rm|qvt9Xz-vjS+^ST?*`TrU| z;pEuz0}VgR9e!M79G?N-M*O#X_!Un60`NCH9(^6F3ce6NT06HD{&(;myL8#tUija_ z_jkuXH=>_L_;+LQ2~6WAbd3a4TL}AC+*?s9{Fn{`G=npgAc&3fi1UoyWftk zpS|#->f6JUJ^IlDLDm1mFMv;V^R9J@1R9<~__c06ZndM|f$)ETkJdkBz>j^0Jra++ zZonk|0Q}AH*LnEJI(QZQGw>I=dDlMAR`}Or@O$C^5QA@o{}g_jJN&rF_#=S@{o?{xbMz@(B#Arou;Se+I%I zgMZhP{@*z1&wzi5GjZQ@^Vcg{=_dgHlNfvz{1fn_-SVXo`K|CT!C&R(UF!gQ;Tz#U z@bJHL($@(8NJI4TVFC$%6h7KKcp&^%_)(trYlPE&Wx((HLwooVcl>&Ir1KB|4t%|v zk9*5WUlsgqAGGVk_4YnfoZhIS=&Y^qhv4Jf@yGq!k>3ly=a13tuMz$?@O|9!@h3Rx zPhf%K<%2QWKltL|1Q}fA|OBuXOXSeYh(48u(#uUJqZD{8son z_z9l=;R>gJ*bCqMm-cW!PyW8^PZm#sl4~pb}0Q&!XjP@V? zTKEN?^y`I6NnZy126)UYq94~fUjY7Y_+@TBF0v0<1>Y1S{H^fk|08<%d*RQ6U*`$` zPDj6u@b|-yck{0DOE`zKI`9v;`MAhF-$3}Zf3}C$d-yd@_!;mI!*BNRdRPuS4-4oy z@X_=;5WWmPTKQza-wOY^C;gu}=?}n9JKi2%=;0SQd=>ly@OwP`OAfyk{<43!hig6j ziw?gR{*Um{=C_UTE%5*H$hSK33FoqY)y^3#5C6Qw4}_n~S^Y^KKEvTN;O~HsWTN zb@Q$JKlqd4IMeKrPjTb}@QLx^@Xy@xaoZgIRl#q74|(`vhu;c+7(O8m4|W?BA9lju z3;#x9IQ&bG{LdZvM))~N;qXl!zQExV*udKkztO|ry zD)yceI0NnBr#t*W_%C^8<33OLcRTvYfG_MF4*%Q3w<%uwp8)(dCx*T42kw%#RdCnC zE%eAn+J-IgTj2lE6Aw<=f9k9q*20&Z9uA-8N&87o+7H1mIwKr)Y+_wN-vcjcal*e& zC0(V@2cHYiR#}9L{IpB96k4?hmRtNv5vAATkLKi%QS{ms$s7772%=<>Dj8)EQ> z;C}-jE&Uda)=ThRjZJ-|$p=5JAMcm&=(k$wSCTAw$iUC;vp7314t5#E=?Sdx0r*qC z7Y>he^UEVTtb)H7KH%o#^ahW}Z-rk5j~Pe8H$x2J_rl)}KgP{3jfCF_{|NjDH?OO| zN`C?ir%%J*?B-p2n*-r{oE;7)d34atv9S#J&)~oG@c(l70Q?*M!%_E#s^Bje5RTe^ zZH2!K{%TM7ekc6B@WFF8yn%HbQ~|2;4qF7f1ViDP34Of04j3U|48EBYM>UkcAM zQbhlH_^Hbuz7Rgz`dI*eFMPE2y$b&H!JJihhaVT|-?zfQ0AJ|gBl|mh;k%z34nOSS zH#zxhgs+0{?$J-2qo0J~JXsQkmzAJRf9}M;75*ch)mrIE|IJSN_rj0oS*@u1zwo6zv(;4{ zmi#3!aQg6~aCm_y{CQ6J1L4mZ6%JQ<(yur7MLq-mPWbP*dA+=<^cR3%7K5*XUkopO zg`@xJO1(;cD|{~eHaG9u-`NY_4F6LP|AbRMjqs(Hgrn{sB+xMQ8XcV<2>(P3J_G)W zOT*#QJ>!#8ob`hM{3Vx#qt4H(;2(!)m>S7{jw}E0Pr{$z=3V=*d*SbekGB5Q2)`aa z!!2*lW~lNX$s7-!VPYhH-34p=hp&M@$<0rWq%Q;hDfm;}d{%@Hz&`@t+s$Wc-iKQi z{95>@+`PXsKJL*-7*FD-&zNvH+wCV#FEU6T_QOwwU+Uo_d$djP+u$#E^R7M8WF|ka z!N2O}<94eANccnG1DA)xQ$1yTwNu8K@b_LB4%d0=(5p@zS_FUTIG(>rATXzm`O2x| zYv51!hr<_o!XM^@|0I0sRpF>>%=_WbhbNnn@O2Zf%CHH34E(!pJ}$C`oy_9+XYd2v zyzYXP{1Etm#^5vIzlgyvg8vG>)T5t5M?Y)eubmWqjQb?~fUD_4Jo3ek{C@bQ*D%KP zw4s9>{Wihhc5OIZ?9uOHrC%R;PQI8m>a1}1_lext<%12z|2omJfmHld&ElCsw~k!v z^poK?!(Zm+%Of^i0RKGv_uYJ)u1I2I>)@N zWn=5$pM#H9hqp`k*N3C7gC2lC1HQo>e%!lG{72z`3%|j`uXXrdY+#JPA^JEo75E;PB{FChkwA)-(>i=;2-z!4?BE;$j^-){yO+K;D6?+lvZ=)*v>xE(eDF&Yke-!=}Px{K8^i77pYJNC;uZO?O;S1n* z%54t&#l0uc-)kxfjxpAPeB%fiHH4AEygI_;v98mxaSiJiI>0CH!{yLik%e zycuAK+qb`OHSnzlzSY3D8u(TN-)i7n4ScJCZ#D4$GYzz=$r0yy49ZkWehF$)!8;@M zt@Un)`@w2afafd>pK0!Unfsbw>I=1o&E*WW*w31+;n)0hfVw)<+$S46!{7$P%Q#+s zHqWuGBDrrh36teV`8_#RqfDjcx9Jp(JvCVOnDm`s?)w^)0g z87w!r+Tccm+YIhBSZDBkgGUS=Gnll?#BXr0!BGY$8k}V?&tSR1)dn{j+-7j6!8(KQ z8$4q0n8BnMP5cH28ysbDqQO}P^9+_7Ty1cp!EFY28mu$;zQH2~j~PtbZQ?gL*x)FG z6AjKXm}juu;A(>#4Q?~I(_o#!_YEE~c+6nZOD2AUgAI-{IMLuNgLwwa4X!r0(cm_N zI}O$ueBa;^gU1Xesm)p1KZAn}jxspW;4FiA2FneuHn`E?HiJ72)){=?;1Pqz3?{u| z@^5gk!BGY$8k}V?&tSR1)dn{j+-7j6!8(KQ8$4q0n8Bo46TiX121gm3XmFOnJcH#1 zR~y`DaGSxM2I~yIZ}5o0V+NC6wbbu4gM$r@GC0xTEQ5Il%MGqJxY6J?gF6k@8GPU1 z5rfAJChalt8yswKl);GxXBo^hSZ;8&!HovD8Qf{G&fxn7j~F~=FzGcDzrn!kPhc@QA@<29x%h_zey=ILhEegR>0g87w!r+Tccm+YIhB zSZDBkgGUS=Gnn+ciQnL0gQE;iG&sv(p22d1s|{{6xXs{BgLMYqH+aP0F@s5UCVqp1 z4URH6(cmnDc?Qc3t~R*Q;5LIh4b~Za-{290#|$RzGw~Z7Y;cspi3VpG%rjVSaJ9jW z2Dcg9X|T@V`v#8~JZ3Oyzlq=AV1uI!PBb{nV4lHpgR2d0G`P*+PJ?v@-#2)~;4yxj|A(k?nryQ&S|I2B8BmvQyOHO~5wzg_dGir<44H2|_W#$Rw*LzbYU1BrCr8fplioZ0w*MiAwf_}on*ck2_P=J4 z?f;1cU7(NJD^6Yezs2^Sk)r)SVy_T&>Az;3?f9w*Q}QvHgE=miGUJy+YPOMu#6@TBsHH&UxDZrBN!5_CJbYtoGkCUHd;A z(|?b8+y7_k^gbV}N$8Leb8Eu?v+aN8R2}}a8afGS|JjFZ|2@>xNxbwtru}^KH{1W= zSvufHV~2m-_Ftu*4r0O6*C{E=L8qtg>~2Os4_D}bpO2Z}-wd_=&sd@TUlr4yyN|W~ zKXixoU*53=G|AKHc?>P;08d({{r@bc{XcS}?SHpAg~ki^V%q1PrMCa(pX=~%>>f)$ zeOB52r$49t7oQx<|16qSo&MMMYyV%x%|K6DS zowvjGKlLl^zjsV~yY>~^|6FRb{H}=Ep0xeO_Wxi{?f=V|>3N5D-0Sq;*IRp3hqt=O zvbKlAhiv~VQ?&nzF8qp<_J7F{+y58Fe``$rpZ_=8|Hr54@NbNg{y!0it{TbRKH$2S zMEXPd!!NE|vUHGfaotx6By@iquW`xU9~S7Al#gS4CV#pOI!i7?ayfVwf8*j3sUcQE zLLwiRL?SVb<`{`$@wQYvoPLd5UM+w6j^%Hn^uU|=mo$<;*;et>2N z!RkJZ>x8R*%->{@NR00hKlZf&T;U-85)*pFTk*a#fpE3ge08tpj?h61qo+vm&;f2keHZ(T9Q}c zp&{||v*LKfu3DV0uw($y<45Q+@yg!frN=T7oH$mld-PaKIuid6;@$&HuHs4?zPEd( zr|Wk2?Hs0iX4KOfX-1M*v8-hPGB663C0F_!7K($F#r3WQ@6W?*w5bQ+vor0dDJ>}>eQ)I;nuBs>)fhg z(w^B3J+^fY>6p15saogWfZvqa3}vmmaDGuW85FB^9{GJ{M~oD$^GOeS$DDkM)4E_R zWJV0nRcRd|f05zv-8%YbqJdTlP<{;1(eHp*4eaI!oC!N{F8R0sK8&UkW>-o_~VmDaVw&oJ>6Ek2$ z+gi3o;wB2*BmxU5aHj~&qQE)|L=Qoxsp#UbLxoudI=T-@$Fv|}bYId@Snx&sA3hUx z7u}C!bUv!3FM4Vp+RyAp$0R_Gx89B*l^o}DTkh%z! z8C@sjeJEk{9@@uo?<$xDHTSQqtNC`5n(x%rY*Wx@&^{2o ztp%}Z+T*0DE^1C=`5z=ZWx8qBM$#qoNzCk`4^em3%%J4MqtCi~3XQ7WB`x-;{>jk-uZ4wYuUaL*#SfKBMcHsOceOqBFG;Q?4=M#g}X z95B0GQdhE2iYH3;5UwcM^EwEq5>ldMDj)ob=+WW%V3|dS;a9TR7)Xq9{1u+R5RaUh z3Io05Gf?7~%V4IL(nha+3Ur!u+=LGTogtkvZ=fG}S<*T4CMv_rkuI5KOq<^Xy2Big zw)P6-SIz!4(CsW>pZOl9UtXEd(IUfpfxHUkmpkF_4It1(^P(@no@Zizdj@S`s!L$_ zTh!y24pdp}Jw8HFGlG0$?~_iM7W9?a2c%2p5ab*C2kEN$wGUcO#p=s^A9=+bdD9ML zCZPAnTnP+jwq;C60z;WYP-U?e35;YeKu3?YN?=juX;>DENMK236HJRm-3l^ZnmLbV zd2TlXM`k|5n7B)WkI!7hn3M!g&OD7$#WL>0h&eseiF%I}T#n((Gc!@2v7*cI{|gyT zt70X$7uwFt?9LK&xZ5JIBJ&$680Y>NVk-JJD1Ku%T>^Fr1I{a`hqfqnNVj7Nq+^o%0_$iK1Q!O}tdsi% z8Z_U*>YweBpC2JTr1T`V>afs>$%sr`z&sP{&?bo$LJq*t#Dzi*LA_t5A+ago-T}#i z(|Q9F@WvCrLQe5cM76c>@lE!=3`XfTBy&oe&=ziK8`MXr6hrC4PWUQ3`^iZUKqfjD zv3=f`5<_hRf^}Gvy-U%PVh{A7}?^Ecx z(bNnkkk@i*ro5J6EcLZTX;52~Z=~=|Xt=aVqqU;P;b&=jTfRvpReDfg=9fWRdXO*M zsHvge(}NUA8D7AU9{fG%s`&=0Bt1whsn3j}LehitKo6Kd3(bB$XjU_;!5sKQ<{F{5 z2R&l;RX%#dBC`R%>A}sAU*d#sL7iv3JCH&2FCbHyG&3_@Gr-Q!9>?qp`An8{ivt!X71B+S-WaZz&!Dog2-R93de z%IY)Ypf_7%VFt|SQE}NCD`KX(T+))BB^8&gQT?D3{(uQGKS7`^`V0Juxi5ey^9Rh` zB#N(z#76wIuB5q@b5Y@roAVDqa_@-4oLo}Q=JSp?-pQr(F_?+$b7`8AGVkpUIz!={ zJRZ61dQ|Qe=3q?Q{7w zt9OaH3r6L$d`kA07i&JphiIvpfZEIFWisi6HzQfT@I{m;%BftmF!Qst|2;e#g>5c@ z9>@F=8VcKzZb385Lv#maI(5t{`j;Y5YJ*azv@QCa>x7>Nr&jlU`}o zq0sGnkY3}2A4Xf3Bk!T?(NCgF^_5GzAhEdy-MHL-5=h7Jw_K)t)O>^d3d>tECn8a~ z<4DAINWGOiS#MRRcoPbsUAmlMbSZ}%ozf1-$}Rl@xrDG>giN`>yxO9FLUeHxbZVmZ z$t-Va7+kls8NZ>@Y4~kH|3ljLX=fm|NJ!L*Z^LRRm7vfm{R$SiB@b32kGl|P-~JZF z##oy#gOI_-IMHK}d}(FEYE-Y-Ug>YNd8J>=$^ltvZSzWhqs=S*jW)0JH`-ijZSzXM zwmI9RGLcygNu5+C#;Sxwjl?5;OKI`S&( z?9y8Fp+M=96J3A=OFH8(FaePPj68@21VEugquQ0$YVS-ms=YJOsP@i8quQ0$YVS;F zwa=uTKC5)d?1pl6CZ$T9Z~=AInW52b(VG0yo-oIwu6S#P>==IKwOIyHmiJ)v1Lzp+ z@(%?^3fq-x6t*kXD6G;Ya}nyeEB!81_nF@!ZC8f23^?J7;s|7^IrcURe=Z1V(OaDa zVXQIt9?K{SUmZl{odjX5F&i!fCy~NqP#vHliHDF$bvhrQLb4XI#f!t8EfJx1v8QkXTagEx z<4Zh`tyG0&Zs{MWk5H)>n!}}?(4$*QFN1C^tpYz%`U!r$F^8byV82uK(J}FVbO~xD z)w`}IhXVc=8m;%PTcFV~N1@7l?1(^v_3X*WbUxTi`3YQ(>Pr$4RahetV7LvsK z$6Y{G+d*yr_}L&G^Em3NUy#0#IU3^qebm)rq8Ot4CylN<6C4*0;c?+GRE@a7Z(CH+?}HCX)+>&HwMhGXopulb8ycd)ar!z%$o2U zR%;J04{=?~{V&VyJ@N399XAw`mB*^z9^ALqW_Y&Eu=mra9O1ZaA!Zw1wdr76h?@|c zFb4+V*th;ynE!K<|JlC~Go4rTKiC__d!^?kw$2~iE5Qw|TBMmiF9|}cmh_%(A0gxWfbyqVw`QBh=6oh?8!W}8{&5r@%?_H3gz-g7CKP(LdIbG+JfKz9_fbBh~twA8G6={SW1w@+{jcC$Tr%*qM#k z^D%z8VTt{MjU88yo%$LJG?(oa>{7_>+z@bAFU1Hv@Ep6#0VG4KMg}%As~b2+46Qn7 z-~pEQ?&BqH$-vd~5PFPrmC&mF2e@{2UtBJ6i>CEFu2~*qbDmArhcfR^uN0AkoW2{a z%o$c@;9$m|t_lG+#<*f;X14X^HOCBs@PFd{MQt`bosBLu{$GZnqs2KJ1BTswIt{{? zA*YY}S!{z$LImqW&kQ0uteb3M-FXW(Rib#ZoXA4P>t0%9iO{l37q;7T+{Fp^aL)`v zN8!KF2 z7e7pr+cn`YlWdE&Mrn=0rY(Ov5xq)a)0VfWQDM`T_cl{RVAGcONh@sH@&RduOV8|nE+R`F{5s$EGOREGHd4x?{A`)2Q z5jJg!y7waKQjf4{i{}y-Khh&?+7fqZ@bMmD)0UJ3PWA|!wq#rmE~k5hOz~ z8jrAP%Tx*6;t@7&8IZtwkFaUWbayh++~*NCZJ8mqZS)A6w#;&$Mm~=^A;PAuZErv< zM%c8)!lo^2SYClmTh@|P*tF#amRw=emYZ1cl+zkLAH3Emb;Q}GEJ1=zPwqJg2>0cH zn{|A`rb)u4Ewf$nlY~uMhLk33+A=J3im++q0_K?_Y#Lc1Bw^FYg+dZGZ7b7|_}=(g zfIgXaB0J*06k*f03OOO}14c_HLLhV+exmJ{lH@*Mw0t|sUGZZ|=ab|;WX5R=-=q{4OocOdxT@)}A$4{0&U@%QC>h02tpm`9vdh=cf3(4NjATU1zepqM1 zaXtjxp^-dXC&ewg*!A0ilj0U#Y>l)Px9DPPABJp-TXeCTM1X*3>`oCNt`l2F0o|gD zFDB+CTXgY#Na_|{d|%R0*!U&<9}n;y7-yo z>lR)7Z1Q!BE`EjBAzO6uYdG@g7M;?%MHj!8aA^s36JNh4GvXFq{BA1IExPzOBqJvu zjo)!B1Pa`ui?0)sTXgYzXdg#SZqY%_{a>l8`F4|<@6^?7xR+|UMHjzM)NqR~{=g|z zqg!a@oxQk`zm#UCVFx9H*bwUGZk;KS2aPk9* z-L9xBSt!L5C3^^0lqaM1;6wpKRS9rs4cj-LX%OvRJxfpB!bebjLn9%1)p=_DbuHeRA{@(D|g(ekaDlwifo5RPTXMEmh)_ zWk;wiJ3?jM5ei*}1gS}^0o@TwP2pAKvLlq5N^QC$lo}vgcZ5>YIIg4&cZ5>YNtX>L);Nc&H4}jOad6ZrDG}0Lz zKe?xo&XU$WjdYGZiGvImFClI=Wa8tIN;exa-P|9L#>~{TF$uC{YOG-0Y*1Q3mQ0Nq z>SjZx##|K7%+zSU;+aY-$daj1{h$-#W6CHFpGZ1qen)x|>5{n_@7?@l)=!6^l=&$vS5?r<{8ZvsJ?6kXWCqfp`^-g@pT>7P zdJXC6te-)%H|ZIqhnx_R=6vKa+Wbj83Vrz!6AMI{Z$Cn8CQz9#vy6%~=PR^9k>-5I zCn2LqbH0;pU3Ef9W{~PYL~FE$U+I0*KxFv?Cc8(w;?bW2BcGv?vf$BW!K2HHM~8?< z=L_2+7E=xMul5A$Lr0E$H%naZM@2j3J;26F{}^W6bF_%F>f1Nr1*GD+$!z$tz}IDg zugeNwhX`Nird^BJc7?BLQf?dehqA!eWr45D3SWl^U+1=e9I3? zSkn0m{f*9F=+_D)e66&0{z8AF^B4LXoxjlE==@4+=P&eY=O=t!n8>UYzAj9nH40xB zCX-h9x*(lI;p@Uw+Mw`tVSr=w5-r3}f>OgCq($Vn0}G^1%fWcIg*G>Dbc99 zQle3HN^8}X5{;@WB^p&%N;IlYX|1|aLaUAtbjfEGDFj_gO0_s4LeQnmF0i3BN=rfn zpWEXv3FB4#N=JSdM3zsaqu_J9KNk;(fY0rzUm#ME_V$!oO{86E1)tl~&q7AQ=k^S( z7;r-D%I#Tdj(-}QgP>44)vZp7;B)!jJvbSpFt=GGD(|ESK9@Hf1x||Kb7g>rqzFD& zrt@h@5qz%9V54B38GeCHF4FUo5mJoE!i)VTzMU%=dCv+F#WhLu!u z>0?&%YfNsL%L8kBX{}|h33UF7%yv!g1j)ZootC*NNWO$REpxfey(>cI(>Y@A_$!9= ze|Pn}n2?T{L){gZG!Uz0W7be@&Gk@>@T#kpIdKkW3`v8uIdP8hzp!>R3(saCALuBq!Pmh0RHpHa^7^@!imr1xpkx$G!n(t(scf=c(Y z^2gTYIT-gGapEzKdt{Jn^<`$dCvDpNvnRvqnhtz-jicbb(Y zcEdk+^-++miSF$J-Q%98X}tlgw6BUn*15jOnaSa;cqGMbEWQ&Mmm&V6pYHUaDgXcS z5B@*92CF~t8rW$4frUI1aB}DhlC9B5^f&n5x(2tA{-3x8N23@Vw)PLcl4{gH_-2qs zaDmnx@GXYp5f^CPkpQdX5f^CPiJnU>9#=@MJ5wa?#AwHvBB#~T4#%A4RL|i z;gyJtMDcNilUR!%pFdzQP52WiUhAB@K}MqY;WzOJe*6z00MFFcU7kV6BWBP#Pd_;c z6EkR?PbtKYyuA@72PZ4!^_UM5e86kg>M~COg==YGzQjZSLkPU|c&yms3gI?*; z;W;w;I$}3^ba++@FE&ex1c=Ubt z_95wbElB9?OFD`+Jp})Y@3XfbNh7|`-l=rp^$4tZ>ig`yNQU}8d-Q$w)c4t=@3W`A z&)(NjXWkVwH09Cv*;C(Vub=Yj`|NQ};ayALrV=`cw|*S;5?Jxn_t~TGvuAyuGg0r3 zT_BJpu;Q%~lE8|05AAcT?=#fge{@}q`aY`~>-!8f8;BZZe?+PKL=Axz?}6Q@#)$8; zciScea>Y#Qg~@FNcwM^5-efH@49M7>clsx)A$MYPAIz0M5$HmjC>e2T(-p&H{ zdGvjbm-$F7^0?~~uTXxu`aZ|IXr2+@=fvOcVHcq9bK))PcRYAkV4IbXP}HOEbK-r{ zDUZI-i4RDZyhD(0;vb}|-mlTH3AvHJFHaCZ;kb+#$P>g*xDpu56U0x1BrudGh@WVY zz(}4Texg+Zi}D2V6A=k4$!|inC8F-z$ara3P}(@ zrM}M}f_ov-wmWU-;=eRO{8WXU@|}oMFNk#SBVbg-_qifSS4EJniXvU&`<$M1HDrwV zKBuRQg=rprpVL!cMm0DdeV@|PVaXaV~eV;R(eDh(<##=DcMcVb~`nHfwVZ|KZSc|*fk z>Wf5aP$W75zvBCxHGg5M?{)eQCj;%*>rBp^?mlZf1ArOFYEi9t$q*kk?0fn?ci*P zJHtK&d{T&+$tpMr4VbM_RD7SaJ@0{xL|qsssZt<({($*B6VUfLJ6@$cREYRK=i}4C zHpK6S^4-^imP*Xmv=RwN=4-6Ds7I_q>5^1dzQ)Sx^XU7WSKnukzR&p@D`KX{<+akY zq~h{5s<*z+`OMc5h(y=pSIm77gwG!^dnJmmi8SHJ$V!^qslLwze;ZVM3ck;Uq)Zi4 z@O>_%^f8d(Lw%n;`aTyj6wb-xQOI5lT~~OV9~5%)!M{g}TFA4g@O|bxfovHv;QP$* zenHs!J{JnVf^9~8pNpviIW|ABSnR1kZUQ6J zJ~I2Z{#gdPoBeSaT@n1VBKT)z3x8bZ z6^SlEE0i~(yn#P1%UcmZvm$_IWeb1YKQmtiGW|B(1pc^;<{VB6QTNBCcv}5&8ELFP z?gcCwo3SIN&8Ysk>~2wSF^blaAf1v0SclIdlsxsvWp-7mmW~vwrS6YAo%*d$Ege5a zrZdr~y3RzS>Xg>1>r6DN&id3!)paHsRj0I8U1vh8j(}#T&vFlW>QgJ#68O~ey%>qo z66;Mn17sw+9e!mX9s!|?aAUn`SApYA*ad?@imtehya~EeYBd2(rAwZA)Am88&r@$& zT2c3=rRLZhP;fg4X^&f-w0hI7W)y{g5Jcsjw0hHi6P&bq)6$SM0nO@kcK@_`)3VV@ z){T}|ltiMO`=r&4R>+^iMs=f2I~WnwjW*qIqfLwNWR`<{`c_Pa+#E;tv_hF2;>HNT zStKH1!s{)rIOaSovE3432!N;ob6y_IKK2H*sD^?d_xFj4U8<5#29gzkTJC+UGZS7LNWRA8kMW)x6TTr}{(~m{kZ%E)WSP}B zsB@94>HlQ8-Se3KaJSv$>;SKm5cVWvEz192?o_3RB}$cmH@B@rk;+H^J|hCcK|1(Sp)1T9664 z^A`PrJgJ?m)5c^||26?SS5Doe%HFQ)JPU&TQvEAQN;^vRujBv%|5V#>mj?}Z@-)Z2 ztpzhj_~}kOdAj4S*T9m2QCuA8hh0+h&W2ER9 z&p&rHJF)hV0qr4L(7%9f!nbTuQ1Yapai@*Rrd~uVs;5|;yNX8YoQfKs22bTG2_X1V zb@M>OxjWDpiE;>&2a7SHx8}6X0zLI>Q0|rk+`OUp0z^`8nM9zMjf9<}hF*@BqL(qE zx9YTg8MO0ZjS&4P###%}cXuj8-)BdV;IynI)c=1tl;wZ(2#^0eh(5ea7fk)i8kDXz z8cvrHxQ~HI^so30fP2#a6X5=zV)jv;|F!OZJSy9~2pe2;EAXz6xv+|?yg3W^MoovW zF2St5_(ly9?0qE@yu*zka|C|zA>$EfmDc^v0^j22@=E?D!qRyBBCHh!YJC`-gvHaZ zMSu4%Bzx!k@S1ge#nZbW67>~NCvAMi(@A^2;_0MgzT)ZMMcS0Fc=`nJtG?ptFbn6G&H2rOLbE1v#M@HhI3r;~on zS3I3h-AC~Bcfe}93ArR@qfS#%^D7qj;2H`Sdkk@oKdBpZd=tp16MGf^{SgvUUDk!s zT+cM(!l+1ls)4kN3!}M71R6+ts)4j8EYiLZqlB+WJ4we^q@6U8b{^MZk#>>^i?lxh z+HXSI{TESMi?sVqNW0&JwEIm+yWfPg`%Or@uSomeP+xM=K-xDmqb8)?|0vQPL&g?q z7gCXS+UHoL9cu2M0V!3ZNV}?OLfRKojUw%$Mv-2{`VDG|2^a#zX@6Qn~-(C z30e1>kafQaS@#uLXTBYN6SD3rvd#ka`HHOb;acP?vQGKs0kXa~A`%Z`C`=`yDZn}M z}V;U@Ox%D>5@}>E8KH>Ll&)wi#_&r-7RGSd^ zJv)O5j*R<`bhLr{8qSPz79kOf541L6o*rBh>fhIxe0+y3p1ZZq)*t? z9vR^`9~lve-izo?$~42K#n!jMNeFCO9C{PYB&944H%eI?Zj@4KEoE`IQOe?Qqm;$r zMk$rnQWgb%9rOvC7U!_mhkU}O#kp+S5udPWaTiXq7Wsrti}TpNi+#eT#ra*Rr+s9S zRb0TlmiUBCiz5rcKhP&^S{$XFOMOCg#a)+xf4ooFw747j%YDM8#obA-^a-05_aMCn zwYnKq(1ckQCo?l6n57ZS(llX~#cA)NmYOij;x@Fw2xe&nvouYZWpVonh>fu*M}m+c z#yH`(yJ5h-CxH`*o`GL!=`VxmU>kI>+d7FyA(Se9>X%?AdBny+)Z+N`!Yv+5+V$yq zTU<&yabU{ajd-6OF1XCmL0! zv{qd?(Wts|qEU6_M5F4I)~YKD<~ryTD=qsh_mEGlw49V`QLMC_;V18rC@m4Jv=aZ0 zFdoLQbfl+1bjYpJ3BgJ$ei=%9Vx^VTZHRPa%&Mf+YGS2ImwaNSmGoWs?emG1Rx-50 zVx^TVHOuO27UHBmtn+8bz2m@#bmIh~K4IDdA|V513E z+Eoj!fJ7wvDvV4KD;?7#B(c&l(=Q>HSm_wq4N4I!9V15$bj|I+^U%j<#e|nWT!SD0 z;63rbJArdT01E;0+gLKW{hS;Es0o<2c7ZvOWi{c~Epto@rikujHXEEuEmLL-GcYFE zN4a_{7pb?nW5F`vcdS(PuQcb6uBL6VhoW|0&0MYtX*Mm*8owB5oaS`@o@uWQogx~m zR;v46roGLkU2M6vORM0Hh6zDs?FrqNN!h_({Q@*ppP_xbhdD{7uVifi^ILa&NpX4@ z$?$h=Jq1onvMF|IqdX_w?Q=nv2T6>;`j}bLH+ib5Eaj;i^7ZO^u zTHVm`_poTW@U5;Id1YOi@LBI&Z1u9kfiQyAHV+%XT6FYGJE7SE|$L2_e`8=I( zHIJ)n?rWh|PqZFnW5+jQ|JaS#)-c~{gImSce#Y3pOOxK^Km>mm)YCo;JF35;#Cst{ z7;RO)FA27+%B4XOYH#8#;JzUumsy>#Q2yN2Z$hWG$D3BkaZYXTDpI^EVSvIS*+?-S zIJTzvOC!ZCY~W`l{K$u@d%gaLmN^qCdVkAWdDhx}pelGiP#{&$?>>Oa1$IjpAWy2k z;IvUq?RPB96OwM4&FHdvMh`(kyTDIELGK=4W2bpIblpEx?DD$wYn0|1)O|EWI<)H3 zI$ZJC56QIE8UGa)?Ea9z>_~ZIJ@x5;rmGL3Vex%3p97?>ex}+KJhbPqLvWHn5PMkl zOB{NF;NjJq0Cd%ZM^w+iE4d#0j5A>>rN1GnU*W3(e|UD~&s{zKOYDKShrVWGFm1Il zkHW0pIqW01hlrbTAEEEfD#AB}IBb62rhs<&gD#JTtPU-X>B%Tn5qnXHL*U=u*F+fF<IG0h%xL_H0yZjUem3DrF8|Hso*>g1;>YoKB7{Z2Ayiq z<7x*{9kQz z-D2z|*8Wd5^@&Y^ z{k28xXk#SBweM(FjR9vma(OG~r~9i+>7C=&iAT2En1KROKr+c9FLJt2Vf#`Wy?m*`=P) zs>7PP>x#NXe6M~OSma{31C5h!$UfE@)buhxmG$vkiJfO-n+C&&_^|xSRcr71sGSFktAT-{uS#BHvQgGW{~4Bl>opRFFl z;2k!2bag+D&3D@1vChQ*VD4)re1lbwK~etP)nBZu|5`mo-%G5?tEIeW+Z0W$@H56< zA+h^y9s4cjeyPL`Y#ndgjSs(vGcc1dr}p#M@wvnjqR_eowzge-BTLx%)cu8hI;H9 zsEq1dO6(;Pc%@h8Q{7@)*+)3FL)iL5qW<~UHRV-x1wE*19XRH?!4#_&r@7N4#qKu6 zSL!MDtEZURNbz;%S(6msdQC+ytEX5|Pcg2M;%j`+OEQ`)wkeLRr}!~a^lqfilIRRx z@V^5ei@*BQ{SH!)C*uvac$uy?h8@Hg&Aj}Ee+|vO7)4dHzlG*)!8hUR7MjTu&10Q5 zrmLm!^>jvZvNY=TIi&28#owDj(@j2sg@2Vp{s~roKTU=qDv6HJwVnchvC9o-(m~MSzO;*# zom`ild?VkizhcIBZdPui3vh~|8UMPTaRgQGKFN%iSoucAD=2?eHw1nbWIXvD%0I;5 z1Dwa=?^^v2hTd1#|7cymVe-2vFK_{5udd7gsV;wSUH)jwe~t1Ny`qBG)a6Un!2X*8 z`6(B%yw~kuW%sPh?gH7VtC4|w9hGrB9T>~jx|-A8td;Mp%MZLv*(+FafBv&_8xQlq zMmFcAjC{mKHpZWU6kmlGQSEg$vN4IA_8gzdFEZujHZoSvbMiAV(mjolEjIGfdSq*N zP}nnr!cLybR{tCu>zqHSU}IIfALW@(-xb{87ht@z7+ypHCEMOuR;LcEnUa4ZjMkJN1PdFvyuX(svD#0%I078Hm^`;Uaa}OY_8d|l~nUSaJJ??^iSN&0w^+FT>+|_eY&s|UO zIaox2(5j*7#~ybYhS0#0pEGXp8VJ)Pr)w&5bNA8UeaoE5e`dLMVs&hM2{QP5M*o9u zp5r%_nSr?eUj#U?! zk6r*5MOGhkP?|c$*z?l1JPPe#sNeD^wAtX;qtMP~eUJ2I>c;F)$Pyl*T~)pfm>R2cj$N=IsS!%(tZxH`ax;GN1%RC8Uyu%(io^8l*YivACyMhHvTUjltz6i^j#j57SV&! z*rrb*m>2{>t{jv`?#lu9e{fJ*B+9p68;=_OSIrL6uo(Z+Sp70BKeuYDkYmqG z+Xqti%(N3o>X~VmkUVZYx?JTplDp!^l#U>&$ETe~QjbqtLsE}VdjMpnt%XlT*Y2B; zNmg90vf^@;y|9WNpR+DkdaRi}Yf8@|^A=|bk*gyQNj;0q+m|%=M*ov$pNTQS+mEE4 zMdqE#1acOccRI@qKQA!6GiZgLMdqDJzMe(qolU-;Mdn>0?IvfDdDrmK*R#l!*0adG zYull%grmm1^>;HPb>yKEJ&VlyhGgUv@X72`5Gd*=vqGvP5ADOyAZL+5&HaC`tNC`5 zn(x%rY$&0Tit5NCYSfYE8LH8<$h_OQgI1zFPKoODEHdvwvh^%7Z=;CFbwS=k)U9Wc zc@LA;v&g(hD1)=e$T|n4^i`Yd5mlT2z&^MXV)odVtWu4O^x^N z2$8J#CuGGxAuIj~S@lnlgRtV0=)$E3Va2Dc1}z6+#i#Pj5IqPhK0vk}gcYB*32Z$G zD?XjH9)uO2!L0NktoTf(rGG;GAguVT1&EGBZ@{mdMwV#(E_I6gUt*_!Z$nnxrAzF5 z2iSTVSz?dK||$`ouju7PLpY#jL=~+>hxKcgQ%#bLCjXq zd$eHW7JD3D)~@_8AGoOPE<@)e?I-KE4VJ?kzd zX6adXsf=il>!(s#(t6fiDo0w+x=ZE%2wKm&OBKl1v+h#uYz95+E>&hT=vjBE3gwsU zS$CW${t~lS*yXo;Fz_&X)Jw9(iyh9ULBLpk`9hpV<9+xeghfUW7ZC%2JtG% zbU#H6?4_BS_ELJ4WNPd=!7*#3gJag1VQ|bEa|w=FV-E?AStA`BvqtsxW7ha#kA894 z!4rD^ieM*yz}#P=Soh*pl2|F`@~gURYu1A;;vSM6;#ZquZg#j~Zg#j~uF`65cDP|~ zcDP|~cDP}#(rRvYSj?64(z5CvBDY**=cZwpo|l%DhfvQ;%g$r7=y_?``P;*^edHm` z%0sB&f8jd1=|*$k+4Ivb&Sk^U|_=kY0o8iJ}VZ8C@I$ zvy+)wR@_6f;vSM!_YgUwD?5#!MA|dDM0^|CkQMikthk3{o6hLUZa)vPaTeu#5b`h? zC&|x-a<$M(up-e-$W*q%^F2axD?C44`o4p{liyZIZiVM}AQ?@M$B0o#CeeUq1D^dt zio+oe$iw(hNb_{sLGyjc6y$)Y-OcUf=Z=95dzkg(K<7y>GKpT$1=5SnmnmN)y^k59 z&JyYU%pb;rZYRCOWSF*0`T%n?<>e%*1I=3M?;!sm6Qa&e(o4>7*|+v&Vv-LHY`FI%Q_D`(I^_C4U>ztIa0r-ANBJAg-$`#z`X=L0 z=MJQAF@L6>9Z7%PyiR&2(zlzpN$*VhPP3WvLz_UaH*b?3CVh_?Pn~l}-)Cl!o=f^W zW{C7Iq&J#XV?oa&{is<>dOqpLoY2O}2rPIQJy8!{EY6(GenmgC;x_DVdhlXVdSMH? zYZ=j9l(7dd>U}At2@x!N_0+Wf#^_P%=ToMGoznKywEo8EQR;7u9;N=q=%KVdHLYJq z4?2I9CNe8MaIQ3okCq-dSCUf+^}xB(6!P`JxzbeHpa;&C2KXArfpd&5K#e?+_Q1K) zw7pO)>vP0NJ#emFzW9{`=h|cPWxG+IBMw}8;9Prxv>rIu?z0Gb;9Pr>*;S=l+Ec6+ zd*EDqdJ^?ppQCijR$V#KsJe2ZQFTgd)s+*Csw*cNRaZ_ls!nOGx^hCRPJND8Zar|W zoRn(O1Lw+_i(yYBN=xLxxk`L8$Vil)F!Dl~1EQ19tUYk9;(rMoIdHC$qPw&nI9Exj z)#`IZS`VD7q-&7T1LrDoY^gnPu9BtZID7a_Af!F&K1W|+6it38h^qS>-35;IIiexf z=ZIsu^*N%yVSF9Zeh{QJPU=`Z5^nM@;Eeg?SdiQBMPb56+AAYca=FAH8)3{gjDLxB zYQj1r z8v}xS$DmDlWD0bY?sgAY&!e+i zgQER_TAyR&4(x#@91rw7L*|ak%mvJIFdDjYz&AG2EpzNqj=MAS3$NO+tb2FbB=h(1 zs&6jqd9PI~^B;)k-&i?T?s#TP6pcNTufK86vc9I=W$h!r#XooTxVxxtOn_-MBAiL6 z$rk5~1p2X_(pKqH{A-t_W_ca@EdOG7ll{NNzy4d$>o%BYK`)ZQDQyAh^&9X4(Caf8 z$L;L^I+*iOZP9~;Ea>%1hzFn-=>YU19e`e>>!23{bd}>L@o*l@jyUtPAAxr z=vYcjp#$Xs-u`^&IOca4m%IZ=hsuu^-D%P7Kwlcg!NMnj~Bols`U>9T$mNo=(}P8GoF}I-ye;IG%UH zK-Y;kGTx>2C#kMD>65LlPcU%Gd6bQKr#*`QOP@L8M4a4568(^+{{={C?vN9@l=5eA z84LNd-lY5?haQSk{8T>l9mb#Y9Qa${qOrvj(YFN`jqO8Hanabmq`9t-;D5nIWBZX* zTr_s-t)K-LjWyw-u_jzJ)`W}3nsCur6D}HS!bO!anbf@?2bP}piEpewoXXmqOp5uA4+QPXo%gP23OTI;i55%i$cwY0SJ_di^lE~ zHN-_@54=t_ii^f>`yxatv>=>p$QjF zOzMY>;-ZNu_kb2$G|_ZHKw^Mw#YGc(Y?@pUkkDh(R4`hQIUW9tvjoLA2j=KZD}6M$_Wu?Qr~xitdG4q*{U5!ecWq(BY`1* z1d_!L5J<`|4-m-rP@G8gTWr%?FsP+Hen}o6kgUXia?t||!I6sP5_HdB`8_BTgeg-C zy#cl!Od|+WwuhCPBEpnyAWYc?!ju(+sdMQB%$|?qYR`l#cD~-ZXD^t?E3+eD^1bI? zD6hb9^oKQQ$1?GZiD0gjH(L1h$1JmtI#xSD{I*i%Om=j&Te4eneF)1+EtH<;*hhrpmf3#Y zJ=A60USVUq>zcn06S}u!l^*JnrsH;4Z{VzcmL?r62~XN8;fM8v2iFr;ccvi+NQ%W< zrI>~>SF<{xo}z1rS?}%6veNL}kw15J*Ed*yySjH4b>(zHJ*M^u3$%-Srj40dkGUK< zj1`ZP`BE97RmVDABP_)Z?mGq5^M$%}SB7~{bZ@XR`!!!7V7#{ZSY`NNlUn*USv6t5zeUO7zW1(L)M zdgU;gSKmVrZY@rn^Lqwl1Z{C-M2%sxV8i3KrRryou&Pl|`Qt|fH2&&*M)TY&6h!dT zufD&3f{`TI6C+Ws^~b$L^Dp|(w5DiMbs<%qu&a%@v7X1ZRCPO3oxu4iJ*&nYN!ict zY-Jly-nh$Y=waP9qR|7#k7tTKUrlMY+tjs}F-@4z$41?YZJ_dmz3F^%%mt^De`0cY0bML^^|mbRDjzp+>YYEu5( z)sNNXMF2c08A!uhzPAZ4(A9JX-p@zoxhc~0zeM6Rs^VR<;Q3fJYKYo zJCe2~0t{rxW{Fenzu<8}@E%&r;w807ikCcZ$AjH$?|2Bc_rHOc{I^a*m%ym4orD6A zMDI#m0~w2qkR&qlJ^UXaBcualguU7#Bh(zY13gF)i;R#CkP*@WGD12)Mo8C@5eDkW z2m^Iwgn>FT!ayAvVW5tTFi=NEu7HJgWaJtI>c|KUt|KE1)ZKw@M&MsSM%F-E9U0*& zzmAM>{ar^!h_lp@5eDkW2m^Iwgn^GoMrhl{z#WKiOdT2FK=u)2gypr!2+05$VaWqz zg!+h#9130}N*!^wDN7)O8o37|Aly1$@)2Z&`~Vpd+9D&QBhep0U)yUSEi%IFEixjc zA|pa7GD4f;e}mLCJezO_8jt_1I}ka|?m+4TbRH6H?f7##x$5|HB}qjkh!jVn7veW_ z1%9%-yocNKwGYL$xn$7P)v`_H$2Qo>0qt<7i6Vt-G5_7|J_u$gLftt)DDt$RDw1Z!P-p%!V6Q>40JtxI;W z)+PPV*1D9jYu&v-+I5Wh0O?vckG1ZajL&-qbs_f=#^(!H*Sc$9hW2OPjVMa$ zYuy9E$z!eiL|w^3DW0x%g{y1bZ$q^z`AwjtzSdm}PN{jVn?ftK%UZWx*1GMo)@|Qn zt@}qL3f8*EL*A}+hnbJz86}AUvV*lQ$2Iih;GR@4W`A0a#~LeZyVBqw++qbNW~J_weAII_+YJjC)hY}A3}Dm zE2OS`%`vtk%lI>BhY6qj?Hber0$b0i z;#Z}6g*$__@M~mV#}PVP(FrM>*yYb%eSpEPxlDIOfYaSEU#0vdAuEe1o0YA8j#*yB zEZ-`tA~b=G>^z&1XRiI4FA51+-2UE}aFxE~z&jUM{dfr13JM|d8QT>d8QT>d8QT>d8QT>d8QT>d8QT>Ukk7tWP~JMW8{{w;g)bnO2s82mP53Nr<8K_S^8K_S^8Tk0ACvB@wJ#Rxk^{MCg5%ZC$ zC(CQ6o+N{*CrchoJ*kgV&n4jD&JTp*Y*Ut?KK10QOSs<-xF4B%k{?Vxg|<^q(vj#x z(AV}NNIUgp_IBziq)t7B)Tt+JioXIW&N(sltl&R8^(4nm0Gno@>JM%f%Wy{bX|oSW z-S;s2lI93Ig8yYMX!awib3t?JtDt2rXih&5iF7V#n)W@+ndIwS&@}CPm@CNFxu9v9 z3o5O1L31tdsVzB~s97JUWt_yBrhN}%_dT*vbH_vo0sEopt;8a3yjYvt@|GF1ukfv1;$6n*I8hE zbP%0ZXMyoiwvo;P8EgiaPyS<*ULOyyVz4rMHt zOcvuS=>{JCA!aE<>4_VtA>w1yoJ7(wm!naXj+$9}fu2l$%J3eA^i(a@14x^e{#!La zB|V+|KJy0Y8Q+2YfN5C_dKQ~#5V`ZHX^Yi|m~(m?a@t=6=}J3(bpGP5J{(h>vK;m< z0(5t({EqTDK19HED{YwjxCJ&Grg)VEbVc`@~`q7 zqbD&7AfA8rj9m5Yg+C0+w zK}TDRG(2R-fgdNWA9S=ONb3h3Z9ZxJprb8GT0iJ$lgsP$gN`;?#pwqfZMij&(GNP> z@-$%pjr%-!VvqMrP=5tCMw?wHexnZyuKxo#@!ik^qHCB%oa@Z!+BGC^qQFfezyTzB zrwDKWiLRr7o)>Kvb8aLMli7!4Fs&fXXK@Dpm-C{{ekAq0Xmcvhp|;Zs>J6q9JAl;B z%*>hO2h$4j^)oYb1^NGMT5%B6mmD9{inp1OPAjNH-6@Q{nK6lJ1wZOb>9j&fomS93 z$DS7rHTUlfDOIEAMH?PFZR~l`P_yAvRHM@hQKQp}PH^pc(dM?h5lGV>Crx$1w1Vtl zT0uIPR?uAi%*^P`jON5R@_d9ceU8Uyf_An+<-BN5Ze~nkTJbiO>a^l0ZFR zu?EQG2q!zd_9?0M1N$d8dYiD|`-h*2dArFc565Ux%uc87o}Atg#Mt%$Zx#9$Mi z50D}Z(=k&FFK|-F&aV=u_j0&)&xn!njnc-6C@GSn-~qxi;fl8 zDfC?vYiEJc;d#;V*kd4r^P&@f zyOs^k^P=r_jfP&8_PRz{z}f2>P1ALa<`5WXuWK|-*EMDcI|tV_W}2^S%rsxum}$PQ zG1GiqV@4*F_PWN*CYXln8h?-fmS*gAjV~f_WacxBvFAl+E~3Hqyy(o+m~!H}#+y;b z(=(l@fZ)2u%uEdR!F7$9_b@=@wt$Ca7p>l!o7*EMDy z2MQ2e*O+O(t}$b;YaBoh_hnA-A!g5u&e-c39gH>hylB6TZIspP8uh&B#2S`Y7I2BR zBy|CoxPc|t1zh90MtXNgq@AV9vjoyx$-M~y;iizEaI;R1*EQxl(2a3jBl&rIU8B%k zz~Q<^(s8}6k$J}Tx<(b+3Xu&>(@cq9BKVJD4Qp(Uk7Cir1k5dY>~8n9h5DR)~|!I?WFbVplq46ejSvp zkk+q*vU0MGejSwUB!8)V9hB|*0JMG`lpRA_zYfY)N$b}^*&5~b>!9pd()x8!wuiKS z9h4nMTE7m;jwh{O2W5Ln>(@cqKGOPiP`016ejSvZNLs%R%1&aw`gKrtGHLxfC_9xh z`gKrtfV6%cl$}OezYfYyC#_!xWoMAquY5C_9(5 zejSvR^O*JPpzJ*I_3NPQeA16OVSXKyUGQCW8a;(NH**K}tM|~QbK7v7)vtqc^~?JT zh%QpbqgDHXkf-QYC(awU^7qbX6i*g8A&AO5ao!J--*5;xa??klRfac#`3pNOMcjJMZhqNy63Uk|#Ru_1MU3jdBF7OKT$kzp4 zVLoYH;1w3Iadd%K7$IL5c!klILF)pqFv^#UF7OJYe7WcXuQ1A2u`ckG)&(BY!u%(L z@2&aHF7{r8(v@$+uz(Y)LAqsGUzc@#E!VLYC$R?fJow_2S6CZ755B0^vC8_oI6$_p zuZvB7g~cYn!r}~OrR(eBOj^SAHD6?M9(-}um52_mJbfLsoVH%_GAOT}wq8ol1ue_2 zlAIc>%dS$ERi(?WlD$wg5znX4>zn< z+J2ukELO{hvE@1R=NOU?W6N{jLo4Wqv1RG9`eAH&9=o-E7+an{4W{i=;@9bA>9YD^ zYsZu7YdZC>7fN5slVa25y| zB#b@3yfR^c$R4{%rN2?(m3|tg-9%}v@JfH9!Yloa3b%JXn#+-$z3b8NIQ~k%Rye;U ztW0E9`YoZo>(Mmb^=KYLRolBBjo$T08}wVk$^f79C0Ym`fh~ow=a*Neu~>1v>yeRq zetCy?8;f=gDxxFCZso|ggdK6VwSG(3ksz(#656{Sjo$Uh?5a{N9Vu3eJ-@soy&v`4 zyB>GI#7<;76OF3tOf;%aX|1}>M5F3D6OF2~cRfng*}ER4>N*ozbxn6Y8oldLswKGV zaRcm$L}`h=>+usHBhgRcS02TqLCB?#xXK)&gI)f;;K;XxU8(sX^;^QOlv>Si36<7w z3A@s}Lq@+P?8@+IsNeNS&G8hvho#vC9s)t^#y{~aI+)TX)_b2j%vj#A-Ow=b*m<6ie74X$5S<@der zmo#|KvMN9EbuZQ+PJA6=@XH$f&ax^$^mQ*`5KvKdEkl=TXcwouM9b&zgUE%}$h~PH z{@m4G24~#Kw%Z5==oZ#JO8G$s-(}~(UqgQTy8QNa`H7V8|14rIw(`eHD(WY1$ zNUHB3t9wifQ*{+>ic{(-RzplT4ZDIAJ+HFfWaSs2Q9IS;ouA-s*5X{6$D^dk)iKa~ z8RDO^ZM7Zy7XA*~4hC$sOK5la?4efHvCQtFgty#5bR$PWO=tu^;c=fNNwdS_|Bb&} zoO1PPMyhk#LXx^eNRm5*8z}Eaj>ms(q~*Y%miDvA)_sg9R|BoJ&?c~OZ#8}mR|AnA zA-NieOrK4z(+YB1A-Nie>_9RSeE`30bmSCVxvj*k-4ZPkmE z%=@JEA|>+yX}w6v{DX8=E>bcdlI}}#VQd_ifq^6!#>SPvV3G@C6OzDCk_%(gB7u=4 zXO5;-0*jJd7@LR$mL$0_Hc@vv2GONSE{u)m4kB=5k_%%KcWLnPNiK{{N&+V*xiB^v z_bSAkp5(&V6kImw@+23=rs%R4d?Cq&u_?I(a?VR~VQf0wJrG!t(>V>49(wWOm`8R$ z2l+heq_`S3_Vy&RhJ}>dlgwI@dV7+&fyLF^lgv#lEw?jW@FLMOQGzr(AkEGUf*_Zz zDcr*XZq~_iH5}z?*vxjxk8(9^hLq-N*bED8xEl5@V4jAnVQ+@vu0M?Yi7;b8-?O}M1DC%t%R6^chS4_b>q{Tm0K|R z8|g!sw<||7xzQwhDl3_M!zAZcJ~s-d)4z7Bkpt1WI8*dRioSOwhej4F z`Xi$h{jZb;*L_5Py%O9nQ}q3mxK~r(b84R&J&@wfgyJ5>nX44{YHA;+cK^+l;$SVp zse;ONe`B4z)s8!nUvC0)oZ69N6!rTCbqY``A0%qVRoq64TfZ;g&4}wU^e|qPzan0@ z%NoT)tMWr8XSgcHzLkGsa;Ez*FmVpQ_WUiB`Wm6d$9!4RbXMy^gR{R=zu$Kh=|+Q8 z=@8)@gK!{n&7P6-6rN>)(}s#OPqfcBM>ob_yrr^u71I^3J@FWn-BGWIqt_SX+1rK@ z^8wq++xA(E1t;LCFmJnGAUh0bJbRslqky}k-bBK2FmnvxNrY1YKa=TAJ^{bkfH893 zloycS81OTh-c;td2mDN?H;wRwB3dHe^gjcqE0|3DF6Pe;_?b+v`#(|o+<>3S^t!jf z@4SGY$@IF<0=zQdXEMF+k5TU%0)8e_;U@xqCe!P_13aI0iuE~M?3FBqI>kZBmAF|P zmRwGp9iW8Y!ogNN-~r8AC?4=s=6qw`J$VSglAvh*k;gfnzI&2OBYbhJ1A=?oLT-P= zP@?NYd@(_Nh!YIMD7=>V`Vfx^OT0x;#StTK{R^t`iE2llzeQEs0gPF<@(?Z>vJ*ju z{T5Xp$y=;CuM?#f)hr{(RZ8(j3J`_25Fw3POyPkz-+kl55Xc}U`RNJAOh||8170qgaq^P zUjjqI-3a>f#n14BG}jZpJV7QnS83eLhe^T~!gIN{yGhC4Xn{kxEjFJJr&uYV1R z9OZFxWETef;%E3Ev$Fxe_!({>TovqvAsRkJ-i^UnVm?f`CEyND_y}?E#ZP9j=bHwV zAmONnty|U}O&$qJWb-AOdIjo2c5tF;l6w-@E7RG8PKuq6!%CQ#AmOOXM^0HsG?URF z%4B;{k2^Tg4w5TOc03IT%7lA2He4k2Q$Ah*rNb=2o-7% z_{Gn-n)Af$U^($?h`&su1>$<1fcIa9JR4IV+<>|dxH*&hkbIngn=`3TIb_113+1Lh zBb*JmIg|RFa8D$>vO|%Ka4FbaN(E>!zTfZqB4y-HU*xn=`4Acwax(pt3oW z8YPL;U>B+UBbhhvN@Bw z)ZY!YT9sN&eFJ{XGqr}G6Yyi6sVk{@81Q4BskKx*iwTA=d5l8xklsuUq$4u-F5Hvc zCY#%Tb0)Q&%Y50KNp&jB6;YnW51!BHHpWo`E%qe`5&RpPv@66bA|I&bA=nPnqZ0Y^Nn?Pa6rf(Yom zEgQ|JnGORY77oVy_Jn4Z42sy9bJN> z%Etd3x4ku3MP$qP(neoC=9#U%8gLOm=9#VIBL{Od9_`tB!fvn@kJxO3Jc^1AIO0Gj z+ep|C7~YX>A{+#lO$1zcf@}i5a46gSA@VZ;KjxWj`4#d9Io^J}G5BVdD7lq=wjtZ7`V9!d?JQH0Zo#d zK$L9o8J--u3H+33WAHOnNp8X)0JjI-sF2)*A-LNS@I3~(3GC++f?gIi;WglN2J`^t zCX@oFE7(3}O(R_J)#6v#E+5Bw;61iwQzApbc4)kLT!ggfk+-mz%4T!E19jn*u~xBP5QGX zb@JV?6FhcXf7Lrn>Wblcau=HWA1`TGk9u=Y_N38PbvE3KQRJTDv1R;K>y|dK-?>XX z)+JvV-*5@^c9(h-jfPw!C4C!3Hk`~G=Zhx(s*9I4Ozh~FzIv(CgtWoB+FESp}9 zb#D~1IcxVL^(?`Aewx+`9g4j0DtZ*Ia_=xu?j4QXkn;^Pn4QSkuy#+R=a_<_*Ey{C zT}^uR(!!3@mHmxch>>)6gK)Kx)TVEMq_sYa7$O*{sY?A+BI8GxMe3yThM3B`cxj!~ z^$?HaglC#n$Qlt6c5A~NGORVpE^UfBQ3>XG!|iODdXwyFkbco1{Q~iB4bm-|Otap! zv{|}E!K80q+H$;+aJkX%D#)j8)@pP_rAeFFG+sqks5EuIen72^F%-8O3Y%WPw9st` z&aedhnyb5|cR%`%oXT)od)QGvaoOc7rf7YAWU$>{u1~buK5@0r-MzFPACLus_IQ*j zUGP(vU67hzNPeH0fcvFFiwFTnV%JC8Ce21k*OvR{eDkYK0` z!lzsg!sh*tKbT)%;?#nW$cB@t-ZL({5S5o+@N1W|1FBbh^|Mm9aEoZC_^s5Ow`zv= ziQk#z%r<__@@hzf&s}txIVVLkjCry!X>ejnTYJ=KlzE|WU2F8|^Gv@03~jLsjr{YR z+B;YSrwheILvc{j#$2;1#p#wpXQk8e)luqkpws#mi#${qET5=Vcu&HBJ0Z&8P{W|7 zPO9ussWP^q^pOR&Q#h^PXSGcieh+mjzsD1P&nNt*TYl(sIHWV(dYm)m<%Lj8)N9wxKGD_SuJI_=l7dp$(zBezvW z-cw>whk0A}LrUE>f?go^aWmnJkgoOw2PcM{jG`)#ME)&i6cw&8Ja;ubN654B7c36d zGD7ATlfrZ%V~!kT%#~x$6>xhE^;=7l&TUje<939EcPA3AH4=`L&8>A@;Ijmg_oe~z z-rQf_Cq&+rR^HQ139k&0_g0m6j>>CNR$g)tc`KZl;=%(OtmR6{d+{ zKWD#Mp!a%){Rzst3rK{G&|#mlMHgrXo>I8MFvsdnu90{H#z`-rRK7I^GYIQq)N^Dv zld|*}pXk3OvaFyiGTvrtC+Hb=DBEDBnX)#MDQhNYB0LI4$b`77*6F+vGGXnmRdAp) zdS|M%C6m_o+BdGXj4f>$GN!jQGmLWWG+ZH1DHiC?L$LOYOLr3H7rJ!cruz%m!GX$u z|0GC7E6Iz*r7KpF_njwkS6#Xj7NB0?ddUK1!fEIaY9)F7tR!y&cL>!=@+Q0wSgj;) z0zYo9R+2Yi8_=qi`x@D?q+`yVRbkA{oKv|l!eGwceCHm-R$>s zH~Z76ySkhGe(q+!`vK^p?q6Qy!H9>6PIq%~&LE(RyE!L`7uVDh zq`SFfBL#@USwvWepVW5vc?5rH-Z1Xw@QR-yN8HWfYHB6!=5P(g6nAsDRuJ^SfFS6B z0V1foIof$RwG>0H;X^0l>N|^3uzQD+wLnNr~=IDfVfW_S$Eh1laH%E(Ek?L-a zPGr8io1>GNukPmP0_Ll`Il7e7jJlf@R(ErBSqIqbfq^GkkRBKy6LmL7Ka+ysZjNpg zZ?7I05Ks>cP`*BQb97G@eN5Th*N@Hmgw36!fnW{{2pc^x@HW|~yE(f444~vFkCP)i zbvH*3GF#ov(FVfmZjK%zZ*@0E4--~*bMy#t;BICXd%kH1;wL#m>iJB}|OFIqtdwIXo~>ia}-$42XJqU_f$($&U3vP$q!;(>wtfgtYYR2kb+Ak?C$urq#9yZF=2U$LZm7FC{XrK7kGPxDACix{o710i$f&zH z{TX3(H>W=*tnTLY7lhT_oc@xqx|`FE%Y?d{)2<}c-JJF$q3-5%APIFhr;8+^?&fr{ zB-GuU4&AdMp}L#Xu}goXx|`E!d{EfBo6}iIsJl5`?zZ8Mx|`F3T~1%>ZcbOaobS}# zoUU^D;R$s&r)%A7kWhDXy44*62I_83k965+>TXVtl7zaO)1xJ!?&frdB-GuU9^+mP z8g)0P$BJy~ZcdMPZ$vr9-JB_T0!<2d+- zZZ17bK)RdDswqf{KIJ;l!rfesf8uT~t6`3DH*>gV+jd9BH@lm&BSr#8-ObricL5f6 zb9OYJX6kOvb}(Dr&DqV_(bV0X9Ya{%&DpUmO5M%baipcYnH^o+&Drt$e)b7j8) zsP5)mZ6}_$;%?5>@sXqM=3G5tbvNf4 zbFSr3Xed_;i<6^9Px<(Ztj14JB61iDOZHtuERAX$N!!TqnpcvU?u{My(iItuE=Yh^`ek zSF0;ky=qFGtZLg_V!{@ydxz`Tc5`>%`i~7u>+Go$J8ZZV2j@wh7-BYgAmyX)vEh6Q zRVE|$T*G1KM5rN{d23(l!+^P^zK5KVab6?+D#L(=u*z;I#w*432J>XBwP5QHaMPm{ zcO#YG!<2*NvRrQO;Xo*e@*7q6d4;=i*WJjPhwx6*ObYQBsawB7eO*HRb4$Gjt8Mpj zHl9$|k=d=Jes_DV_`b4VOQ>%fK>af=xJli7KB;?2eW{_|J&}AU3R1~0x76I2aDT!j zw@`mVz0V_cr=f;(*67WhW2HXNQuDpq?s*&tpe`(++UIEp*xPCTBPCf(UiZvWJ+*5d+j-4JYb#_7Y*+cc|D!jpB_LQ~iswsuLnc7QJaQ=P5KR}XyV^FQ)^>Zg8x8*KibMXNYKwEd$_Hd9%AK`k=oj8k0;bav3OOD z%appOMOZRIxbtq+?2^c-DAg~2&WZ4f%A9`rXh`Joi`ri z1IFU6JF4h>H1pbh8cN_C=fz?y%C?o4n~z(vZRM4}L^Rp9^74drj`J!W1{^v?8dp=K zaWzF6S5u^MHAMr0X~?q31k(&dfqwh7$SEEWL9>uJYSNU1AYXvA35EFy!5O??bq+xd zeYu4h8fkz+8Kx1Ag{JNnzrc-~XRDHZ17J8ZBJl)nK@ig#JVKl|!v<2dkgC{FQ9533 z@5u>Oi=m2k6ZGHVHY#0?wzw^tn(Kt`v#AG>m#ytv$p{zT{)&cC2?i;zuBe;52EBya z-l{2)Y%!TsXNtRpZVg#^tM*P`X&Mi45^`nW*QnK-J?ZPr&2DouHJE(sSRe*XYA#dt znwkfcIHbJJndo7Gv!oVPpdIC9;IX4b3^2m=drT0#&YccE$FifOrK7wZVTSRVeu`W2 z2=xk+kc0C)`1J~m?bK~Ug>~D|E381iZX0@q<57Ta8+rx$vvk`~VcjTl=VTzB3Em=D5{4n& zdZvd)giY|)LnNX#9aO(VPK7^A<|qzh zE>McM)!LK7@V%6tvO zE1pJpLQF?+@pQI~`bCPnn6F`Y#oa3bt6!wJ`+D?D^@|jDe*{?lBE{YGLaARwVfBj? zce91@k`nb3uxi7QTR+i>P%*{0#tQ+++hr0z!S|74`~++-<0oJP7(am^sGmR()K5SJ z>nHe(6{znkB8bUL`~-wUNbnr~8$SU->nAvo?Z>dRXc75ZKLNXl^%F4P`U#kC{RGUn zeu6&&wtfP_)=%Jpz4{3*V?pXCAQS5+kb=Zda4!(divFe^%FcqHr7wD8&GnT$H|eM^%F4L`UwbIKLL4LKLKIuCm;^|1k7Sj zFb!(_1Z;Nt2`(d3^%G=JmhlrvuKEesgieaXirq|@Bz}UUkwZVhiwTqMMLqQsNUr(` z-T{I#AtX#j+lPfW4O#K*JMl|D!Fd>B#!oPwMH@eXHnRE&2wOjaHnRE&2wOh^Ve2QL z@YYYjeCsEmLe@{fabx`i#9wCp1RmtEeu8S4PsUF`KGsjbA!Gdngsq=|u=NuVwtfP_ ziJyRp#81FP;wNAt@e?qS_z9Ru`~*xSeuD2o!o*K-01}CxfC6h+8vF!IBz}ShFi89a zoR||o0cY~WPcR?c5;37AOy1WY7;0wxka0q54lPe9ocKfzLz zllTcPMN@3zC!oH@Pe9Q638=aC6OdmP6U+$ah2$ZOfiWCwsEUm1DImS=G;hJq525a?S`3b%R zk@XXt1$^Ttko_nLOUrgJ+xiLEPpqGSu=NwLDC;L6Z42sy9o_f|#^JW{6Z{mQ^%Ioi z`4clNEmz0KoAnbAwtfP_Ud#ZETq9xYCm?M71Y3ZO^%E>ZzV#Dqjr_z#?+`mHoi2U2^8)xaKfYj24P(zd|uPp%~pqvDFr!NDIa9cGWU|la%p5 zLXj~PJ+=3dpw#6pm^yW8>bR^WY^~Lctuw@ZRPN5J7h|VJxYODR!^a_MC`XAJUi%Ih z{e{YvnSvir3Lb+>Y!u~QQ{8$Rd5qV6olT2ko21yknoiee9f)x588MDmhomtMa zOuoP$Tv+eR<@PQ}%6Zn5qr9FsyqxCSxekAXgy$OS9TMvG3H2jZO4$;8MCF>Jyq-*W zT}DZ6Bbz1C5mtu;xg*c8=mPC)|Yrm<*wk?-HgYb28|7;EdWgx7}&uaN_I zjkLUYmf9VysY6;`GYob&3<~0o+gyv9R}gQUNgWQ~$7Za9!MuC8Av`K6c^nqLszs%i zJg-swTUBeM_2xRQ<5}Y+q_$S#0SUEIhL&;_Rg6sSHEv`o*3{fa@#CbFYY*P+0fhqR z49rNz6g?EDZE1?WYG$4*P#~|KnW#S+OJ93t>EAG){_mby;>WS+@sj=jBkHtdIo>^K7*q&K>3#(r>mb`Al|35sl^v{ng8MAj8 z>h7y2l{_q07>#mAefU%0_sU6%GbAb9Nu$i!scsEDxF0(dQwT)=t-q+ zvau(X{)j}5@;EuNvnQ39ZBHr@{#PfJhy#`A37;qv}}`=rvVkT5x^#P{X?_nlOF7u=GQN-k`M|Gtw- zAEAr>^OH&?C?`3oR6y6*4?nbE9NA( z(&qLz32{=1`Szrez%&VQQi-rRsl+nPNhJaGq>_L%3C&5R5QA(Xh_H2hIBE5y5_1Ne zRJs)z-)s_=jW`oH_M}n{;{217O3eOOCzV*#rYDuy(ZwVz8^0d6%}FKMt2QTSSiK;toPFA`HO3M+A2Ou}6J0zfqh zbGbCu1Y#2A%DHS%lQ5SjtR`X3oCZP%0h!s;rPsYY-3(eitW(}ZN34`yUeKiuz3$}& zEzYK{e$;oJhCnm@>_ z!auP*%PY9vi^LieEG~WotC}j~4yV(8hjqLsvB=C9eT197yeuo<`94fM(J4Q%PpACE zKAjXc2aqQA>6D+?r&E679njAlKoZy-K$<8z1s|e@@{`s8r!#nm@MJb*S8yua{P`(d z?#&L~Lr=?3Wozyn48yZ0Kdm0N)EqgYo}bRLdV(}*yS7LE-oaz&r1@^jIX9qDnV->v z`~|^E=FepQvfv!Tvk0#YZpJz{zXRdbs2JMll`n#6Nx&y$ek2R4l9y#w$;+~;^krEd zUzU~M{2!>LO76)R^ereuRTV^bs(uGnZk4_)%j3(k@>_CSJVjOJ0g!1Xa{LU|)m;@O zpCC&rydvzY@QRRvX(v)xE4)H{9omU1!oCWx2>U8rVXg3rP%2y^HYy@Y&>1wM+zL6v zJ~5a;SR|X|c%Q-=sYp}Ant#wRDWYiD;r~SeYC(ZJq02B>a%P^ad6Gz#Ly!~s%kER8 zno;2BO7LvtFEW|6uM%^Q4Jdx!9{k{Hm0#rct^&QD0NaBgV;t@yk3HB8bT5^1)Za!P zyO77WhDTGvqhSsyw&KkLcgGK|=aZYSfNSG4B5cC}Lx)P!3Np*p8Qkd!?g(@W6(+}l zKw%^tBWHxE<0(qlq~Uh*knxz;*DhFos1@+r|Wd-Pyb3CAHE9gQ0(Po!Lrbesd4 z(FvR*8`0*v|M%fmsAm{mXBb_F;1;hF;iiyLYm6=#wO;3VNFbfan@H!A+5ekJ7nIrm z6WHwkO{|7)X8&*E>*&yC|8L^`fX)7&z-Iq%;>Ez9AfwisbS-dn)OwSD4*oi7y(xc0 zzK&XN>Tdw+sP(2@hw9f+>rH1_I%>VH|3JQuTCbaO>ZtW*u(@>9dNY}?qt=^6SVyh5 z1L4&+g1HmA+X&_%C_w7L-&X5EBbX_V?$r66glz;fVH?3r*hVmuzZ##u=w&0AnXksD zKaH>&pT6j2Bbb@5#;4!?GU`o@PrrLB%oa9+`Aonzg84(NDAoA%y9wI}X12wDDT28Z zhyx>-SqlRrm>ZE}BADrL9~i;hM)ZDruEB^=MAr!BQwj2g8Ns;(8Nqxj@y!b}2%8Az z@dP!3`9Oj*&<~5NrW53zYw?gh2x{>12?RB6c{xGdk7Th?csG9I7!TVNKl{=OAk7=e ze&itJnEgoVV)i2`oY{{Q1l^Am1l^A$g58fi2Q18fBtbPkqg@Hp_&fyv&3+_7yB`^& zbxWWL>xWWL>x+!?Ulk0fmOBY%XVbU$)47Nq-;WMcOtr6Adl zoB;&0A1R>jM^e5%<1@PFn1s!J{n)He*xbn-S+gH0Y;-?zC$h2ok$*-aM|qqa+1dR_ zX50Np!gfEByzPD@VY?qm92lR>VjnjRYW5@9y4;W4486qcM_!J)F#C~`tNW2`LMO#8 z$H62_lKn^*Ioyw2kTBU^)YJV)$<_VHWk66SgoMdJ<1?N;4L7(S*?{GO*^lI`XZItu zk##?ku-%W;M%MjE!gfEBu-%WO@OD3v`F1~&3fcWg&JK1zlK9K)e&mmE!|q33hqZ>; zk0c+vAITwO_ah10{Yb)gKa#NBk0hMzM>3J@M>3J@M>3J@M>3J@M>3J@M>3J@N4^OO zll{oQBa!S!Qs87il8IzL@_Zzc{YXw)$$lhfxnw``6L3rRBO|PolKn_7&yxK}Hd?YD z$waar$waar$waar`6Uv`ek5f}_9M$sPO=}#x7=*9A4z@9ek4J=A4$#aekA!ZZkbk8 z6q1MZW@;cEk-2x^p5*eQ^OD=&_(a??^X-15z-B*^u-T7fnPxvyK;4fNkj7_OH3dNc zK0ZPRA{d{?kyiI3nPZGk4%ckkJ;?ZG<1;&gdvA6>atI!PW zVD=+l2e#dhBy9I1*&+EH8ZLaewli;v*bKDxO%Ys^N$L4Q-;yt1;POM4dz9pZ+#!xHBl25li^W|5eEW9WSzeAn??cD&X`Gd?x{4;NgcoJX~K80Vw z;^IfJs;M&Wa5^=i*P_!=6__K7zQj#`DZs9Zq3dW1J&S|a6>ZC~40M8DVBt~G&N6X0 zt{m_%!s+03>@8IcC!7sj=5I#0BKQO05rnIPYx00cQrFsmF9og`#nx#Ij)BcvG5UD$ zZwYvGzoO$a6x$xGApYiTdDIQzF>K%o!7hZQu{#~_VT_rI;-7)Q-wT-S6;&h-_(tH0 zAv=l8$HGLYsMdBMVnq#QsM2z4xusVt?N(98c58IJG8P~&%ZDvqW| zwWKVU=+)NH^c<(ATliTvfp08VjR{cYSes@Gh-HIQomgq+AIw-F_L8Uw=;m2I%cXq;0 zqISz-?pN7Sdu?uRCMWc|@ho@bIr!J_fXF??!YW%ene#0pa=US1}b z+q<5HeySLRRe5%wh7(w&`w3mUq1!*98x04R((PYl=o-<5-2+VV2kJX*4m8QRb?kNS zK_ZlWDRQMLvaepAWs%ZHMiprvnddZo!tPKm6r&79UyV$}%&ru9OCds5 zBtmkIcLyaxa%y)64-~Sph(lUxOK+hdBxG$ z$eMd9;5#BPP1MWlk)8=omE^(o68-SJ2#-j2j9pF`GC8jThRjf|)9`EZxK^-68Wqo0 z4WZ&oKvWg4H6rzB@4hzB-fd=xn*%#T)NaKpyF~bXd5qT8sDxi04Dc|{}nmi*l!x1F!Qu(zg?yZ_uFVB_VnB;U7{aIg!TaP}re(!5npIa}Fhd=mc zns0i>2y~yegi|jeL4OiqIg}+P$R;sm)mCsO`?1`A_;A%?ZKBL?6J>t9i84RlM43wl zDs!okenx?jo9<;MIa77(HOX13+vSOFGSOV^>qN6d{Tg<$n+@{zI`7v~HqF+dxg)2Wm2GpeDlyYO>itO*S8> z$u`l4r6z*_uE zo<7BQ)RFiX&yGZyz+dys6TfMy(RZaOQb*!nMH~)#8HqMI2P5$V_TTH|{?LO}+{cqv z@2$4tUbl(3*KH#14Fko!(TLlvBk?AaoS~I>vq{d>%DctWS!S*-W^XljXX#@0Hj~`G zz8Ftr_ioRQQyI4RnB;7odN-Kl&N^%#H=O4+?P{80iK&+Y&a?f()0vpn(6SwPL9evDI+GCe?7lCe^TLU^Of@vYTo+(IibZoMe)w8crTq4X2p9rW%%*q^X88 z23EuO2Uf#51FPZuq#AyBkm}aI8ZPQr4Ke4w$x;p9-(OLmPkO_3wYC~2Z&D4DH>rlH z1FK=0k=<0obd#J>zd5IzE|WCX&^@pkW|+IC8fKcLsfL}BYLEx<&I7AqkAc-NH>rl( z5BO>|9MG>CDk)d3RKxuJ6ty;~hN*S78fv8)Xr;;01o{r!KBl-TS zb)!ihQ2%2-3!6-GKV4B2jN}Juw;pAZ2RpU7Fg6*lc|n5GOE+_I?oXN zyQ!f1BVmZRZ@cvCur9=me#h1Msz+D#?;3Vkl*o$dJ(IqDsgB#fyLLw4+kM^lO>$oI zT&Q^jlvJrcGGtd9scd@vQm2Izpkf8mjAJw66(f&kI zq0gHN!wg@u2nMn`fKk z)TXNpgIx^+?I7oviZJU`o5W+GDQD{8U`rsSU2IC5E2Ujx*iUO}GT6IWY*_|hYS_=x zp<|P?fmFK%JKu4FFv-X^!VtT?QuCFKjfo8z=LeaUG)+P`4@^X70PAImwl~%`? zArKh5xlvA^Y;Qz1hhBEGwWl`7UPj;p^$g5GCOOw>Sj&#vA?b(q)KZsf*(kiDU|Y1q ziraX^ehWx&EhZD346i$!>UJ1edURZLm|i)jj^DAzT{>maXPu$Xv;VxtneN>^w6Ld> z!Y)N&ZFo^)$%&I|jSFTosgLWlI(piqI<7Yo zw~6I@y{>NNwn=5&pmi~;jsAT1M*5$_iok_y5K7YYT!HosZE$o z*LLuDZ0%--g*xwz(1<=gl}C z`8Ldk`O73Y&YMNphS?Ba{V&37v>r6fhVs}j8^SishOiB@A#B5J$lr$9P_IV$E{#8x z`8Ldkunn`JUN+2z`8LePfi5=8hA;iHVKzqtwqZ6eqGfHE4PhH*!}|X}A7=Blu{CQU zj*YD${J$Gp(?6i*M(~Nbua#PjpE7J187H57cP6}oTi)LoP$LN67*KNpn3{kZg4oH# zNQ-tQ%#F;Q@ZSW~5VQd`?*slH45&F7>@}cf5E}d&18T+r!35L@r~x&UuYW+z-U*wp z38*=VY^>z6G;MU&If}epoWc>1k^B*1k^B*1k^B*1k`Y4|IY(z7{!wW z)Ks8rY!XmIeN8|OK^ss*%{L9G;pTW0l81CeY9JkvxmO?|xk;GKCIL0fw*fT*n}8a^ zCZL98nt&PsHK0boegQTAfU5IBgn*iTNUH%g%oz|+a}_fFRY1*R;Mjl~ACEc{P{XH{ z4X9zZ4X9y1u>m!NZ9ol+vH>-uWk3x(x(TSc3AgcjJlu#vo?S3!CHTcCdsc#L7;{$Q zkHE8MB?#NI5^QeH@)FdcrzDOb2YEM9c@tMP67W!7=vy?E7x)0zMU%q1XeuxCEt<*; zEJYVh9N{N(JQtq9f}-H9dhpICc;J6RX*^C28BxA#u) zsr`N@z!wR^C!%jFe2FSzGqF}SjQ&$oowc%E^fDXKU$uUzI{W`jU1{%(q($==mP04e z>k0=9z9X3ZDwNj zRKnq)r5!?m6qaxQ-XyFL`I`vVI)R%>xu-JJ_@%_RW?FB8 z?_!+PMuI>P4Wp%%YH72znevub6cTdA!&@FWBU>=i^ti>N;6OWY&MB(SbPQ2m@t)wx zI5l(JLgLiCp)cW<#Ho30P3RdKr{=XkjYXEmsd>W)Yn+-loUq2Jd7BZ|I5lqsVU1Js zM!pMJmYWF9e2pqMC{fR6~r*?lLztyT!yTUrP`x8F~ zzS_h7q+5Zb_OL&hI;uVFPx&+Q)gJbzvfk7l_NVOv`PClwr?V`zhyAY8kgxWz-%UBy z9`PCibvDi?G_m{tkp!t34bPbwPJMb`osUgaV`0%HGTCq=ESh5pA*irU(d zBgamP+7|-sf9#}a*l42nJ9bhuVhf_vG%h-a2gl{uNzu6kdF+H=mbRubVKI%1tF|G? zV<*MchZCHEepphqBS9WJDH*aKK^{9Psa`^m$4*LWRuZI@9ByQ>QMduWaXB8Wsh?FFG2>yPc&BigcA~HzJBcs56h+ZWj&B*uf_UsCzKu-u*h%~|DG0|-;v07cf>_D% z%>vR&j&G-YeO7XO&xr|}`}(n2pRl>}60)I{9N#T$XeGz@??E?FSaEhKW3$H|eM zTFLQ)%vLKo-auHb$}Qw|xmk~5zXRx3I4IbpSuGhYx^D>?HeVYQMoj?08v$r)D?Y9(hpNvM^a2_&Ib za;8WUY9(iiC81VwCUif5glZ*cV)s)d)Jo2zT?(wnPBK|Z=&_SbIig{#m7E#ua?;Xc zCz(o@vz#6~$yB*6)@N!ZXKLLX5^5!9THUokQ!6<$(q*Hmm7EzR3AK_lqa~qMa;8HP zY9(jJAWX_y$(gYtn;tvKjCU(hj-u|HCHP+ zvzChU*a^>1L?L-dZ>9#)5t+-ktV?d2&Fya`XSQ>hFIIAfQ zY`K86lFQB#kXCZGnu4UNpz4`m1}phw{1YoVTf-boOO zCOiPeO3sbuGfb`ITnDq&O3rQ0j;2;}ZVX|yl5=BOlv>HTaipb{%#JQra&9~ifJC7@ zz{57MGlx350op?yT-lgI9b9bKLmh~v`6jM))S@f&Ev51W zKGyAV4#M_0N8eH^UtlS^l*$+SmQo7a;~cV-vd1}m%oQ;B@jFD8pa80?@Po`{C?g6v z1BsO!tfaV=FJjGC60lwTkz81PoqgJiy|{KAV>YGk0%O=H}kD5)q#EuM*PPPJPQHa`jl) zF{ZFXlEMnKs-&=9&lV;jLQ25GB-X$t=Q=g}lHakyZ^`K@{QC*NrxSk13O`!34YK2X zyhnowTa^0Q#uGd?EUdDI%UBr;Jucm$Ov8_vTx62-8hD1sT`Z-+jnG(UG}y(I*dQUy zKk&3Fx*B*S$34>|XJNZ;J=yIq^mB}~!xL$?umOr77#eq^vhkRzYg? zDeXO7&2qHmx4ePg(kzYlJ0p1GJi}lQ!=PD037#Ww^t5IPWHG6|IdC~|HubQ2))D87 zrK;-#CP4TSam6xl|?`hJRR z6JdQnMYizm%MtHDZP;ypd9R&1H2$Yvj(9Jo`g|-eM|=Y->-KzIJ1mKS3&eaq-)`Xq z+~dmE>%00&(d8Aca{TEa=*g#VBmuu1l+X0N+%KQ$d%2&&#;cPl2MgUG%V%DKvc{{E zq2jthmKWG~buv;30bfC$FJ)Kh3}#}1nlB^&F2@^;^=`hLLVJf$=s}MF#D@^^E3b$A z1AuDz;cMw|=MDVB>ras_FZ=rhfPLBDyOYsdOI}A#k8wAk=#6LN2N$A$ z<#KyFvHGiHj2kdm2)FWUpN1T6mr!iGLMblQe=u{eNGQ53MV)+?V1~ zV}YCSTT*~oF6+u$H3zcaje;7Mu#k2Moj><1<$h}-*3R%xs95c$kS^ugj$;R8Go_KO z>JE2_i834ijfHGx?(Wif2a_X21(eyyW_PzR$n%>cHN3Z7iGQoX?y1{Q2OY(JX8I*P`sjnmT_rFrw zd{V2$&0)okQaG3R7ZHDJgWsJr;WY{VMFzjQvySmxE!)H2VVqg8i(gGzAy{*YKdm+0x| z5GtJSB~>b23s=MVD%wx13#2#V$(d7R^4 z!g?Ks;~X$di#kw2{o9QwX|zE#mXmtav?96m;TwOUIE`?Dd3U)4>J zR;ypVh~NzT1XT>r3ID=0P1j(^5d^u%9aOI%NYgc_=_SZL?xKw>J9-)8W@GUOS9#cP zZR~-O{2|45;#xecia&i2U>J8{C&Z1Nus-t+Y%a&P|8iyJz zu5{Uyr=>ncHz=-h-vhVPQ?sZ+t;^T-FHgNd2CeRGKwFtwPuWJg_akv}>JcVJNn&;C z-WIa}7+mLExg^YJYl=G?jT`E9vSH|;9NQh_n3PV?n!Qy z&CNSy&!R!IwXFW_T;^xFG%xN{m`n5Gi2@ggzXX$#i9pGXM3Lc{EIxNLnkQT?Ah+|v zvjpUJUQ~TL2r|<_a610VosvbQWzcI>!yKO<2Z@V*0x((zg*L|9ECjch>!Entr%<#L zGf*bp?k@ntcrkBw5{}}t(RA@d!g0)#Z}B9;srU*AA5Z=*XtOaTiKl#o{KmK(6&+7y zetWz%e&cC`C*=7h#dtbTfpx_^3mSJZe|CIm3E=J*!EJ8b&T_jihf4F}yHQ(l_v?UH z#&nv;-93Oe#8nCWM0}s%KZA0gb~5bvXCk9?5&+l9T@6K3S5VK~Oq7&beLC`UV^Lgc z4TpMeEfLlV0)s_THwglRMN&5tA(CK`^v-Xw6u!bTJ%=CyhCrC!m2il*eiHxv6H!a) z-3Uh0Pyy}f6AowH@|%h2Mda(mui$2SF(;!SE{7`V6PX{zXQMBsPiB5Pz7CC$zJU4J z_%g_pzVu+g6)|5>sPN#pn($@sgIkqT5vFfBmjy9cBz+s1IPvF1;DJ$0!-K-~jW+;c z@CsC0`ep$cERw#R@?lz(Zzh7xJzmpAvMbdW*8wQJ{@BbOuM5DpI zBYk}rO0J|lP9@oe@j~kVAhWY^6UEv1;wBgzQklq|Na=AW^34 z0OSnn$jtn8!eo06Yv)afE7AegUPRBkx(xv6v$P5-K%@eMO`39xZ3c^+KQqm533~+6{0Bu`3 znE8$I9tFTds8DjB?}e0>5lDhnN$0%mUoO>@Yrl2;j{* z=Cbj;8Gy$Su8OZDo3SjaF+LQW%f^wm1>=MdI|&ge8_&1n`D;dlwrmWzMdsTDR{+lQ zr6}3DzkmqC2lGv~p0FG9?cdo3!d{+hy=)_4Kjv0#wux{Mb89nOcm!;UV!j_d+sqGV zX5tIbD%qANkw3`s_v4Mh*Rfpl?E(_WT$mjvb0LH!zv7Sr6^FI>_18hKT>K)b(1%37_-9!ao*2<>_|NMkXr%Lh|8ETwc(b znDPJR1&uShQ^B`w=f$;d4>(255*-vo% z&q+|e8j0d?Eq<$i51cyy)bIzH@_oMtHwRV)&uro$WU)9m3swzP#vS(b+y+P-ucS`V z5di1rhppukL`>}AeTw9V_bH;VDv}@Gr$~NypCb9;eTpcoisXljBC&i>U^5og8FOnX zKY~p)HRgLI^CJmQi=RNX(w*ts6?6+lAjL9S1ATJN*vGE&? z$nNAwn-E_{l!=@QI^#u@U=lT(7k|Y3$t-n2{1_#eLio7&1m;iu3uqUi4XL_+8E;Q} z2w?8_RR2`wX3eREUqa{NkY(lc)PjH-YjHYr_0)oZ8f!tY_DyKyR#7Z`i@oHJI59H!q4K*q2~GkdusRhIyN%yPPUJi53zC`rVh}PvcUeI8 z?ZJS*aNon7`sbjFyWHoH8+9EN#`Qz}2TSuV@MsWwQ88dBHTvYf!sjhodBx#%5VGlY zvN^!#=vaKM(%&J>klp)s!sdX4u4xa{y}OT49BL@g&*XA@n=tce!TTf>^;c5)U4$ZS zDDX%y6uTr8yYx}~f@O3G#ZBu}sy+(F`D+=C-v;aib(L%q3djAKqa=qw7jK->07GZOvO5^g}JW z_$NLS8Q3|+L1B}711a-M{IE8Y8%cW_-(=;aJWfUas^^xpK6#lcdb#k&q=Chjy4D7Z z^!}=iOH_PK^Ua2>$M!1G35KXEAsTLoes730O&4P8)|V^ML5Ap*glK{xdeIPR8ZG0r zt}#SM8lu}0qHPV)D~3qZ2qSS?2meG%T49L(k`PTbM6VelP4mSMttD3|(M^V^E@vxZ zFGKW(A+l+_@ul@)LuDI&=Y;AgL-mfK(li2FoYvmeT9l2mS)LG`W{BQ5L^gdjiYi{C zR7;G24Ka331$;lDy4X;CW~glX22dSz)T)dMB`WkU6Yp*qJ< z+4RMr+Q(2?2|bJ^?d|_=s8$*(o9rY|SghvxedVLt)damtqWmhqLe7F6W>N z%@{t!)Qa1CB1+Xc=xtZ$pm{O}@kQB@KikYfI!7>1=7_vgLc02+I7|Oo93+Ps&chSV zPm}W$4spfc+#~+q*K9#f(^b5^K}0+960O9~69)TMSkX2Zimpa3UfhR;fPQ)L+CJ(I zm6pT z4SzChueK_VWCi^sse-r6{Zs6Hc^F(_s$jN`8=IsLO&$g;L>ju%DWRD4wXB%kh3fPR zRf8`RMFwH1q>A(;6(g?++Qa2alyRaDvm*9%iHWJSp@+%6TrLAK3AM;8dG>byg5r6G zv{7`Jm*}wYA}#7Oqr*_VyJnI2-Wb-2Cl%dU^%48x6cN!kA}%uoZtqcvh*Mk|CG3mh zTb^N(+Ub`9E%LJiIz98GF0xJu+0=i;x)>=1m0h5cy`L1sS9dDstt{u}N`p1FpZufy z&XV$$Y__t33&cHO=DP{&BEaIuQ1p> zVbClCHDS=4FsOIQASVoVF$^wBBzTMrWQ~zCP12>~IB#296|OJ}&uyeV?GBRm^j7WO zNYmLJZ2H1Hr|lHB)XSWXydSB$49eo=_HK`tQ?^TCFY74o8YXkbt2#IJ43k#-v$o;f zVN%jx*l|!$^I?YFOTx@?hRa(}-_zT>4HG&3u3d7T^~@d~%*@jGI8$pJ>vucLc;xE{cKjpdfttkpFUS><9NWl+}`&R&buk+c_SDC zznhA6pfhp~iKmdb)ev7Vq$Iu=+d=KpJ*H48Zt}Iu*qB0Z0yp`FHByvmw)4p2V!C-+ z43n3wb!kaE4wFvTZG>pv+Z1+$DQuX`n=>c}^c^N^Xp_RMIqDe})5^PcC#pg=qpS9?|ifStDoc6 zh*N$R%r_CIehd-063o{>0PtT&oGvGUY=`~di#VmwCgSub0Hg3~{7S?rgWL3*aE!IX zoyYMn3MsS~;in?a&&NgKZ}BSxuK=jtz(uV8IZVe16{REL8IT&O$oADpMOH&<8H}lL zRj>k1_ln%3V9*}?9<&wZ3@ht!Jcd(NP*7_YD5l3H~OD#QA2+Ce!xHKv66!r|X|+`|fIo%!#~XaOTI6zjFHi8NB=}nqzk~SW z4F1Ff|Ahp!!*W62$8VFzo)n1qj-xKn(??UHJ8(fExb?->YNd{|GYv z?`r(F@qdKB8vjRcunF=zj^Gtgpr~>r!5s-!G2p_#5h@i8As8+PxOGwOzNowC$Hb7J z1}FL}VF_voqLoCKpoTEIlduFeq@z6v%a(pNI)-pF+2o>~2)EFj9T!a_A2DqwIPo*c z;#Y@KlK?b05_ecEafhMA9hQ9X4;Y~l;|@zcWF0vX;|@zc{RzM@V%%ZLXN0p6;|@zc zCtMXV?y%$w!i^E*4okiy+@5CKVF}!sNOYtbcUa;|VnUj6hb5jQI@63hED0phm1f*w zNs%OGrx|xxQY?v{G~*6SLYMCnnww_aVM**xMq*x?afc;omjW+HGw!e?D~aRMj5{nT zcYlC8i_(lcEHQD1X~rFvn7G3<;|@!z+-`6?JwSe^biCPqtQU7B%+B^{EuCB2b}F)nNU?lj{LOU8<98`6wBEE(_a zi*iidVOVk^&@zlWEV(q4xWkgw)Hh<>VaXbTPQ3iC9j1|29Fj-O z-boFlrI}lVgybG&bMsCq;||LhcUZEW%ltB~y-GS2X53-PM1hOL>%p&tfk0Wt9Y$xe z_$=cNqvZlJ?l3w_K*k-$)s!h_SmE>d%Q+=ak$`cBaSd}!pp=O+6Tw1oGaa+MFE}aH zHU{~52~NsOa8h1^lk)w7lTsr{8%l6eYSfP?6@!yfqi=x_PQ>7(R0p%eh`~vz&DkTf z5q)5(F@&ok1}CM)vZ%(0!AYrcq-AgtM}!0?rN(cA+Z9VtXO5dL^`Xn4gAa7lW%nTi z-~uO|)k4Oh@O19y$jwHdqVRM%kt?L|bpB%$bwR}Mn5Qf9$iF?}QXoC38NVNE8!=m| zVyUKiOVZmxpo<}eUx{Iz9()zRG6rR23SK90ibK(iK^dhj0x~G0bc}WoAe4SbKn7)$ zZbfkLQ()x2L>0<-f(6$U`Q_AoB`7NYT1y0ioT7`vVSolNMAf;!Bh}@%E7dUx)!!1T z-x;bZ?uvhkY=n7ikLu(Vvqv#c^n!DqWP|UeGFI_alGx0122U5>z-PEMV}()a)WkaM`U|G@Tl} z@JT%&s00^T3D~^uMFS+b=;uI&1pUffX3HFsqk@MYW>|L!W3tX*R4MDjZB-905O;Sb zU%y3VI4!~7gZNVT?pk<{s=vDyKBromZSRCv2YHR4T5sQ^y#A4>^)e z#~rVXpIBIP%t6OG?iQNdxKO*dkC~=+5(vKZow}>ZEhM>p=ocrF)?>WsJ%3g2Qq?%5 z#{Q~{m)0D2++sunz9&iUoKDJcHL=qujC*|%z{O}Rt|oRdJ$-@Mr%5kBgE0o*+c<&L zddR@85A@`LZ;lC=08c%f;G4qhAPsHAne}RBg>H%IvkgJYg;=gZB9T4_T24+xl6G0w8D5{!IkOvTos@X-t2jN-I z7KinyxM<%3=7pHZPIP1q;M6@tp_ZIU?1TTO9`5UdpW@mFKP%Th_zBwwKVkdeCu|@5 zgxh2D;Af&EHV=L#CdB5!&qQZz9{fyn#pc1!#O&BS_?hU5&4Zs$=ee&{6_(#`PFFtW!Q7j7I)!BRqW(I9KDC353kZJZnR*?~?IHV|&dy>uVf1&{^3+Bs- z2COUuHY*Fl#o=$jujFcg-b#p_8g&blmBS6GGbxE2Zb&T`kc*7eSpssAk*=nA>Fa>S z7ntC1179>Mha1xJp47Z9BUnM1w#@=Of@K*|AXoGQ#83mKos!N0$+qQD*~| zWkhE5%V40(h)f5wbs3S_oZVBG5t%WBbs3Qv%c67{kr_u?E+aU;fSga%RO(e~0SDpq?H2c!2n$o?qQ?Ya> z&9 z`VY!HpJ3lD*m!I&sXzFLv1KpafD50k>6AJrYSL2FM+Ql*a11c zZvHXF>K~idZoVnRac+Vc%dQVQh`^~hVO#iEiQ?%+(EF7G~FyD z3!HX0bDg?3Fgdvgxeq_ACGLbF%ggQkRZ`+Xro@dWX^97!5}!Rubv(%E_{2#KjTb(m zeD>0RMuc;W2+K}ZomUy1UponLq{Aq|beFw-@ggli zEjMZ`TiWz8(|MQo{8jHPX~9QpD?~tl)oV*w{2){O$4glJU{n0^rA=3{_(~T~GEn|_ zY15A6RAp#iT+(y{?+-EQSC%x@F$&80sBZpJws?oU5r_|Du5jF@LGP*rsw3{-zcq!{}FRjCM zNF0HK-5h%icyWeLrYc>p7z?E@(&n>-PnT82A?hqLVlNRZY%2V=4 z!|Q}ZrV$y0Pl^0n+Fmts&V1mHv6d0+1i9eE;;HYzc^9Utv7*{$s}=Q#c^G_JthfuX zr2eWE_iFaNPgJ-j@K@SylPJ@B3cfyKhPI zlK1lRlBR8%rZglA;cym87VQ3n?Iq z$O~GRze7OBaT$usIBqGfGY%~}D$D=(JNJIy`(BnV2#%w?Ht(H#zkAQU_uO;OJ?Grz zV?bLmK}!PKiV4~h&{j+^C;@H71Pdgft(ag)0@{iRD(m&Ap|)azQEMFn+KLIrEml}t zF~Nicv=tL9wIKbC6%$Nb7a*Xmn4ocAiWL*gSet-NTQR{ZT-51WF~Mo#|I}7YaEACY zwG|Vrmw>inf(;VTR!p!_0@{iR&a`HrP;JEoXGz_(6%(9e@i^j_12I|_LF2Ow_Op>< zSp*Ld)Rsl?E;d(N7Qwr(K{PFkvk(XE7@;^jlGPTm%vkoO#J<~&_4_P?%@*UuXBk|m zVOkc!MFNLZKk$VgLK5*=7QB_ki_fxPuYfcs3f?9l&52OuHLS(w5KEsQe3t)(AMsg+ zCWseM+y13Dg$quDl!|;45-J=fh-~Cn-c~M^FAmtp_)u&kV`$5b=4t}diOVihW7G8; zQsl1$U3Sr00jcUnXRe1pU*Wzhp2ypTAB)~xA9avc_t|QKck&O^0 z#ix^SxC`f1Of;jDXkUe|TkvOiA@MBoBm`CBI|OT_N;eUl%J$i7k+($Mk1Qee8GNVg zFXEw9@g<4j@#``=@t*{cCJ-o{YfUHseIrR!!Kxw{h(riaWP9o&|H}N6SPsmcyNLiv zq&~rbeLae^CKH=F0?@IhyoR`b%se#&1Cfsro=Vt?EMoFn!Zy;{r67`hDdVP9Bd&ZE zzA}3lp3d?j&K+N?!7u2*GI?y;l$*JU6|8$RVsM7e*cq8l<~)6!M7F!e$5PPrpM5!b zA&7OxXC%==H_=0A097Iv{lmnx==+jr&7iJB#jn_qPqAVj`?{Xq;LeqgwZC#7bKJw0 z-C-WWRxuAJY+=q1y}>+~?meg~=7Zaaa)x<$p7(GM#^OYA6W-1Qe8KOePuC;;+Zarm z^zd-W$J#$RLz>*8%mWN0^WbYhR4vouEy5yjUsvsC!8Z}nkN-utnXE41(C!79^;qMrv)5KF8~lq(R%59Mki} zj?GY=wv+l$8EbAd2-X<{6QS&M=%nkR_`g6BFC(G_U)6Q4Fg3IGPr&%BUe2m4Ba3ol z{AVOY9)^Zfdm2M6x)$qdcaT)e4eDtd4Z6!rxzD27Ec-P&0dDx2`ZZnPwZ58Nqn}<6 z8muAmW)7!YxT1^CXXP8Q``b`6Dv0tJ^{RQ?Bstq8VM)z7T$d5o0^<7WVPc%piEaPG?N)1Q(3*Y#X<=(Yp%N)kqwIGU=*Rp;ZE_HpYVk17oUf#v^W& zv|EtOC}{-4sz4EotC*c(V@T1x9Q^GCh;|jT4>O5T%m}-R8DUp3BkU?>ggwQK0Z%bw zz*Ec^@Dwu!JjILwPcdV_Q_QYG4L!xI9RW`SsDiWvi*V#a`{m@zQ6V#d08irF4}48@F%G>REP zS21IAUB!$@pm?Yz#1$y=dYm1}YK#11EPGR8-{Z!PP|O(bDrN#3#f-4g##pA&#st*b zn1EUvV@2YZVHP-s z@OYs*^B*xEMnXks=vf2yi9CY5s)>A39r-%pnT)TC zJWY634CxyqL5NQ^hiT@5G-n~sW|8V_g37r9IMv**1CI1T`l?s`0AL{UTZ~xs>i=Sr zKXqC`Bu+YRQjjui|-sa7D#U#O^*_RWZ{aY)7m6 zQ0?*s%rikybpBSC%?%j*So_z212X3_-vpa5t8fI>LeNy960?jOSXl`Nl}3fyRDyTA3-2jUYvgj|e3o}ym zKOP%N@NalUXKcb=(HVcyZa|9Gs7%prK#Fz)Ecybpto$b=XPFee%@lpQw3)4rKs%`r zcGD@i9ija1m?I@QE*zEPTrY=CAvvl^*`(xfOpf!sGTww7nIK0((k2UFF4jfr41(aF z__$OMeCDX8&vFmJBS0`g4n&sP>_`uR&L9Y`=RhqH1h*IjGd%>5$N)D za>;I!D-)9aDw91&q zVRB8(zVT^Ik=wim{SQ)S(xh2T@PQ(l!ZAbP6&aBd?$f0lu`$#7^_B2Sxld5a``C76 z-}T?RlqbDXUIR@mbBLuVuau9l5z1g%sY`L6E+t|&0K{)*+5)@7AcnaiA8Y^L6R}jk zz#wkd)h{sBUlS<*H8Th0@pHe?HRJrx4}6;*0-eHZf6#3|8yxgE*iDFf%_M5a{-!~D zrp5}ir$yZcJ6^q{!H$b5FmX9ETk<$%5PZ%<(BUD_DOfK-V7U|{iQH$X%J)d!7p(97 zmu}&!JWPj(Nl5g9#W?}|ph@(CrN_`3JxjPxR|TpbWj{V|eca$`@^C%p)#`Z4h2J>_I6>*=UB3~h{XRUAir*701jS9GKCoW;A zXAQ1Zx)pA41>U4IAAI96^&OvMRr` z8cpWYbY5gGi6b+$6+Ct6E4bVsSnwSje#hkTfBagv1tgY_wf|}&kPgx*JQh4==pt=# zpS1@j?qyYu3bqd$Z0CB|28c~4qf-!@ROhH@Us&fLW!z`LwuYVkv^>1tV4Le<`@M(l zY16n>%$_(^WYrxSZa-yEA`aTMlZ) zuy@by39{VihHu(kQA3RPS=he1X58S?%B`Jn*55DXIlUj1 z`&8B%^kW#`m9kE8zbX4YyV({ubjR+>YjdIfyDO-ITAwuaerR{aWQHFwdHZ))JVgF- z!??twKz1WfO0aovmwuc!tO>Hsb_w!Ek05V%iJSQ}@#+kyqAvEG=INU1?MF0@UuzVB zidmd4?=;Wbaen>-EO3QTj5Zt|@%E!40Yj6<4~A)kM6)JRXz|&>?oUP}B{c7nt-g zTQ*xrdFu~#%R2QBTJ{yMWwTxEnv^<&N6NF!(>2vA4Rty-aSSQXGtWuNx3ep1q^0}* zLzi^SB)0ZXOSq)0@d^}Pu94q_k)94>bB6UVAor=#y@Z zbbE9LsB3}pGf9wy?&^QnIcvT8-QgifxCjE}KjP>qmK=vi<=_>HdUzJ+a?B)K$0hv0 zs2tBShcIm1NGiN7sf1-bOF{U<@9Ro^%d6BiC0MeT49^<%t>$AZm|PnND{3lP+_PG> zT3#l*Hl8<=R2jt13r4;MrpDOz-}BKyQ_4)QlwOoly9u_0Jg4xUwuH3)Pl~16O!7%y z@-MJbA|e0NML+GoS*ypH{`KG0jhN+)+H*>QUL?umx@t?yMC^RcG$~!kMtqH#(M@F{ zqD-j0OhnGtbOTqWKS5f3ZM~$tJTUEf*7Ds%^ZF+YCj=3|$J+lGO4YS|H*3k$__`93 zo{N*Z7QMO_D|9V-buCuuTA0upT?<}vhZ-&~>jY(cw@KhU1ZH|6+{$zZYuHUJ|L|>H zC9`V;RZ1n@Ds^kZttu0;+@K3xQ-(b^H)<^#UGPO>TEp5c{ieorsYlZHd6?E{OiT5x zC6XMnpbVXPjnUWBm$Be4+OAl@ihoTakX9FSIgn+9%jAuX*b?bm?C}P58kU z5tLpF8ob7|B271hb-50q=8rJnG6pX)dFSh_$oo9E)&yOE#|C^9h_jHqCFx`E#X5cXxEPV?z&(<_Y zZHqZ0OeYB*H{QmN5fMJt{)Yrt6P_DXwL8$;Ca@w<_jUHsG(K}Zm4%X%c?16l0t5s1 z&w-ai@7KK?C2_y*;Q#2B-fsG{`({+k+yt)g^Y*R>m%F^(!v*;_i0d`y;8GN5Ps8vF zm?J^K++E;7?!mR+vltJ9+=FYskDxj6Q*a01kZi4W)DYnC)ioF=QB(#nx7IqbcL7wa z+Z}8RsvZbtHt_oc=<#4ByDB6*{|aWu(55h#?+VVIjp#u5-w;u74&fkPk#z*W5vGai zOIkxkjR?fTRCZ$LBtWo0@W;@dLM3U$$1|biP52F;#i%lZf$$rkONY`#sKS(_p>o3U z@Q-0)hBAZ`VJ=dHDsIJh3WfF|&eqFQ!Df^csyr7@;?dO>hNduiCQ!)7oCS+!FiRk~hM8*aKuiIn&AwQbpzSh zaDs438XGQQV>5x^<)}-zv<`THFLgihv3=omu6^P1T>HYAT>HWmx_!ZinW1tgam2$_ zbWmy>hDO(+E#b*5Tel@#ZQAlU^Gz8<`a~Snu%y?&{d-glpEv3sjEIfMU$Sm3WYakW zpY!8(E2h%I2cV$S6Cg zOiR^X6D`WLyu~WDl4Rk&&sRs#u z{wZV(sb8}gbJ~Egy$uh8o4-LYciO-`VlW%EF-Ht!>CYT7_%c$ffLe<#NrW$JWg_lT z4X-2^h|t&yUqP66AQOkpYtqB7C8*?@^l;ZyZF+{vYtK;);ya06Q!jPRQD@QsXD z5nhuXeiP&4k&i>>h2O*YM1*&egx`NF;8cXyq-!`G;Wg>u4_poOnLt#9@8j$e;Wg>u zPZCKW@*ER9KsXqPsqjEKm>|w;(!=)(_z-2vr&vEMKZvLYn$I>Pl}3~Gp&9hhJotA+ z!<}B?hXf6;Ne@3V39(pj0QSc4CmukcP-eSAqEiuGlOFy&qZ1KclO8@qI1}MD>ESOB zcXebII5_-8!nKj@#Q7zrsS6Y_>PrBNX>Q{hPzq1I10`0cmi!N%#AkqZ>ilc*AWrpM zT_CZ%;apvKF>(cp$OC*gf*_e5uz5|oTKX@@9BWi9Jd&u9TrABKB$r66Ah~pBfr(X&4Z_rKawZ)0%7D?!g_%)@*H8kKp1(RuwEdH zyg;}v!Sg4PfZSl#nBe)7h$Vr!iF5eGmcYUU&!0qs5?Gqx`IAV21Xd(?{v;BTz^cR# zLHCHlZV@aHCV2iN61Aov(4J`Hlenz>ZAp*lMgJbw~NTh}0P zQ-bGDBIQ;G0yifpJ0cltIui6Gc>W|(Wu1e--UQE|M5b8>k?ghv&!0qQSYJorjs(x2 zMCv8bpWykENP`4En&A19NTUSqOYrPm?@&8fmr|pX9;Q$U+TstuV4k;E+0olEYm{lH$SB*jrhAiU&_)dj;gOVeD-J zE<|tWGa*H9LaK-GR~85lFawtj;}aN@=2@R`kV9iaCWRd3)u@YA{yYk`%cp}*PC3tc z2FsrUTu|PN_)s}Fc}FvA(I;qpprQy}jbD2W`m(T!{i;@>0g0k}&m%`1#b7SFpU49d zZpthAB%^IjhLr$?IE8^Ek8T#%*lQ4_FP2YnA6TN6T%6)Qu!J0WNCi;wgly(aaUWPh zjy%}AAec+aI4#&8Lj6i6TtM)3z)%`zo$MdIj+Etn*p<%!OsHgg8HgC6o|D}40OCP& zAW2@k4{$K@AmQr>7ewBJ=`DFZ;ZWo^gf|loPoRF6+(I-;1&SCq4X`vQ3~8FY_X3vi z4=nj!UBXw1RbWcfypf<8<$&bIC`DU@CPka|fov?}oS^@7MaTAj^ZGS@`)j{%? zPFlZtZ6MW2I2pNs>AMK00N%w@pU< z2ob^-Sie20KXnc$rQPG=$S60nNk-`@(%@t-s8yGgS6?-+ZVfN93|k`VEq5yL*I z(YpxVF5t(R;62|*wt)HyqU&(Tnd9*X#BmD=5{NuS_`R%lB4A&Hn6k_p@hz|AEt8`* z@>5bOk}hFZyr0kP zlcS=ZF6G8%piMnOwCweCx(1+T;B-0b8;sBpNoR^V%|*zl=?Wd90hYxpyKYEyAf zSMEVfn9}-3`>!;756ehbZ=#mLM^0AD~rF5s6d3TP^lEIQ4zjErBV*8#Up%$N@Xc~EfL`> zR4S8%Q;}mpP?;i}iR@}E`ys+GNys+x5B+}^Pg;n*ughh@QRyB}r z`gmbgBct{4!m1_`QXem@nn_q6FRYryqV(~?s@cq23l^jLWb*=qsyV!+1MgJ9xBXF6 ze`56W#3`>PnOMU9jqueZ6H7Ih^VK91lZ1m2zM5oWiu9#gPLih%kuz^QA3SL!>g1vc zg=nexA8>y#I4Cn+jt!l)8d>5b4tvL1f%>M4r zVTi%*oBDnXck8y_0|C7MY#F(kd&#UVEMf3@UBa)t629Y=API6MY~hn!3ET2YFh@XG z0wqB8H(BiYEaCZQbqSx-KWM{iz@SsQSOrOdMfoXTXPwXI1Jt<&cDQ-6sup(mg+v3- zS*_UNOLb`d)DJSxrLU7b?I@QLC!{#J%cAVS*DryHTYZK#&0M z=EYq+bHNPS;JpTOAMY!@3YrW*3s8N29^VTzUjUzsdtYf8@dYW^>}HzrDoDX*FC-iZ zQn1;J2uFhyZ1!Tpu^*_E|u)0Lax`R-llgKHN7IF@+TM;eNKTkfJ_(fR!tx zs1M&Q2`K8r2PFYTefVA`aKvMvE_**v1nDtQD+%JRCS+7s5LU3oI`JzW1NB;hj(7}I z7f-1N=`m0{i8m0W$3Wdcq6UMdkT2>+#;YJb2I@_Wj|b^7Q14-U;sm#t_M<515=!0o zDi%bKf%+to1cLM!s0XB=K(SH-G=&oM7^r&%q{l#giuFVHipKzGK6{ggChJ2p=%IO# z8{iW37^sH?4Lt_x5gr=}IN~u-pE!m<3F{LmAvzVL$3T6a(TN~E2I>&uOpqP}^#$Ut z4$@NRNT~64TTLVp259GaV`(gUAH(U~ye!2@ho?=rM?#{|V3{L1RC1fyC0- zk6g$u48%TL9g*XayTs7u2_!QiiMuQcH+VVEUW1mJpr9>N&Dv z5L263H?A1Oq6d&B5afzMEOrlIT*mPeRQk#IGrvZM1-VT+{#zCn2+|7@|0Bnl3UXqP zKT9|f$e=LlzlynZYGJmKo#chLLs7YNst(hCv~SPV3l(hCx|Brvy>UXZvgfrX{? zg2aOoSXxRiNW4G-D@y4FiH9Vxs`Q7bT3lI;D0odNy&&G6uRblQ8U|dz)$Edq)CVBgp&OJ; zB5VbzoRmx^Y!~pAefwf`weieDw)L$K^kNwvqf(~Wr;7MSfPlz2H*DG=(y6zX-Mg8#n+nBbEs-a zuF|<$+t~+frE{r`s9+7sEuG6GiQuzf$kMq-0aphf07**cPC`swP+s9TcQxR~AYa^w z^vF9mxSvJMJst52gYw$Gxt9W78oWZ{sj;jGK8Wwqxg_l>t@9_NUqk_p=={kN78az= zpDbm40zvBh$t2-mkUD=d#j;@8hKZ>9d8Ci1Ad0ErE&-m=uVjKsLU^*7B-nvYEv;cv z`#v_cb~YYH6s=szwT!v=g~$m^^<{KT>1jIE42h<+E~J5B-^Pdu`ewCM5eIO=#`S?z zv20Q(*tiY%g=$8d4a%fsCwd~t+pkhG+Ec=SsboK@|DNDG!E~wAkAUP;(j%!d_Q?O} z;m2qhl)H8Kzuj;%Tth9$n0^CdoL;cSZDoo3QD?zXR+8)0GAUp8YFSCHSIdOZx>w6e za=ltslIvBZ2O)K@mX+jswX7u9t7Rp*UM(w;UJc%lN|hzahpjTdm8Hn0Yl5ePdSzvz z&j##Yq4{NLGFTZMi|HEsQPe-8I2H@(SS+swM~#H*2+ zJsB}UdNndJ%v3iRT7Wy^^CO)_tL-njC#NgI7bD(k3 zwTwK>j-9H28lP_c13PO8My7sQ%3+d;t8)5fDTm2%0s)WDP^o*vp29jTYZ#x|5GPD4>TeJMHHD#sB<+c zBh;}1lLEv#gGqN-ngaKMx%t7{1R)qSA!cYoJi1F0VumKfpHa|- zd=f$CzEcOkyGwUNpALS1*VMHkjdhZXjPJ9u4w6>5H)ePBo~a1lOBqj-xB7Lg=>0nP z4|Y{YiTjhn-o3xtRsACdAJD;LyHK@=V$w-hFus~dere3yy{tGs*8V04g(=wXS+kTf zt9M0pnnlR0LRZD4e`a10euqrnGj&$v-HN=rM=K~4$t%Lj6ErKg2WqQ{EKWMR2KIU{ zx6T>Q%USH^4E!5Nx7-M*x7-lq9S`5buY1`p;nA1v?quvm_zGsw;($XdHdwKlpx$ruc7h90 zgW!by1i36<@FXjvC?P{N_CnAb?@B~Wgc34bDrtp* zCm*BNqwvNaAX71VJqq>f$GA_T@ckQ+CKcm82@R)X+$T}^fnT90Y~@mg z_uayR==CVnual3_>rrT4Ctsop2R@7hrSy6f-b)@YrPrhIQ>-8JfA;@*`Sp9`b$;_6 zdE|eP6)&Z`qwpcgPj^S*BgBf=rvq(c;U`{&u1T^Yfh5tX7~LI(pJ#L;Mt4WyA;Os$ z-5rJcJ@PTSI|}uC?jhqlLy5t@ua86z(l9x(*GKAy{1eEu;>_=+`Jt=x(K7qgcN{K1RPraVg^yG5R%% z^$X-<^lKFB7s$ux*C;Myt*c`6YZQwlsgBXFQCz{6)Wzu6D6V9MR>bJnD4xLdHwEMc z^2L*WfCtf^fHF@ep7||0IYyU7;ZE{jA+ z0;^JVStOM8DipRRMVCb)YBeL!o}$Yl5w}?3Z7I4e5(x=(r0B9plv@9UCp%MgStQJj z;VEw1NSG^kQrx(a$XMqCTThBEi$s-m1p<3hbXg>(S)T-g+fsB{BxYFbv^!FCStRNu z(4V5qBGDj$kEXuCK%)fiOFhZJOzU)%@KA~_i^MFc+o2R)7Ku65l_atfk?p`KE8=VIFKz64rHu_fW%(s z#wG)4x-1l37Kvty@roNa5(_mW@$D5^qS78T;Ms1TP$g?3pucQ{CM*7uMpDi?vL z>Ng;Lj4q2*!&5+j{YuLLH!@nq=(0#PkC<$ocYq)uC7Kzb%OZ9gBcfXozAZDO0WA|!X6m($LsDkybEM4F=SZ2U&yg}ypCe_a zK1a$-eU6lw`Wz`U^*K^z>T{&b)C(zN^b=$n+4-$9Uu2rd8*5^xqsp0?qVEKpn?a1s zEN-~08lchfYN~Y+=ZD5bpZGgQwv&!?;&_73)u1~+*8cCHrIX}+rtPdD&B;mfO2l?j z+JWskS#02InVpw(PyQ*fUB`ShMJIEUjCK8gNbsY(t7R#8GnGl$)|2IOzAe-^xl9Rq zld$@Zu!+|&<3gf6J*I0F_iD8U<3rbKp{~^(rdA7et!~>r`2ef2Sl8+vQ>!JqR`;1& zou_N{(C*3KW8w=;tpXF@&R{L`K5s0lGXe8s?dP_1U34v32Zo()@oB`(6Btvz!rW=* zcI~nCl9#!4&U9YR3O6UFIIw$QCd_kV*zE!h{tbWcDby7BrJ=wVdr{V?J;%qpde2^p zIylp~;%xR5yC$4jebh^i9e8e*90{J})q9(f)V<;5c7W~;FNED2UI@E4ybyM8cp>cF z@WOz1!wUo64KEBVlncaPimUfnVef_)2D}?y-iUyA!^;H-csIPzO7?De;VwV#h8Nyp z=iTsfE0TFPyr7$MH@q<5-SEPIcf$(#?dm<&>BLv>xmW33 zgw$cN`Afe-u@D(KAgul0!km))!fAX+5Z8w8O14$!g8#ZJwSFz$7hs+~x-0pPn%vVv zyOMWja>0joC2yFR3*NV@?DH%(_8r0en_Xq+E=Dl^djzpLr0iADEv&*Kj9$C<@-#Mt z6mjL(>HV)=5M~794}nE~4nS^TiNRzbL%)?4%ZrLafBYEoYH<^KmarB#q2~x|aT9u;uogF=7YJ){ z6AD-iXmJy=B%sAj$d-T>H=&>e^o3HP0tx5~r9vSI=nJKwK7R={)E7#HqSg=s`a-Et z++u~bxCtdBpv6t7R4(1r;wEIw4tZZe$bZvkC}Vvc*tEC_RayUmfEG8QY4Xw`Ep9?H z#E8)sN`>krpv6t7K>}Lbgc>EF#Z73YYNf;?|&6Ij8irH;q zCi0x#H(ah1rnS1 z4Jl9@X_E+B5n3Rz$%O3`Es$6>VJAWhBsPU`FhUC?R`X9lQy{x(V^hD6_(BL+#McfW z-dG^9^xv~wu|Q(8m_c^2#%4bNko`z}A;k)zr}15O9R!u-dB2Izp>ywj8BNavEcofK#jjq!`k0i@PUaypTSO(g8Lq1LGM5V z3Vi;?0^@HiR0RWc5*E?lSRnq!BKjK(KE?V$X_Z}8K=aw>JTyMHV}Wry0?mU}7*<7e zI~IuBv50QRf=B2gH*Uv*PrLz1idmmPG0|zaW5MSct=*0VhX`x8V}Z}@Sm1Lz7JP|m z>ad0YJZ}MLI<&AZwB!>A7SY!jI=>DD6wyr>x^gAAt#XT%2?F6#lTeURZaPjAFG9GCYClZ_+-<@T94DP}+xbt&;a5KH~h$*ssZNQqVlN43YPzfeD|p zv(5cl_rOxk)c?a#cl-!o~`a{I&g*dy3*oO(er zvLNW8sY$-jD!g8d!Eb%GOw;5F4=YtlO_OhFtgBK(B*wSM23Y6J+{)_z87+=TfZWyf z`m|2FRM+d%x?T%2Z)UwdqwBRs*YY7#%M3l+*29JpnIE%=tPZWLs5I5O%oN2IJfa`2 z0w=tkiSHpvA2fB!al&%1PWKpE@fyK{rc_+u$h;q7-djiI-RtH3kT35?yu6E_zY`s78Cv?p)rZ)PB7g@OkA6=&N4lcqQr1R ztB9#ymw}7M-oQsm2HhF>SF8{|xDrILh(sZW3l({bni(49yji`h;k zX8?ycuLmc88DN+e*SGN}Vmus(+*DBTa|ENjmcAfN5Q!G!>-YGRM8yGz*U}d#W{b)7 z?4c=h(BIJ^M2Dt-7SVwyuV)X{v7Z)3c|CjRbRt+9aCkj?XvRXM$J<&VmGLKNA@q4Y zdstA#c|Ci$hS}r1o;^JER)G07T=-*%dbgXsI1t(mxbVH~uMndnPW5HF1B!+j`F97A z{t50l$A{g^kF}rc*~Rac1O%b{iSyn1JI!M&OJpC<8fJ!UED_$lj%y8&Vx<{#hjx=7 z!>ET0*sL=`iWSJM`~`}6iymbW%Lr~VbznMvto{GMItb=vd39KpSBDl|hxXDB83bqQ z{8H*`b<*om(lW52HTzCH{CznP7xcgok75o%rHlrQeR|AMQoEh zxY+yrSo@2Yu)#&9l;VfIq`2Lx+^$_!4cx0)-2P6ezNdu?IneTyqd@zV-)k!T&0V!xEs zzy#}JU?{#(;B=ul>TpIq+KqM~K^~qn>vd1$mk#b_?B zbh&s!j*DG>^;d~>p5*TmuM=54Tqfi;hY73w2}f`au0(Jf%A_@hAu+HRoa%BQdD@H( z#!vJ31l-^iJx)jG`gUAFtL2i2C$d9W_qUoO12vK_r6`t+v>rz+xxG}Rd#TvpOB6&t zp;qE2D&%wDda{WCq zUtCSn;>zt)^h|Sw^s2uMMojTK1!BP0DK-9hU-zSX{ZDj`e^?A6)cWJy9P%Vjn0aN0 zC}VY&C1*?Brh6RcRR!6Ztj_S85pkz`2}g^SGxAyUOcdZ_!LxGBXX7EyjO5Da$ecv; z6(CK?lW2KO87a^5$Ao{DXSS1_g2&<@QMrtJ znjcLbQ{eI)cSy4WbsoR@$`igiJ@+JU=wR;7&8-@>853vvpZM~y?q_+}JieAvW_Wpg zd~LLfdjGS$Ml|FPsYX9?U%{Be$9e+vn9@Nm-!PnIG>p-;z}1B;8{0#2)yb>Om;=cb zrYFz}j4tb+Eb_<17`p7srWK4F!bx`sr`#c2<{xrt{}cn=z@5$D@pPw{u{4AHQB9pz z<&vr=g=>-25yV+GM##H`B@<7_< zfpV7zMk;@PE~xZ#0dCIFnnl%UePN=Jd!80B$s4HNOe@25vOnG(+VUi)4f-UP>04JD zG@>!b1b*ZqQVkRMM5-BHWS;R@Atzl&G8HW!qtuCX&6iWB=bq+lpwSZNOqUg@8~9|@ zUyYzSE(iMgX&m!oG(T0iY)TIF>BYD_)9nvEzgFcU*g+F>GJTXeI4QsLa-8UOy3AnJ z9*6pRQl5|tece~%cI!yV2|b53FPRYr!(Uk&s4r=X;tSzy?>eGPw$ zD}2(UnT4WETr49+nZF}O5Ed>N7diRH$5#wixm`OZm0!H!m_Ip=)CF8WK+N?6#BkUx!tazi+5K={>_HiaXudoQZpJ!9CpBYW}BHxNe; zx#KyQ{hr_|uRliXS2!u;?_v%CvO!->Apn)!?IU*{H0g{6&XjrX z8F!=_EAzA*e`!y%XY|&2H6G1DI1=FJpqvrwOKJ)@)3nBneb+%_g19)`FDPK6YP>o1 z!JvU(X5^EToQPlH%$#?{UHb64*2j#7&~U)`nbDO9hN~vI+?Jard?<{)AQOe_I~jAD zFlEuN?9=b3de!o=k-=G;&qm^&;nI!vNRO!~oPvDH2_#oGK_Iyc3&*KdB)8p8znO}9 zbULb8d44RHtxUb#bppeIbvf>(B%&wFH!X~*P6-2zP^SLW`QvX>Egwrzm~L{FAJa{) z^79gD8GqyC_Kmp_fd zp1}X#+3{jrE@&+sQ*qb&!RA=k6IJATqKaKll)DQ6nY2S}^v)Ohs<`9Dw41n3d4tnv zw@Ge=A!nSzEk#$7Z%sjS2c&RrH|3Z@!F1ka(|M-DU4Nz9|6aF`W)=D?J;z6Gds9BI z`KNlr2nO|d>jcya+^sE!g?x)vocYhl=cwG8zfW~E?0lA~jX{K^{xKXPEHQ7P-zNjd zVM~`$UUB1%vrm+~q4oZe(#qFKBczq-q>=kqT%|I%+Ui4L`gy!5Y@F`Pxh_t1A6>p< z?8M6<`2wcUqtPpp#XI&9>o)|X=Y3P&yS>4m8@`pmcMq&&Y1Gbr1T6x*V$hj8t*OoC&%@&IGys%3@3~$2%hhS)Pb0e7=E+tZ9`SFh+RhSxKHGB3I|}T3%Ii`)GYN zM8V^5VNPVZM@F!G6ZA{90=)uS_|%N z%hL4Q?n9OI$R6avu3&EIp$Dxv+9xk15&h1auLj1Id`L__obL52; z>TV$_a?R0V*Bo_^fnhwb8%o@Y;@pKhE07RopM^G5eWcJ4Wi(WeyFE#?7M$JEwkMRj zO3e*>E$^%wHd$&eUY0~GD^r#0N@#&2w~I{5J!Rs_ns3I`?oEHYdnru^k33nE-@&fl zVG^HMx6EhnS9W1wERS={FGpyt3gr9>K8a)c%=IgnZgBkyCP;Z59*N~Ro*W$49E?p*xn1OA4_MP=8L<9A@1EWSb;NO` z$F#ef&alhWn`_`RF#Lh42o2k61bF8v;6yUwvjB`L)7Tb6u_55I^Tw7%ky* zDtP|0aWtuuWN6aHwR%SPk)P-zPp{_l{pgLzBMDw~9D*0;6FiYmR-eP4#4B})H&XK) zrvMP>as1hV|3^|;e+0u=_%ML~4V^o-H*DIn?)uL48ya@bJ^SjjXV18P)0WPiGupOv zHe9o*V@IH&ee3284coSFy>`R8j)wEkzk0=GmtJ)Kl9g9qcJYda%eSv<;P0Ys+wrqx z>*n(|Y}~YE1Fl%TVcUis_3bQVN5}e2TRLXoZ%bZ8XD;RvR2T&}&`0^#2*CQP+ z$QTv7j!UQwf~#8J>7{QR<1gPnBV_Dx+I zw!bXsNA|&bDXKvR`3V}n~ZHQ4Ct4coV0ziCH@PDPGixqaaAG2?mC1}J-4#UwsdURzELOgMK9M_d@+l*ZCk$fh7H@nj2&CoZM|NjVHuZ$%xf7& zA-S+0al|75?$KwGrI6KYIZc@?2#iR-q+|Q_7q8uxUz&+LzYF4?HDnJ13CuMjU6z*| zktX?hYdh9ne#4e^I_2ftHmpN+F;)0*$2ErK8`{>cyFt+F#JQ=_H;=UAjeq&fBJ*$O z7SxDSD*B>rL&w%_9anS2Ap$+Ne$#f;S;IRvwQUi4vD3D$yKe3J^=t)FF|?uMYBGU8 zLc^HGXIy{%*|QOXvq~ogTpS31d%@T2SOhkatO;Lg;n;YfOYe*lU{Xr z-(7p1h<%}T?C`#RC!*#_;6A5VJ^djkVb@ugIC1-YOWks%JSa^iOe z?4aEm`e|tAieC&byma^%!_CW&JcURrq*jFvyTJEc;5*GN_Ovql^rSrv|I>s|OD%kO zxU(~Bx0I=d)jHu5p?&tOWS0c)1Uxn6bapt!cCB?p;%*D=%l7Y6J@$;G`kd-lt@bsk ztUWzx*CdbFE%-_G*|jJjHHfVC^m6^Jj`cA&tNYZ=!`ZA;c2U;*47LxdDeY>ON~x?G zYEf6V9NzcF)~1_>cdBGtPnT+I&vvO}s;52M*G(+*fu&nj4?puE)utYkTB$ojs=sqs z?bM+sLb|dNjVLEn&j&&>H7}%wdWTilPG{qtb^&ydU!Z^N0AGgpGU+3yr~`~WF`r-x z^UvKrRrjTp`Vd*vc6|E8pJ^6*S(-tKOW(t2QnFOCRnoe`s=UZ zG$=E?H%mkMx^pikJ$J4JXy#hX;^WS>NX2J4<0}{8st1T!2ll;s9j3Lbx2)~j)V8)` z(^g}sok%@E<`L=vVn(V5?t~8M550igHDd0kbzr7-Byf|DF|FgNsS)Pw(ep4f>&bcK zJZvWS{COCWqvv5njyVsTnLK|UM&fbiVNBb3N}J5Xoa|~2o5^mv)uIN5Igb?1%N|j! zszH3&emx2mBowR*l&Sl_c}7@=0Ry1f;l?C(X6|1^|U{R77qw5Tb#YcJc-yYGlP zpkCu_Tjiu4W{he;mMK32c=Hjvu5$E$OsI91y{gW4phE#d6_9euU zJLl!>OJH{AJfQx+VqcD)u|TJM;TyI;*s@DrujQY}P+cY+g_2 zRfiFAVD+AM{M@yAb-#T^*=qZ=WE+C542%P()dK!|Owx7PXQcc3=g(|e-P*V0=_5|& zqQhAlQgx}rDwUPF@!Fvw`_<*mEq$|FvZ}XPe+>^0cdu@0!Ot`JIZUWo%^Pm%YWU!H zhx=9AwHNp7v8Sdlw9hHGPfz`fzumCi4h(aK6-%mRcvi0y+vpTOaprdxwe+!VEqzTb zea$VcjV-OVgE{ja@z~z_@>xiKf@A(vRa1=Tm(*iB+FbbSF~$6I<|`J`ao2}Vl?}(V zkaDxo=C#|dZeP1){q-CET(jAZj_sZ6;Q4~1bO#)CFX6Q2!`$V1-Cmxl?qq$Y$1|=l zRgvxgmrW?ol{wyoR5xrUq*?GKs-#N60XLxf)F!oYxMdI$en<^v_dS_yRaf5pR1c;s z_~uq6?X#0T>dK>s;d^Vo`3PdqNw%n~ZXRyK6lI@L4&Pgk-H_bZsJhfQe@XG*)S@t_ zsNtp-Oh)*sNj4p}7bKhAWcC?Fzie&tLZ|12&SZ$lrzUfV?b8_Bf&v$ge59UbnJA%$J{~a&$i2bXZM6E%P`?c;->jM?&|YE_MgLf~)uyYT-Aq%g-6*{Ar>0 z*R6{!Earw-Guwu~@&ZPU9a#VJ=_`M29$o)L|7S3cX&SyPE?u8z`W1cU<=0mhZQs83 zhLy6Q`e%3Mj%{aS_8#r1C3m~7SV#t+MGvFf)lN1;6wo&`1o@CE%>Pxo=)qwp(s9N>=MlJ=dwSaU^{8Ga0cUg1Evo;0*y9Krnyal{eNLf$hIRai=*Sc= zMMQ*1YwR;BuwHznrCOit>$^(a+@Az5+kt9u)hmmd`P;tHw6YR+_`Amrj;A8 z8|5!(rESdZH>WPPjc|k*J+YiVuF$3UIuR^P(vA;j-+)(et?#wn(HFmHsB%#qyEm&_01=E{0O{stIgk4gU!q~$S=x4>w~jzc49vzqz2D!>C3{~wrBvld3)9= zy3@gi(ySA`)9J?Vhfi?m4WJVqXXTv5l?S<{>qu34e|J zZGk0d{)?mWEnoyYQ1yz`8nwCgZ%1nB&0nubtg&~pVQ5fd{WxPJR*iL>b@VY;-mz}p zxbJXwSY7FKL5LJSyr88GhCei%fkQF~56K|B{*^)aw>t=5Zqw0hqBm z|AwSJYpj%WQugemJtt|;#CHm7e7^rFOcnF(*^&Z@a{p6$ooB@NQT-WKo1BJ=L_2(1 zw8K?s>HitWQXsH-Ee>TI&!os7t!Sdh>KGEE9JMC3JCu=p-MCwe-9d&#%*LZa9A$Y& zh49R%4R}ON;2WnKPAaqX!q`T53ha%c_PzsySl3lUgMD|wV|oi5r)sD*JJ^?P?du0b ze}ecJJ$2O(| zCzp!Z)Z_ft?V2eOU-d<(ueKggkG)>iWcw9RJ6(5Tzp;A!bqd?IYElQY{a3Z(OCELd zQ4YcD1YE%H{j4sH@RBHo@fxG4h zpxY@$16><}+mmgB0}Xux*#mI?IMF9SJUmscj8{|41K4QLj21-T$>R>aT_-X$L+BF@I{K z{sgBJPh$76PI8L6bK^6FRKjHqRsJ3pG`BXckveU>lXauKco(=mCvh!#^X zR^b4*xN;A;%>fS4LdKDRNadgYp*65E=CCAWq1!b78AV^T(Gh$xW9SGXQX_Ws)dB>Z zS6eFC**!R@E^Wd=vwj&=9ih&<2D=4RrTDScJbVZ3`K6&tTHevHsCK>+ugAD)!N1!v zmC~#0a8NsTT?u}y&^@8sTW4Z_&8-qrkKzo&@bilYvwQNw@C{EnhIE~s{Rhn>yQVaB zR1Npwh+Z3ZZge?2?dg_NxDi@J=Yi}kzU((GKH8-^hwbU9R@7#wvwNVmN$=+92(@+f zwK~!IVQJWPv$FVwC%N8hsg8)%51&kf-z*J|)@%6;+8mI{C6q^+Ii;bNF6@S7UG!wd z4IG%PaJHj&sH@e9)Mq=pjt;gu4fWYQ*`7U}Ez6I>pM13QD4LL*rKYIHqs|R*WOr6O zWviAuvHGFx;Lri?{lMxP3E0>BhPvf>K_^n(+H@3T?%6YN@M!MQ@B!#k@0titxj5^s zkfG`$s;Nh{b~-!N&6}JXtDVF~QVHJfsmY!rYIUbR@W{mIF4YIucc*%Pl@s4M-$|)e z_O#OBY(LXx2agW*4-a&9cJ>VScdAEpgH0i-)qUV}s1B!udsw_0c#k^qXzMDcWS*0# zMgpGUw8Idq?}HX#2R??8@QR52%ekpw49O#UX`aGL|gY!CsVJ6JO3rCWUrPVyad@*IIXr?)#qqmdI zL=(rmR_1sU{7azxcxOLPJk{MdFw}K)wYVVvS>)MgUXf>iQ8%x63^htY%44ok zPxX$ZQ&K5i5vgS%bkP3`3TAFpahyb6W5!7wduyO=z*tMR&OVyel17AySevfI*j*=* zDcPx7+MuGja_$gxpn+rRkQR5;#$5TNt!gETfVv2=L7Vzi_kc=5HbJ4%dK@!CkBf{5 z7u6rhsc{F!(OWNW+10QRdTSwcK3$wBa$^YSWu+mL`0Sp}J+1O3LwS-6f4Z z@=7>!FYj2pId?}(-WdLy&_P@wGq%7Qy$2KHc{JI)Q|rU8)#JV5=&-8AJlBiUa8BL4 zo`Y)s0EQ%PDCtuN;3Dll(uytht*uRmk7^a69~SG2*>3j|s0ecH(kuQE?=H5JU4J?O z>CKvwdv4Xcsz?v9QFkMOZ(LS zHapbMnG`c}zc=eXGN^8BJ21u+==yo4&UfePp*`7bOP(*H<&3(vE<_48*FQmr#4OKG z()FZ%Xk17kEXFjchR&|GP8cgGob^q1wd|TTwJDpOi5VW}kTAbvJKWJdod>j^$gYDk zNE{A_A#SpJ^8E~*&(L8~idJdjxPA-RQa2)cM?Ks|&ZcUo7G926{n4I*fx~;?L&s_3 zZ1jaj3>TgZsE;IiB|P@c99G4*Jkh@5qKnmhFhj;@Gb)mWEvvQk!vo6pblh zf3X;}9XCD#E>Ik=3fH>`4x;*b4z}!&>H;aMozy&+0)wjUO1-Ryc7cnW$kWb^9rl@(ZF`3M;H;Wz*H^Y(IUu$* zoPBV}VF#!<-q>C#P}IIbwO0bJ3y-WxV;Wfwn=IhOJR|w==nO^m>gi#_Fxfq7O7|Y9 zyM65!cglq;OwXg`PO?K~J8w|`&bIWxI0PeNNW%b!=A1(F!1S>A?V1WV!9Y(g0o;In zeX0g?a8t5t^&D!#s!g`!S|J+!pj?H;?%U>YMM~dB?kNaGc2+hKz5rM#%M`fH(5jN^%kIT8WOyy95Li zJ{CO2UMoTJ5t}m*Gjel=yHw=_6K*GX}ies1WH%WVGQEcsx#Yt5DuWDM=`Sf^5&o#;xg#aQA~2`h>ZQt?xAOf zo?)_VPY>pv&i=!2r!Q|)eOS3{Q5UzV&i8E{grII|R5M$gjW;_JR!xMn4`U(S4$KFsUK#6o_gJ6mJp~viBd+{Ap@ed` z>>bZF`XZ|_##qnSG5rHR|B3MUXnW8%RxphJ_C&!6NBzn-n^9k7sRmb%z^OP4HCgf- z=;Vqc2DAGNf`INW6Fp2-q)k*2Xs6Jq++^b|B?50-*U_%-)lO+W?icOtYU_f8@y+EL zS61(&(Ce!YEzCM!4Ad*A&-Y>xMl6)oNfMo4soQ+H_A>H&%1i6r6kM-U*%j zuwILOIF#*%_0iq!{7_d7$9o!7YCyFNb*p{-S|@o163Pw?f$v^YIrYlE3f$n2owZ}$ z6My2PG-F+j_=;=IbAgB`9rN}`5fu^p1GgBNQDG^pl&hc1$lDldy8)I;|3S5&ZKqKM z_GF#%dUaIw8ArJ6bF-JzZVs-39~{O$7wKT=V&}lUf<_N{Eat1ZPGlZOC`^O4ZpCd5 z80$x!SGn5|LK5p)L1uG;j%C`eqsTl24J3!RulHR*nr&12ME;C)DQtunLbc$3_Cq?4 zuJ1y(zFD(PPK{_sHf#1lbi=11F7<`tFg)w!QczAfNxvvFVr+}Vo$q~R9)JIpPkD!W zF=|)3HmF|mO9Mx1GB2}&LS@B&jgUwX*V2H*&$l#k5w4}7W4uK(*GNG0N!*BwR6Y|2 zTd&Lp({T+IWEf$nASTaH0mqJEcbGj|D8VhySRuZcF{}_g9Z8=PSRtqmt&oy;8rf27 z9UT}r*q7}&EdSM%C$l|+-8}x4CP;MijW$kKxpDcCmyJqINd=61U_bJK41hwL7> z{g5Ji>u&fyYAs1Lpq+RRhYpz}l5-H|&Mil|v#3{Hd)2n)-Rg^6P+V{j&Zk>+K6`p4 zt~I#i{d|TP`7gW6#1W@{B86WRy4IeWK{K!z(TCk)N06+udk_4j+{Qq`s)pJ;UuS0* z{C=JN>L6(F3>2ybSzZFwZ(o+|=|Xa1x3TBKV0MZg-P1ao8_xRoWN$gFMJ6Qfpc+1^ zez;`tyY}=l?mP4OVGe4|&+kxb>gmefVxN=hysC3`XOp1TQv2JBAp5&(;9T7^co(WW z4OhfhE>cqtb{)v#9OE#keha*ltwth09l~`%Q*cw9f1S6R2bljqxsc>(z3Y^MDUP6;7%?jF?8G&!zB#$l8+_dm4M7 zPxmxBH_oeT%Jv+@aBNQ63(DZ_zcPCi|KV4V|FhIo~OTDbLjD= zhm)Vee6!-%)8~ttiH|?QzDVo(WN%OUGj4F^9O1uLV`|}uA4xZvTRD9We!@(jN$h^^>V^>LK9=nkZM>_ihmLtz zyj@+YIJ~%rNNeihaWq-^M)Jr#;==Ez8!c6%6ZW? zEvtW0uVx@CzNi5-_E;QCl@(f=H|)F!6%H@=*}Q2h-w+3~_%}hFvOY(mxaZ?QTn4=t z{~$cRCkF+y>wi9=yT0-XUc(P72KyOq@9n~N?0pA&d$EQl>!Ex{OSk%|p84gCDR+kY z4h*QaJ}4a7z5`G=hIcgKjhlOqvcilJjP1cv7~-7?TctT#xh@@}KXL1*VhPE2jg z&TqVD_Y_{8wv1%-5CS<7Ft4h_B@91T1-U)go50e4kJ`_@*xKLYQ z&nc6id1?Mox)j)_35?Mzp;}3R1@IN>qUJ@-&h%<^i|WvF=!uY;ibPgOup7*d;%;pR zM_lD+9`id)?_g_!bDg?qkyDBewp&p-#Nr?$zU?PMPLWqRTYa8!x(c>kTjsRk9LfZg z?7Fk>9RSI1$I3X~IOW8un|eB%@qeICR+;vL@&12vZvrP*RppPrbcd!vWZy*804|`C zJs~JdlFrtU&2$F{IzFnas=JHSMpg9|M@5LrI5Gm_Z*V2zxS)XOjEWEymyyL~aC8Kh z`H9HphDgxCW#sog=X}rGsyZUe=l?HAzpC#$@7#OOJ@?#m&%N*7uHa>8U{705_w?JC zCueZljn^}E3ewtKbp(s@bYCzWxVPKabiL1n+}+N=%(uNv8-_UHttscY+0<+%uz{x| zyMo8tCOc!h#BY*Dv2|{x4t7i$M-3&tO1}%rzLk^tVx4CTA!ZVnEONrWdMl07D`wmX z{oAXjYoSIEFA-(b*x??sHCT_>mtHk3d-u-jIk^L^bkMt_eMN$=(ki!}UU{#zR~H;7 zIX@HBI3eMt)5phlT#C+mMAl4oy%c|D^qki7e@E`TvUe@U{D;UgOS$tt-sw6HhZP*O zqw6%;wtC)ey3KeY0D4ik>N%?e03|z#d~NZKg~9bZhI8*YEb|8uYu@kV;dN{C4Z(-2b}kr3cE> z*Ytd{Yx%)4vNjIKk%I zr!RQqKKi_pTu)E$T76JkV7KmaE%+YSpxcyKoCs=1@5yKD*K6?l;vrkQPSi~suvF^g z-cxWOh~5(Uc7MOea`F8ht~Z?B(>n*XrWD`rxwF^0WR;6nlbQhewx@jCOQf(@&t*Mo z6!yZYk-hpKyo5{V^p19)EwdOR`|jiJrFQgexk+U$yKqn5G_Lnivy$T8J;Kw>SGPR5 zhy2-7UTWx-a_;p=vWUCxV-azuODjSPdtX<-6c(>p_ydtTFXZtt86FEwR=7;UAfs-EeqWT;CVCyT|kdaeb}-iaG~$8PMM zG+k`??9~?4L$xz-we|%ry}-@8 zP_s{54A@FR9~2?G9IojsoCN7nPKv^ex4NG#Igv^fk$G$=8YD{NH9fQuOqSv}W{-oDCPe>qJ%|Aho}HbR8q| z>k;kN<}y<%z$+J$H?s%HOXl|KQPbO-l)V1f)2gBOG_NYx?X-@&&iKqruigHI&{v7JdPd1CNq?k%VN_48o+2qrGP0z^geo2{0*?VBmh!l`NyN<)}SkT?FFnM>ZN>ZWlS&tTl z?ZVTzbW6VX(2}ZZss#4Fpl2ja`?9}*cFx~GyW2dRd*60sPFn5`ZZyHCzE9lY5-P^ADd)sX9A~;uF!O{5pw7Hp2V0*pYl5_|mbso`a zOooSnw?{WK(V+IRkHnS`P%@`e!aLEq;*f?$DD^;XJ8E2gP=uf#(=Wjh5^cG!x$eBB z^;6F8yKl$Iy|4b_o%4Rbz4vtc(>r&v_s;Phm~KQ>bc^NcwqZbb*K(=7?yhCtiF~%?!`1`cg#nV3|?_3qT5Ah`@T@rIj>Ct_zSvh`0&SWp;(>HKB`PgI{ z!kOjI$Se}3Fxr-MJR=DurmJ>0Rre$(!$f&IO+lz6=j3zMtbXq{=*kzTp_UT2$edH0 zX=T$c(LnQSk7Oi5A`H*sc@K_AXf?ajSmMBYY0ug|Ev^v-MetZ#P((6aE-zjPQUo=k z$FTYwvH*xLrD0t6veeV@kq(w1HXAT-8L~Y z+Phsxz+!$hv^#O_m3Sxg=OK3y-nE#txp0>pfQQz9 zFeYGd(q8Wc_g(viuB8WEICkZgSk&~vn|iMuL44qYSAB37zFqi@3%lkYiphv??7}<_ z!ljp9dg*^$*tP5sEJVBN{@dgRCT;I_4ZrK|!_wXH3&$VDf+3lZ?Ru};wc(zNE*xuvZn~`vimBAxVWfA_ z?T-oz-|%XGHE}YB@(h`{zuJb)IQ@#j%c8@up}IA-Ro(GOw*`+k_8lQ!hmzx~x0pS=dB(_Ekd zCtXt_gg5m*fIUi=VkUeSc3VZ@ZFJYfuB1&^1+&`~JdVVkv`tu192y%LDK?%|Y;Kjx%dzI6FeqxFx)}ABkd*5s44YRazIwmbR)M^ic9^A4x%}A_`(87!DbRgg z+h-hvT_=yR7)IBNHTu%i`wq3rkMz7#Rs-YoG+7gT7^L?LmE_m)_eo2#b5q}~QG3$< zTxY>|Fr?3j1jJVhhpb&pC+t()n*ItEn9W(-RsEtJg|l_(1F#{H-e`^>;R z1lD88D`>Xb=~r6Y4?LB26WiM->as@-B4NR%5n93!(?&w=pRA3fIR3}Qfu)Rii@5jF z9a!6c<(1e^0=ou`_TGN_ygTn2f2Tt`ZrXWa3Bg$G-1^DW@q&Oh8%+0Iht1IOzTi>v z?~}ZApZkIC!?4!lIu!?OJxBE(f?2@cqqbk$doa!m2CdwZzq>wp-wsUf z$P$vSarq+~S#)8gj;4u$;ocXVx^vgHyBG+z#;v{&geG(auX!r1`$^aL|F=!mmW#-%>u11+AD%M%>oyl+p)Zio zxM=ML?xvQ8i0Pef?|B;Be*eiLth z@)Qex?)JP5S+d^Yu#q|O@eIq?4fItC5NH^R^p=FJ01pUi`vq*S7jms)0plVpuc;Ob zv+|?428cmBZ!w6QqqRnBR&*Ee?v3@PV!4=W7WGBV`Sa)Mb!LXTcl-dpb$3q8B z9;uGuf#Zia_V?j$vz5zlJ-*(kwTk&xtpSQg4eO3lN#?78{K)Un>-Y*0!+FY>CxO?%ObkC|KyuBxE0|@Q22R zgRp-?C|m%JEUPzGPbSvS2aVcTs~DCFVY$>qg|!MuMxVfwVX;~Wa`k#x&P^2?p~$M1 zua%9IdDM66!=RZ9p$fU6R4uilZcFlyx@t`YP!BL^ zG8iJmxk8~4R?C{5iAD+elnf;kUI%$>td$Xh9g!0k#vq^u7PE?IAf*ao+^u4B0ta3O z1t?{Wcwtimg`s?}m&Zn^r>3)FZN0`KAq>E1CEJ?FRO(*j95zI=lWp885=N+5Ja57L zwp$MPPCX)EZ7!(Qu+khsK2TCou~K!h+Rt*WRv&`g0~jbuvLe062s@vMlQgRNp)@h+ z15kBtEL>9xxv4S)YR%6CpD@iTUA!ZJWb$Z@ER%DW#!#+Jm`z#H*S8VBo6sIn$T5^t zEL*XWiCUw9p`K93brD$89^SaD@AQ>}uIek%AwcTG&?@Os#?&E^2kNZ`6I;D$**dG9 ze6Cy;QLsR9c}vwWVUkdAX)wdNN~t_0?-bOvn3N3+RNOnomPm`=R`+3BlL(?-6zYo( zs@4dbjeOJrrxa6kLF8k098!WgE5$vaY41iDL`1GtgFXFh-(%TGbo+gj#O~cO*r9Xb z98J4#1~NX!t-F{UIEw5UhYOMZ<*HLEB@z5s-5Mc!2k{nGp?45xad9|?>sBe6>N47| z+ItwhdANbge7h{L%R;*>idD3UuP`s8HEWZS3uA?5jOXzyC0NRAbG0t*KCTfM5p;j! zEwO#*;)XF6FuT-O7D9Dw#R*1c(bvIEf!kwhBHbb^H0l&}gco5XhwQ<`&f>OohY)DK z*lbF9is7yms*e zgPT^OiNx)_nuGrocehYHu?=cj!~u&5wYIF7Qf~Y&kBRRBN5DEnYtn5B7!UasxIl52OiRMM(Cn3x)Y;xND3gP(WN@YqQFD{{WSPe@qVVTr% zl@_+4+Bb?f4y44Ql(9O%=D6C3850M4`4kkBD!+2FL?5Yd?S_?St?Ywftfgk3I0B3@=mkd3g8P?TV|bNAGKfnED@1tko2&yrM0rkLiAIrM#Pa#6fx;x zPq>KJ@nTh3g~Gt84q@3a=qctZ^z@dU8F_l@2tsMm*N!!ZhRZooXdQ_(p#kEB!5N2{ z4WuJeMSo_h?=eUQf$6x zKlWA7itY7+jImNh8nWQV?n_ssJ(Kn5ot)GVZ2^@E(;?~y=f9fwG$DRev5H@u z5{MlmUwClC!>AibR68@XR-g-&FfvJ+R>J0oR?X`-tY5wso_*Y=MS_w~P2R>Z34eLz zS%V#3Dwh5n?s%<%5sj8F+thF$zQ9NoUiK)?+JlP-C2G!37!Na2UcuTN+bu!ATRI8T z$dHlkAd+_|I$FnT4v9=ki&57z@_kfh>d2`Z9Cf#FVbLh1dqFFb5s-G{aZ_2@XrP_O zYGLgH4lGQD_@;xU{MP1L);NOuR`pN4R~2;^o8$d7dRAvn(wi}tkjX9)=MN0$?h4&^4d~0DP$Ez zv9LVXEai>fHEB6I5LJyflCV?ewd29~tzDE+4p1Y@^7&X;HmsWNcNl3ag*Mh4jaWsp zPv{FwbG0~O;&!z{$5<>xDGb$eje_*9wLUjq z8c~yvJ1uw*;z%I`fUq9ITB0x#{*^u!4`XyL)#R!iuZMnt(9!MF@!Y8VosC`f;>hHe^m zZlnR15#u~&YXiuFxK=DLXmwG()n@g{&;fa2R0AG{_`$8wbdiIKFx`k@Y*aQa>`L)N zBB%&QCoQB{OFemrEiHW;Mx)JTvMQP4$kRmRf=Ra2lvvQSNc2G!H<=alXf`(BM}z|t zB?&H$Ky0j8`G!VTWJMtAl551evATmU#1h<8Y>t)xN~jtY^H;}4$azJzN(M&gpV1R) zKm*stNKw5g=pfP!X=OsRrx0>44Ta1D9MiFKt^q%0GTavUFZd$ROL@>)BA`XLES1vm zSQ!C1+*7oPK|3A+J2;~7Wl|gvT4{*)3Ef2U&^ZwS0;`Z4dd2+K3FxzCV^Vp^op89; zh+qk04ndWxgA#p}yba|ve+^(G3cv+Z_i21G&~_V2!-dC=VK6)@PYj{R2EzP^73EVI zL?A#KRtWtLS;+_{!y}8OQLIXU9Ih8)IOv!Ie+2Q26sw6^W2<_qXz!!72}{kenJ&PY7%}$`;^q3!BC}{ z6tCWbgP$&g)_h7MC? zb@FUdm2?z`8Vhr@T4FRRE=Cc$RU@BXt9($QnuL*p%B zQ?wezY0_Ls6^Q(;S<-s8_g#|JPTho$41l%-ge(=Pp`oZcX_uvtn&7nJ2nCS54v(ASOmg(4#qw5_(e!qacC?r> zy#X@-uHuNY@4=V`&0r0*D99mZVG$11BgsJ#gMv*mN9=uIQb(#ab1twUJjR!mlCu_#Hc8T6 znW6K1rpzk^kSu~e+Ac<|Aj@!)IuDs)RzB5xw%G-FAnLO$Yt|yXm23-Oy{lrqBSg)n z_N4jIS_uJ-G>eu*N@)7BErQ{kf?j*OBu|K7^Q#Lx?@?xE|nPP}cB$kj7yg3&N zW?3bJg;H~C(5gUpVb#U=ESr9&J+#t!f%LB~Bk?GPrb3wMKr0->4+JYP=?o7AGc_Y> zfzWKc?$Ps)t2gGhR1z9)R&=!PL~&o0VQM*&OqQBhSs{1LDv3X&%~U+tJVK=~Xf;gX zOFUG**yu-lbeSzR3nF0&$-if1U_^z!S;^rc2OqCVo zJF=x3!8U0ELWA)-DA$@0Df;AewOY~SX_ykPV66wC6`^2G-iB|BL>xukQAcNLp-{Dv zKsxl?q+O=$VnP$w&n!Rm4{ca{3NH~IF{^~4j6T}EiTO}N+w4^ids}xL(8W{>@x+wDB;DO~OtlS8r@sa*2R*JCL z)ja$a3D0R}#kG~_`52Z3fIFwl;o51CHC?$ZtQL+s%=YbNlS)ZwvDb@84EfUsqdJ3G z@WSAjx#?b>7(vkrP(LQTG z-sc*x$-u5tyrQxZC9=>g(m>8M4HSmC*5SGo6%Ln#T^O^rCw9AZ?TJJ;R!=Ugmn6Ti z6LpEgM6s$w`6s6!03kv=hJ~`Q53zM|tcjg>x0#;aB70b+Gk&D3sI z$yZ9mYLiFO&`B<{zzHi(bELW<`H^3!P7(cCQz|p9KMm&VPsv;X^#y&G$a=(AaMT&5 z)wW7>R~4eqEMmJ(kQf;$XKPrzt3FPRX>L|((AldmE-xCA-rrc8WKPv3m2BB~ONyco z^ESo03?pp~KuYav)0sqgkzZjJP#HC>+{w47J}uRWd0c=!pVtMvE_AhAo@@12hij(b z5kIYCh}``v${YwaPU}*vj~b_`hE5xmWUZJ885QEri@8k%g;<6`GRKr8rd+8_D;tdg zbD^Oqtn{Sbi@c-{LA9xPYad#s+!rr{5*AM;s?W;(^EYz8z3Fagp|GiAYSlHP5bNb+21CuH*=I^baW zY#uAnFcM~{)%lX`%M5{~39wAD6%2>6O`0YwU#vmsLs&&9{+OT=`PMHsfB2M(>pW57 zr_3wzX~crUSGJy6TG(Jsq=LDTRCjID3F7W#Zh$z`vnPa_;GsGolP>+u2nFRTM2VBn zyQ;+b$vj}QY{-a&+{DhnGr;RrPvxCISxZ#GL@`7m7dR&6I$DSfbT%T#;#A4l=L`)k z;)_jA6*G9m!2Quu8V4mek`io|tU-#1nIMcP z7S=lP0H$*q`ThcjcCvz_j7cgiVUZyfM*Z?b)(!Xr&K+X2H5JjFJ{dL@SIg?tex0|A z?zBBa+v_~VBxGdhw~T32NC}?W%7Qp&zDhX~#BSB|iNARuTbV>f=x?sA!6}5GY$>0t zQN^lDt>(N8q-EyH@+6&*{tBS#aW=g~E1-Oh+Eltoep962Yx<=75N9>YgDD$&{0Kqq ztsC6D`}TJ)qURW25o;BLjmVy4Jay`VLgg3-N-&5 z1(7N*xtPNEO^&36h;mCoKcNyyMz~`6=~1F67tp3Q!NmF-7baT6-9`;1Vi{s3ir8!Q z`Xi!|o3sNFTfQ7k3yUH(3RXZ{Q_U3mBsuN|mYpmrS|af$oyXC&H>x+%ltsmNYg?XZ zQQ6*6~?m=psds>ptrnQ@FNChPF5Z6MM2R!a1;qocC9MO8gcr}+a zJMhdtEn{tUlN0N6ZMs*~+i!Mg!dXWB%}9WH8hi5-hXZGD{;a8T^b& zeE@45gVe96SBp>!e)h?$J(w7*M7Rsm8$mO}h!2dkJrL753q;dpu_Z>Gx-NmsZ}U)- zA|n1VE{g)Ax8K^?XmviNX4sZjv_D%1Do!k;`I3zG@;0yT6|o-O?3oR$!;3`d(f@jV zt-QClEWdTb@TNj^+uo5tcpafUn_!aVX9)RWxst7?kO;Qkc1|*TFG}LNU^#Fx8mePA z&#Px{Q=vn~03lDt(V9YtCRh-ui6-Yf*U9pq8LvL*bh~3d zy?j`TgOHlOgrr_JO?eZIz^LMjq@?hz=^@NhGxr6%z@T8S>wrQ*|m_ zO2R{v6^A@6Im@1-;y3C`afpmT!5o&pP;<-yj4Mvl-@7bIsMD#v@CfJO;Loir55t5BBEEm=yJiqblhR)4XHg(dplWOFNnLUkETg~uO z^Y0LU9h;oP5=t~sx<9llk+u8xECO$)?W{kdf)a5i2MI8Iu;cnSC5(uZ4lAuU(ZN_c zC3MF!>`#MHLV*N3=&Gejk}bsZw=!Pv;*jdNh|pG0An#_WvnisHIiwYXw(QmQG|E1z zb1@;YVG}J71c`c!PG!av#;KAzqYN{R9SZ2ANg;W$G=}7B$dfgu1j+t{mEz2hJA@fB zpf!7Rlp^r#&9oLNfA%KMGg%hL`kRBYE=8i{k?Y}^=d1QQ-a?=?n;@c!vS1BMQ<+Vs zSxS2@o)Su=1S#sI%$!iMr_`w-5HBz9z&^TKq55M`28a|5NK`8D0yWx|CNfoUn)E%2 zI|j*7m@CWpjuA}h?mrL8t>0WQc#ID z?WfL;*Zsw+n1lK|Di3j$SeOGYstI zBz;RSkqz};ozUu3B>9w@ll5p!#I*q}iU|9sL?%S?>vhgXWTl~##9e=`T?n$kjgyc% z)qt4>iK8Z-ZBNU52;_<{PKZYXaU~zJ%1>}nO%gp2%BWJ5Y;)DNU_lEphJ4J6ou~!| zk#%AZl`T2d7c8JPPVLHRuNF#bd_zOOTB}dwE3MHY#kQ=cNpu;XORS@)WUQ$#i!&J& zF~6hxaSb1qx5=~!C^&bcAk|9r^V8BMyj>yUooCGkiyi~SH; zhayX!hULXyU7N*cUFdE-o+h17yi-Y?PasJrLb8#(1$&FG!&N|Kn7G|1uc%CS(|ae{ z`a#>BBR1e!W~$Jte908}v?+Msdigmf5VK8q{N-uZIBQr z9l-NU{F1NGM9cL?>~x|T!x{uDwEjf~cbl<9xHnFCPMipI22#`lVs%4u-x~AgFowbs zi>!p!qd77*9kaq_0f>6&>u<=TvK*<)>a-@tlR~C%vg%R=X&@~$eJth1YNZ0!n}C~y z5R}9gH=-Al)r~S^jzx>o(D1;Pbt?vI12zjUw+rwKF(n!kY;H#PWmPry)|tT4^%49l z=5&>$m?69^Tpi29ld&%INeWQ&3i%bVlto^Fm#J_my>^XpS#_HjdD~6)dzV5da=R|h zt-c(k!h^djrcMI#6`PnbotuDS%c9g3)SHqa z5lz|B;-ugFRJP>BbnHKY27snzx!VXER4brw!*9H@txKI!U3(Spn2t0sL7n1@Es3N= zOa*JB@GDGV3sS$ZN-Dv=Ru?ZTZ%03_!^S+JMn%Gj9QO9Yd#Z&1z0(LfStt<_#>8Pl z&RANB9OGpoOD__IjmM=u*#cM$2urY}UOB14kpwT4V*No7anxc2x&;K5PSqM~@&413 zv1cYmtZqPagv6yp7WQFECeMn9Q0w0gAPiCc&Fp-`Hy0okFz=xbWY zpeiAke62o37`iKO#_3b3>|434_(>wRL2?=kuNjX#1f;@r2n!cw6EBV4yb{nBV}txgRM8J;gw2}lm2Or4atjyUK-|Y zu*QlQmd!*6RzeYwjTe*m zR+X_~;FB(*bh6wcJ|AuRQ&1l{`ia89fTEwkD{iu{2RG7^UqI29B>*@Xs4-yC=11rR zQUrV+FB;%^BaeusYs^444JfH6Qt`|b%F(u7;FhF_GhkUnKcMR*uoi0=!EN*lV@vS0 zfpxsthtj@5ywY5Ps!T9qVj4TmY+80^c-n^k^|Fo8;L1${c+R#u%*$gaCRh~DlPwz4 za!C|K6KR&w3wbInn}Z<>i-^oOs^u;pD zh_Ypsq^yMD(z~ ze5Y$&^9dIN3s0gob+X7VdG=Cba2PFRl2Hz{!Lp+T*O7E|pW|^E-N;Lv(MCU<(uY4K zescUE0xr>-t_@?l6a%@B??;TKt2b^@f%)De{2*I^2k~Gfl#HuXkSej5lSHX}^_VRv zkf^8JN3BK4F#oEJ%A3;AoZTM$E)Q5VEpL zzG~&{Hj9Y>NwnqsoK0}HF}_3J4qoW<ZGXoY8pK;La)wEaXuMFI zx=iMo9~pio3aByn_+ibhjK_CdQ-6apMK!6*n>95x4&s7ISFeLHZP>v?-=@AnY+hGf zHUtMi_Z%Cm%#*P~e^oEAPr(WpzqPO%eT}?qV4bE~D8xb~tfHHW_E)2u`B8bDX7?rR zsEd-eO}{`FWk*?b%IOTu_Y5rGPfp?pg8lZl>(_a`jaNhCzthp(J`MeQaeR+_mf$=d z`Fw}hJ9#xU{<~%xy1S;KkDu)Ptvi?z+^WZGr0;j*u!)B|;@!a&2d8P}S9dTo_}GR{ z_#VM4-q;E6369;~3EwlgwIkjeTy$wC`n`f1KHUl5JGi4Gj&mh%>qNg#Fsmc}>|pRY zb|OUbsqSFk;GB;5e!&&kyLQN*v$;3oi|5ybNG=CMlg_WG)j&%+r$Q%c`n?^gitl>bjm zgMVcj{5!y$bmm)k<(yE6EC;GN`2< zj$(e^Nc?=_#}L1i_{WIjxLEysi1^LK-OPQ4_}#=0ApI@CJLU8LD*a)>IbSikx#|Bc z@$-ovOFlD@ZIv_exy1J;{xESouAd`;i=4kCr$6Dd(k{Vb;#b^nz)Sc*AMu$F8ZP=L zpAE`?-{9_-;0r#m6#B^#4~{kb1;m@gXAyrP@i!Achxk#%Pdd=b^%(Py^Lh32&q{w- zF!QTN>u;)Ia1HrfL_T_KFDSl9dK&H19&IBIv=>y`;xt_ zVz-gcWyF6^d_4vFQRRPFuun$LpC!IOaVvEYe4Y5g8Tua+KRiSK81W;ByMFGA^d+C4 zW`0&MpK?Zfr*a)f`tAD}hcik43gSP?;HMLxzrWGHkMx^~f19}X9K*n81cwF<_IIAo z3eH^Xl%FQ)TcpQN{ak=Ao#-!~27mW7_zvJApVcQ?PQFV1R|6M2@cfLNKTmvC2LIMH z{O=hVPvo1CSemd|s6t36q3 z<@NsJc;a)3yGL~@@r}gY&b*5FC~cHu*y zX9Jh~eB(bXKUXu|=PUi8!A10Mo&IISFUjDG$)|OP@d?SNkN9cdG5loWn~1OZPs62u zl}||gpTB3g9MLJCGH@yHY?c>4^|OuifA@V7qTR~pt&acD@CD?51@TLMY`A;IA0~bs zarfUoPW%PpsNmCNGM^=W*-s33RPP4CSBSsmZo|h&|83$gy3c?*^YbI(fBLE6(qGEw z0pjm^!0w`z;~B(XNBkh*o%CVWH2BjVW52ih^8WX6;0K^R-gWEIl2Cx3`q_6cqyID&%Et>YApQ>-{AIv} z&pBTS8`YoR|`kP6A zGwDB;Dc5&N|Fu6EVU_ehBYx0xjgR}Kzazfww?=ps>3iT99{~U4BKjNdCm)P2BIlp| z!3br1D4&-pZr_uCPgXvM1$TQrTJphZeL3 zz$Nlrw%qs>NxulVwwHf5K5K}-O6mC{aTx|aEAiXEUO@iGv%~pE-guYtcdGb$HR-=} zmtn4lHz@s~L2stN{!h~XLR0G zPW)TMe?dFx^uHy3z5P$ER zjnBUrJeE;w+z2W}J(TXP+@arq4!Pf#8 z`~Mj2Ki#6>Y{g;EGwtp?;>R@+j$l#D07c@6FiX6#|sR9Df&zK97FtnUTJtg`79#7j`RaY9;^YrKlCu`2W|j<0LCe^IIl5_ z^sgbG@6bQ553>uKLe@+3oF{l|GRmzkYyxj(e8bnSEG~pCUf{;|BZ_@vka>L;?K(Tr(Y!QC%s=y`mZU@ABoFd zz{Nh#qCAh~y`PcKS06Xvdg6an`on_BOnBOH;!{B~Jp7`;s-xZ|arZ|5jF8_!0+YU4S3wiH4;F6yQX`g2j{{rcMbDh!u z(JsMviT|7qK8mlOpA!Gz5+nQw@n4Yt!x{VkN8(p;+(-7o9*3CRmb1LG$mhAl?>oaN zmk^)l^wh(b6W>7mn2#F$k;F^HAHLTBm|6X7BmS=U82t$Ge^Q)35|t?TBMm~Qc{l%2?CgQU&aU=4X`3B?T%5 zmh=O}Kfl)K-%7kh{8;+cK2AShaS|mi?;-sz`t7ctpCkU2uNePVvAkaaF69btvvT#2 z*S8cuG}uAEaU<~u$mjc;jn8+9?|-!qZ9r7NtKlI45Io-$nYb{@e=We(Apv zU;P|o;C{&0i68lh(R=;=*!fTnkzFGG=ZqcugW?oo;_~e0m^^1wf0py!%ZVR5ZuuD^ zzLfY2{=smk&k?_9nc<%&{W$R-USas<#4jR#8OL9F;{Qy1^9G~;6!Fg!Kju*bhKb)o z{KGPFkIz2De?q)`sp0>J_`{0xN8&OA0WN7r=fBnHck`%{RQ_J=<-=b{G>xI zU9ZP2#NR{toJn3S;#)HH_+G^m3G(Z8q@PXu@BQN~#P`nV)eng8{DhTjl6-zm{AV0L z&a>OWv(ZtyO-`o%Ld7M{V1(XIPauA3rr+O8{H+-~pCkUI9~<}0wDVQspWJBt&t~G= ziU0W!!;dEZ9^%`Hdpo*@_@@6gLT`^>CSJSN_-rGe2lwq<-n*5aM2X9z}i+aQsQsU_>-S-`d=F3ciScS8u9%;ldi}AQk+DI%Y&pJqun@-_nviB z=Q#fnz(ud#`6naXhxGG^A9-II?<2lH{eeZK9|SJ-zA3Z*tws9R|I`S*U%rTV7wybR zWc|Z6Z z;`bkH3H}4==Mum8)ESC+dpwo+-_g#y9u5H)`8+Sv?%qK9y>}TO_Y>Yh{KdnD-(r{G zI^uI^KcB<=NVr()abNbQvx(n9{OCIkaQ*)U@dtit_^G6SjQ9l^|6#9VEdMuW#sxo&JpWePc30&kni|a1dkpEYv;s4*{GdX2^eoOk_5)aQZ9AeQ=&r3`n z{z(7xUx*)0{O8vj{RPBdOnd|VrBjH%lK7u!2hJnDmiU)hFSigs2e`<2lycsic$4(^ zZ?be>LHzAXk8vX9a1QbJlYY@Yrq7{07FmE_4U^e3$fR)9*c!_&vmb zbDA-}h4|y-(@Q?CC;J|2^1Sh6&@Ap!Z z=U%Th{+|D1iLd;fF~H;cSw#F2u3stI^?^z%OA zk1;>)7wsfIll9_u=?>!WrJum&7u-ku^W@|H(oBqZM1N-f+|qjo)15{9XZxFdILNXa z%qPC>5d$tE{aWB+mnLbKNFJP__+i2Rnf6{FpH;NyFthsEM*O^A+i%ya%ZcB7pW#%a z;9r1Cd(X}zUk_aBcV@<)znOe`Hd+p^Hg>`HNPj-#`D=*(lJwndzblCUh4`O2et%?d zyYVb2q{#Dtw;TV1DTpJ8fAk)syN&p9#NYf413pjwClLS6afaW4_=S8uV-0juth`;g|#$W^aybHL( z<58o33-NK{KYX6yClh}M@f&|*fcFd65&z_v(NB^7%Zl?y;__YKlAmKUdj3=LIhp|m zy0gJU#2;@Me{a{l_#$#R?>`K8IUGU!jr( zUCRF|(w{?o`x}kVXNk8I=a0nYt)%}f$CZ)20xszuPC4}OnU7Ax=Nn3YXmEbUZ+w9K z5B{Mspm_}*BYqO&5B=nSz#Nm?9T!{v$A}+A{O9Zkd+c^FpZMnwF?nt#{c6SeBXM~x z>90P+7(Ac%UQfJ6KBp0X$25FCLi+1IW_(^t`db}8%<#7o{{iv+Ck?-t_^*kdd$r;F z5#I+DaUj1ZFS8ZjCwT8;hPs}gPW)oFyYKL!nQ$07@p(1r-@|@wE$QDt{E!1JKR%!M z7R8e}vG4C8{p%mJ-(KEN5-*%-d|3U#zZ3uc5r*$Wmj8@#iRfEEJ>N+D`=A&6X5w(4 z^m8})yqFGepH+YG2=Vv-oAGauzIz%u9I80%{QnsJC+rfunE36q+k2AFJmOcgT^~Yx z8S(GlVGJgSzY4gPi~ZM3;;&VD{zzOV$miBK8J`z1KbI3P(>~Yu%)b(^o??WL5dZo# z{C_wN{t)?mgZ|93$YbF*2 z_gfBGVD{=D#+NQ5pSi@l-(~dY6JJLB3hK`R#9s|u^8egSTyBE+UK#w2AhJOQv7AhxiA-Zsp?eCioxX?|#(q_mR&&2t-J^ zX0d-inD~*v4@~64zs^>CpWwP*8RCBX>BK)pzj`qrcn$GaoNwvAi+F?hsT_B&C;oQg z+s`uk#dZna3taNKl=<}f{V?g9Y!^q7&*v29kHqC0q#wJ+7#Dc&A>uO`|M79qUW-hB zPWh(M`}PpeA$|${7N>tXaLMQ08UJ=U>8tlxf(J9*Gl(DdeB(bx{9NLvyv=aBzrpK? zFUjcDKM{ZJAx7`|b`|lfIlg;4`F}=n{zzPI2QK4_jr0=^=e_TdPxUj#f1LPT#IHEd z@a4pRJq`aEPz;gJk(u^#1aR@kK9jL;bBVwI_s00MFTX^$9;#YFs#K(`l zCs=u3lZn$FLHv)m8H0-~`QRnQXH(yX$bSj(Q-5O_bUVDB_)%Qnh32oHVd6t2qrZ{m zdJFMS1qQgE@E+o?`=dS2>IptV{KY>t{7kz9Hxl3Pa^v$T@$V3C%Ek!zTu+Df0pL*pTQf02I6vxz@S{GkJk|4WGXsJ`tJ z-1~?Dp6(Zk?9gnd6o;)!m@n6= z*z7b63$<{hTpP-j!$PapXok75NjYM>E*tR|W}mS5#3h}HuwiSpWV<0^N6uDbiknsz z#wwL5JYri|>MtA}B&Vb4LBvM79tSlH)mod@ZCt)?00&SYdok1}GJ8Wr}9e30dTX>{CnT&y7>Te&+QM2U_7AAtbmCr=ZALnzkXmoEH{gx5JQoypFYs zlZoFr7NZb=SdU}DHIQ6mV?O^aTm11DZ`s^Y&P~w$H06hG>4`&VGPyrteg;{xXl@(Q zR-Q#mf@Y{2Qrg)Sa*UMhAD?D^;^Hjx6BnPDrCG8di=3Dd=;FEa7Nuzx&z-+Gi!8{b zwRrB5Otu%#)pn4myv6e{7*FMS@x1v91Kp9?cA`fOVZT9~hB1WW=6#=6+qJJ)#m13? z&}(ehi#?x3zH&ap$m~UnPn;hNm$4mWSSU5O%I}5THeYKYqFR9M+i@6E~}RYkp*NFr{mzLk1BSewY)1Zn#1PF zJe@#*_?GVOt)~TG3rx+vG?Il&<}X0qR`O$EQBH&mtF=J3(#FQXqONOeBiNG^XYAm+ z9JPr{bF?<0J89P^8aN|FBr<#9JX9hMQVq{8z82cq-S5>JbP#Gy&kBhvg+g;=;4J6dLt1)1iyaB;Q) zE<6EkSrSW}+k@f=V#n3sM~dl!6SA!uNG6#DC!DZAS*VEz2QfgRL2{g{o?#*Y)Gaz1 zMNiLw9nYq=aKSvZ1n%Wt^qtk)wpvf^vae?_*f#4RjL$j1?x?oqdusFh)Smh2;{}Wk zJdm-}fepIrs6EKLiDM9Kw`{x1?|M9fZ8~f`Yj%!<5%C66fjsO+<_raFXN;{*<1Ol? zcA}l%wW<=^SI1SC)OSHMdkkl{1(s&QU3X`R$WoyF?t5yxH91I7SEnmAb?67CP znqizOgbs4Bggvz-AGT>ROmQB2u#QN*h$amIfL9QV(Cx7EAMpn*y zTg(^rn4M61a9HtBvn;9W>GX1*&FaZDxkdpS#x`--iuUyCIq30zQfM5BIaWpiE4j&V z948kI55apY7MCtvy|#aOUpRmE{Mn0wkysn%CXOpgo;f6&lBXYq8++@zxo(B3+G(;>pldC)UzJ~mYu@meVEY_Os6*#YL%68+|gNE zyyS8OO%;FJRkncp%oN#y%qtc}RO9n>bj+5FtP-ZKmtX%N=zSn^2|2rpPm)THKu9 zS#8Ei+>P=SEUzD7l|7hCY}4=%hA<(H`(k{n_6xZ*mhud zyOiCL8#N;4rdH1=WUf^kPIDZEh%i*-msFA?#ub$Ea!F2p3Hd97Y@u>oH-Mv#Q z4Lx*~RQoDNJU4I*a3sgM+9|ntkh6C`IYwdgox zSI|rio@ucGo?IhlnWxuexLBu=IN~66 zS_3>mJeeBrvH*HMtcJ*v>8OVyhZwmGy0Wy&Fy|NlPwqjHBeh&4oA; za+-b1PMOAl+u~%XPHFREP?Ij-2;y&)3aq?!e9=Ma*+b*S4!}6Lm)vN;zP84isS^g# z+Wl-|9K3`>zqTT4TSGYoH_rb;YXvytOO60bgf3!}barHskfIsL=;Tw^5IYTf0G4P? zv0OJ-zlrX%SkQ+@;3RquE$3?ybJY85wWo~+;-U=FNvl<4^?QB5mrptlp0+f2)lOle zCl^D)132o*tOn}OJqlzYmPxLeZ}%;mdaP+I9`U@zHlI-}OODSn>+A{>^%FQ_M0#9t z$nv8Zr=%^Lkq;t{rn9mVNH>Y2loBS^`zx0LESwrr$K5^;6kGl7wst&G4l)TLSF2_{ zEJjL?<3Y?*x51B`Xws-Gk^!6xR4juwF4mMcXZZMVCMtE9ef4yd z-isPZO}zlIH&%ErQq(oq$~Zz8-U%ER48L`(<>s10rAT}cPxX1A>KaImo0GyQh?KcD zT*zgLn0E9yNc4uUt=4?blKK~_(v^&IdadHb5(cTV<^)wIg^dZ7u^%G~kwxYqlrTxk z4}|@M5iO|esjdxEmmUeW!R+!z#MGU;3)5@FBb|jHb8xEEZe+3G$6$;e;`G3f&DA?@ zoVq9-H_igp2M{H;9@9O;WDhvk)x*y_$2nnWx#?EL0%&EMXYH!2?lo^qy+uQnbS=>x zhfWWnzU?8GJlufjEGo7?aSd{HQCL-^QSl!!F2spJUSGn(MzTV+e5xM~@}!>4qb&e3 zX{s@oqN+GWwq~d2&0Vw23oQ>@Gp^Sr(q)bd;LSOzu2Lf6ketWF+4Dy4yYh*NYM@^!*uC$X_~d1UpM%_6D8D)o_N^~UPS_ObtUCXPVmnU5+>hKE#j z(?d0P=Q^B?$-Z`(4DwLQA{wC#4k>*RfwV}qFrsUjA%x;_Tq1E8w#E#h2qSP@a7?B6 zjBQnnTvLDHn&ojGcOl{ZL}xU4jYUdt4)`+o%6@B_%5)nyETNyYvig$|Qz?nC%;?Yf zWVQ~q$o{xgkvOJk77Y!*(Aek7b<_q94os(t0yE&Tu{KeZX^3RIvS+=~^kd>Jb<%YS zIgDIslYwVLstIj5NIOm*lM@uyL8tJR*JPwC>e4n~lB!7Ps;E2!=-H8T7~7&Tu2(XF zE0!TXF4iovOg?BADKVEJJP zwt%(9vAns2-zVcADNfwEt&wvL<5n!0H4*CUlTB@zY2uM<>&iyKyx!Z?PY)QMYKpIj^9`LW zQgSzP;?DJ3q(}7Kd&rJqqUkJ;g}vE+MV@K(h4Ph#rxHVB3kl&wyHo?pwp?^%P&yp6 zjBLR_Dk8j)9!%(+yhgu0+wfb$k*P*atK2%y6*$g4u5A`uGHEs)%p<-{F?tM%nMz2R z%+3YFtztQ$SK=^xP^c)=j>w31(CL6@7>-on;-EuCNFr2|G76q_D)O9!P7aMNekOIH z;S^Scl@;9sRy8ob#puRdIVp0U)b{$^cxgmU4}BWReXg**CxsJ=53;|H} zQ6bjgr2QvD#Pb$P_S#1xFy)cHX;sJZR*d}OvjSZ?2a2tAgPXmzw=0t5$vh62PMu5H zC^K{$Yvtl9Iq6s%Uus%ry@XLb`^h2trZ^-8&u^ersl)5jAaI<==ucaJRMoiWD^^zG?Nafcw5n2^&;`JVzE>U@?CnDX$k`i zB5CMgk~tFbvE@+!B0kP)#PyuEp3o{jE%ynZtmJVK7>{H4*D!Ojo zXWRxQXBqb=YKz{GG5+ZoX*RvJmaXTQvus-RP*7o{;|5LH;(wZpx~#)#S#Za*A1SBt z)1fVGp%@*{OB@dMu1dsYEs~Cw&br7b*P_{)8y3-Xq(zLC%TMHN)o_+(F*B4-4_3#j zn9`J^k0+YWb#OF^u5$AZrx+X&MC%D{vFruQ17-&?dhQ(tL zk%X(Ioh=_Ll?y^4XQCz=9`ogl%&^IQ4&O8i6bTx-O(8ciUpT_0E;_myf_Lck;j$EM z)2!)qDmeNL>lt&^qA z8e%puEtG8bo3MZpLSzS*7@WotSQaqSYK**EMfXP?)m~pTihi>CwdkzZqNdB5iIr&I zk?0|JRc1DR=i(YDwXFtHYge2cSgU&WVA<&WTW6bf4_6m;2HEAedf^FSkCZ z{Y+#Q*fT@>rBA7amWuNrV3|R{tbT6H;VkM5BkMxae7pn6bG;mV1f8~m9f&&u4ZN6U zZYtKxxx5aa`l}qy7p*a&Y!aT`Ses;MR`Mxxmgcj1bV|Felt=9TW8M@?HMoQbZWs<> zkzP}WHu4m^%HeWuMBAf_U4$azNuQpFiY?3M1=Vgg*`x++*%3`xn>|C)fv5(?f5nCk zu#&;Fg}OS=#cJY=6i?F9>PbG4SSHt8D@!Qgh$Q=Mni-T)W(<6#O{U%=Q)Vef22E3Q zA!Kz=EvuVENs`kzNolNty|Ug|TSx&hG~`5_NDu0GS)IG}Orp^0$7M_~bUORMCJBi~ z^l6I?a(7ZiRa_NSUD6RD3Is|Swfmt`H8ZQKiXBbnyIfQbeBK`x!MU9n^>v&Bty+B< zqcj>MQ3pzwfayW^@z_6KtH^=s$~h^{6}2(+b7r-fqUK2mh4XL|6Dny}AZ}xclg2SZ zg#JpW8#yN$H)x@QF0@abR-&%mEruJMrk>30(%1aPE)A6lhE4S-(W@(A+}YXuXd>3d zfsqucl}F9xTCI$8=)!lk@r*6QG|zZ3!OBlcZ{?w)?R*lMN{`poKU~S)7usl3De&SW z{gWWQ3w~NQ=D)ZHs6sAer(Jw@y5sm>)`u}*1#y_g@WRtRa7gDOP+_kwwzPV4d6^(i zt3=W~AZl%Kx3((QI+9kCnq!3@6YA`di$V2I<3PbCb&KL^4TfccJDs*^^NO*0xrFsu zsHkX7Kz25h-n?XEO|6DmsFCDAN+-5U+K|%;uvv%@#9o?eL7!9_F1W1Lu&MfO(}bqf zeqG0H=_C+=YSl7+2?WJxU2>LpXd8r^ewg`_?1-PtlwCp2t(7tYlNx9g^Rn_KMDSI9 zvY%tGmtMt?Em?ol)j~W2shc<+C*?~yTs{pwKCIE|gvT$VEerOIRn#fzuj*=^4P!0y ztTeD0t@f~5PW9voS2OMS>O2d&CN?1xh_w9Gh^Dj(Y?bJ^SD{x%5PYl{j^_wLAW=hkr9lLh$5Se}X2aH9X$y1lB^O|#Gsqa2WFI>(VNb-0ZYWC|&Pa0w z%uA`93cR2nwPMRy1(hhVW)v5%inMB_v|31Z>A!~XF4F5+lMbA&iAmc2SYWQcW)_m8 zQPR7$8gWYT6g=?9D6@oDbD3ePR81m;X8gSiut^)%o{YJz#;jrYp(gD2M#MjB1&ol~ zaI8=-Tb-N8uhR9x-gKo3$#$ho-StT{InlpI+7|aXl6+*hytmgiTr{CRMA4|fDl|o7 zsvk5vDZY*#5yqPv3}Ue|ABem%O>bEH?sSzxOR+qy)~=!`*D70Lm$VgPl{@KYfn^pjZRdOjEUA4C#{|60s(!;CD8Sx4X%JnttQ2!pG=54f3JRP zXdIn3;JZ&{!n#TSWmT@+gw0R9SLWhW)s!BU4G4;&x>RGyA7Vn7P>7%V89p)x=u-*um7He59@%R7Tm8vPa&gEkG%uZ%?g( z+x8(H*}A5Sgnf}tyg*uPs5g2aZNhT+;s%kkPBU)6G-DX%Cv&n$3`N&%4iE?^|-4Wz}OC9S*!xFWf3~@pHP`N+^XhzBl_kTwVVB){*QF{^Cp78HTAy>h=bm1tRkvZjq$Vf0dkJokK zW&tY>Vd@~)z?1}DUFOe{OyBygp`k``+|GEMPkU zdwo2*VjFxM>2n&5h0{_UGmOczFlhpTB||ulRL; zycaGXNmp3+$`5=Fw@a`TSK;l?e{6%@@av`6A1wJ{_995$hkrbg|5v=xZu#|BEU@R_ z)A8$OkpCs|{IT2ZdB5(kpPGN+;rS=5=X6LC&hJ(}@7J68g1@Kl&wKf+cvhZYPKFn8 zg9X3NJ<4v#^M~MH_W4O*A`@=+5!~=;{J_Vr*kK~|k+hPZCVnKJzk|>Fb?%`_YT2XG zK7M^e=J|m8s`zyl>HXsQ_v>3T&(GrXex0{5UE`jv^OJq#lKCIx210(_%L#eSmj9i6 z-s|riKJVANMZpuFS&8rR^}YBf>HG6bdETR6TfU*45aW|g|7u{#=WoavC%=BvH+a;i z#d7EZhTzMPVc|{D*J6n7XA54`1~bL@cD1xSqy&f;Xvr>M4{-SG`|7$G&lYRp<^6}^W`aNLD=c9Aiueaxq^$jZY>GtRU zJM;Wf?#s0FCVQUSnDFT!m=%4qFF(UY^5WUt!SlDS*lEvi^bOAV+$>)G@*uuQ{^vTt zt3Q8S1{YfS`1QAm?|OrOzRdLNZWxIBa}h0oHVilCebw^+*l*K!)4y>3)ilo^_Zh44 z<;$X!^h@@6*@h;I3E|e?Q)Aw}`{!TG=d<$L`i?#H!Cct+c~5iRH0giyA$$Jj^y6)L z6+R}ZG~p$`vFF#EZul%*uERgqTetsWpImqFHTvB33ahvuv;XuPo^Ssx>ecD_e;c>w LPt81#`5F8_F*2=& literal 0 HcmV?d00001 diff --git a/src/segwayrmp/package.xml b/src/segwayrmp/package.xml new file mode 100755 index 0000000..b4c9143 --- /dev/null +++ b/src/segwayrmp/package.xml @@ -0,0 +1,31 @@ + + + + segwayrmp + 0.0.0 + TODO: Package description + ninebot + TODO: License declaration + + ament_cmake + + rclcpp + rclpy + std_msgs + nav_msgs + geometry_msgs + + segway_msgs + tf2 + tf2_ros + rclcpp_action + rclcpp_components + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/segwayrmp/src/SmartCar.cpp b/src/segwayrmp/src/SmartCar.cpp new file mode 100755 index 0000000..f54da0f --- /dev/null +++ b/src/segwayrmp/src/SmartCar.cpp @@ -0,0 +1,27 @@ +#include "rclcpp/rclcpp.hpp" +#include "segwayrmp/robot.h" + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("SmartCar"); + + node->declare_parameter("serial_full_name", "/dev/ttyUSB0"); + std::string serial_full_name; + node->get_parameter("serial_full_name", serial_full_name); + // init_control()parameter: Fill in the full path name of the actual serial port being used + + set_smart_car_serial((char*)serial_full_name.c_str());//If a serial port is used, set the serial port name. + set_comu_interface(comu_serial);//Before calling init_control_ctrl, need to call this function set whether the communication port is serial or CAN. + + if (init_control_ctrl() == -1) { + printf("init_control failed!\n"); + exit_control_ctrl(); + } else { + printf("init_control success!\n"); + } + robot::Chassis sbv(node); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/src/segwayrmp/src/robot.cpp b/src/segwayrmp/src/robot.cpp new file mode 100755 index 0000000..8122a96 --- /dev/null +++ b/src/segwayrmp/src/robot.cpp @@ -0,0 +1,489 @@ +#include "segwayrmp/robot.h" +#include +#define VEL_DT 0.05 //50ms +#define RAD_DEGREE_CONVER 57.2958 +#define HOST_SPEED_UINIT 3600 // +#define HOST_ANGULAR_SPEED_UINIT 2271 + +typedef struct{ + uint32_t typeId; + uint8_t dataSize; + uint64_t *segwayTimeStamp; + uint8_t * updateFlag; + void * dataPtr; +}SegwayData; + +chassis_speed_data_t SpeedData; +uint64_t Speed_TimeStamp; +uint8_t Speed_update; + +motor_ticks_t TickData; +uint64_t Tick_TimeStamp; +uint8_t Tick_update; + +imu_gyr_original_data_t ImuGyroData; +uint64_t ImuGyro_TimeStamp; +uint8_t ImuGyro_update; + +imu_acc_original_data_t ImuAccData; +uint64_t ImuAcc_TimeStamp; +uint8_t ImuAcc_update; + +odom_pos_xy_t OdomPoseXy; +odom_euler_xy_t OdomEulerXy; +odom_euler_z_t OdomEulerZ; +odom_vel_line_xy_t OdomVelLineXy; +uint64_t Odom_TimeStamp; +uint8_t OdomPoseXy_update; +uint8_t OdomEulerXy_update; +uint8_t OdomEulerZ_update; +uint8_t OdomVelLineXy_update; + +static SegwayData segway_data_tbl[] = { + {Chassis_Data_Speed, sizeof(SpeedData), &Speed_TimeStamp, &Speed_update, &SpeedData}, + {Chassis_Data_Ticks, sizeof(TickData), &Tick_TimeStamp, &Tick_update, &TickData}, + {Chassis_Data_Imu_Gyr, sizeof(ImuGyroData), &ImuGyro_TimeStamp, &ImuGyro_update, &ImuGyroData}, + {Chassis_Data_Imu_Acc, sizeof(ImuAccData), &ImuAcc_TimeStamp, &ImuAcc_update, &ImuAccData}, + {Chassis_Data_Odom_Pose_xy, sizeof(OdomPoseXy), &Odom_TimeStamp, &OdomPoseXy_update, &OdomPoseXy}, + {Chassis_Data_Odom_Euler_xy, sizeof(OdomEulerXy), &Odom_TimeStamp, &OdomEulerXy_update, &OdomEulerXy}, + {Chassis_Data_Odom_Euler_z, sizeof(OdomEulerZ), &Odom_TimeStamp, &OdomEulerZ_update, &OdomEulerZ}, + {Chassis_Data_Odom_Linevel_xy, sizeof(OdomVelLineXy), &Odom_TimeStamp, &OdomVelLineXy_update, &OdomVelLineXy} +}; + +std::shared_ptr car_node; +rclcpp::Client::SharedPtr event_client; + +void PubData(StampedBasicFrame_ *frame) +{ + uint8_t i = 0; + for (; i < sizeof(segway_data_tbl)/sizeof(segway_data_tbl[0]); i++) + { + if (frame->type_id == segway_data_tbl[i].typeId) break; + } + if (i < sizeof(segway_data_tbl)/sizeof(segway_data_tbl[0])){ + *(segway_data_tbl[i].segwayTimeStamp) = frame->timestamp; + *(segway_data_tbl[i].updateFlag) =1; + memcpy( segway_data_tbl[i].dataPtr, frame->data, segway_data_tbl[i].dataSize); + } +} + +void EventPubData(int event_no) +{ + robot::Chassis::pub_event_callback(event_no); +} + +namespace robot +{ +void Chassis::pub_event_callback(int event_no) +{ + using eventServiceResponseFutrue = rclcpp::Client::SharedFuture; + auto event_request = std::make_shared(); + event_request->chassis_send_event_id = event_no; + auto event_response_receive_callback = [](eventServiceResponseFutrue futrue) { + (void)futrue; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "event sended successfully"); + }; + auto event_future_result = event_client->async_send_request(event_request, event_response_receive_callback); +} + +Chassis::Chassis(rclcpp::Node::SharedPtr nh) : node(nh) +{ + using namespace std::placeholders; + car_node = nh; + + timestamp_data.on_new_data = PubData; + aprctrl_datastamped_jni_register(×tamp_data); + event_data.event_callback = EventPubData; + aprctrl_eventcallback_jni_register(&event_data); + + node->declare_parameter("bins_directory", "/sdcard/firmware/"); + node->declare_parameter("chassis_version", "1.01"); + node->declare_parameter("route_version", "1.01"); + node->declare_parameter("connect_version", "1.01"); + + bms_fb_pub = node->create_publisher("/bms_fb", 1); + chassis_ctrl_src_fb_pub = node->create_publisher("/chassis_ctrl_src_fb", 1); + chassis_mileage_meter_fb_pub = node->create_publisher("/chassis_mileage_meter_fb", 1); + chassis_mode_fb_pub = node->create_publisher("/chassis_mode_fb", 1); + error_code_fb_pub = node->create_publisher("/error_code_fb", 1); + motor_work_mode_fb_pub = node->create_publisher("/motor_work_mode_fb", 1); + speed_fb_pub = node->create_publisher("/speed_fb", 1); + ticks_fb_pub = node->create_publisher("/ticks_fb", 1); + odom_pub = node->create_publisher("/odom", 1); + imu_pub = node->create_publisher("/imu", 1); + + event_client = node->create_client("event_srv"); + + ros_get_charge_mos_ctrl_status_cmd_server = node->create_service( + "get_charge_mos_ctrl_status", std::bind(&Chassis::ros_get_charge_mos_ctrl_status_cmd_callback, this, _1, _2)); + ros_get_load_param_cmd_server = node->create_service( + "get_load_param", std::bind(&Chassis::ros_get_load_param_cmd_callback, this, _1, _2)); + ros_get_sw_version_cmd_server = node->create_service( + "get_sw_version", std::bind(&Chassis::ros_get_sw_version_cmd_callback, this, _1, _2)); + ros_get_vel_max_feedback_cmd_server = node->create_service( + "get_vel_max_feedback", std::bind(&Chassis::ros_get_vel_max_feedback_cmd_callback, this, _1, _2)); + ros_set_charge_mos_ctrl_cmd_server = node->create_service( + "set_charge_mos_ctrl", std::bind(&Chassis::ros_set_charge_mos_ctrl_cmd_callback, this, _1, _2)); + ros_set_chassis_enable_cmd_server = node->create_service( + "set_chassis_enable", std::bind(&Chassis::ros_set_chassis_enable_cmd_callback, this, _1, _2)); + ros_set_chassis_poweroff_cmd_server = node->create_service( + "set_chassis_poweroff", std::bind(&Chassis::ros_set_chassis_poweroff_cmd_callback, this, _1, _2)); + ros_set_load_param_cmd_server = node->create_service( + "set_load_param", std::bind(&Chassis::ros_set_load_param_cmd_callback, this, _1, _2)); + ros_set_remove_push_cmd_server = node->create_service( + "set_remove_push", std::bind(&Chassis::ros_set_remove_push_cmd_callback, this, _1, _2)); + ros_set_vel_max_cmd_server = node->create_service( + "set_vel_max", std::bind(&Chassis::ros_set_vel_max_cmd_callback, this, _1, _2)); + + velocity_sub = node->create_subscription( + "cmd_vel", 1, std::bind(&Chassis::cmd_vel_callback, this, std::placeholders::_1)); + + + + iap_action_server = rclcpp_action::create_server( + node, + "iapCmd", + std::bind(&Chassis::handle_iapCmdGoal, this, _1, _2), + std::bind(&Chassis::handle_iapCmdCancel, this, _1), + std::bind(&Chassis::handle_iapCmdAccepted, this, _1)); + + odom_broadcaster = std::make_shared(node); + timer_1000hz = node->create_wall_timer(std::chrono::milliseconds(1), std::bind(&Chassis::timer_1000hz_callback, this)); + timer_1hz = node->create_wall_timer(std::chrono::milliseconds(1000), std::bind(&Chassis::timer_1hz_callback, this)); +} + +void Chassis::ros_get_charge_mos_ctrl_status_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + int16_t ret = 0; + if (request->ros_get_chassis_charge_ctrl_status == true){ + ret = get_charge_mos_ctrl_status(); + response->chassis_charge_ctrl_status = ret; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "receive RosGetChargeMosCtrlStatusCmd cmd[%d], charge_ctrl_status[%d]", + 1, ret); + } + else { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_chassis_charge_ctrl_status false"); + } +} +void Chassis::ros_get_load_param_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + if (request->ros_get_load_param == false) { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_load_param fasle"); + return ; + } + response->get_load_param = get_chassis_load_state(); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "get_load_param[%d]", response->get_load_param ); +} +void Chassis::ros_get_sw_version_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + if (request->ros_get_sw_version_cmd == false) { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_sw_version_cmd fasle"); + return; + } + response->host_version = get_host_version(); + response->central_version = get_chassis_central_version(); + response->motor_version = get_chassis_motor_version(); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_sw_version_cmd true"); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "host_version:%d, central_version:%d, motor_version:%d", + response->host_version, response->central_version, response->motor_version); +} +void Chassis::ros_get_vel_max_feedback_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + if (request->ros_get_vel_max_fb_cmd == false) { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_vel_max_fb_cmd fasle"); + return; + } + response->forward_max_vel_fb = get_line_forward_max_vel_fb(); + response->backward_max_vel_fb = get_line_backward_max_vel_fb(); + response->angular_max_vel_fb = get_angular_max_vel_fb(); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_get_vel_max_fb_cmd true"); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "forward_max_vel_fb:%d, backward_max_vel_fb:%d, angular_max_vel_fb:%d", + response->forward_max_vel_fb, response->backward_max_vel_fb, response->angular_max_vel_fb); +} +void Chassis::ros_set_charge_mos_ctrl_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + uint8_t ret; + if (request->ros_set_chassis_charge_ctrl == false) { + ret = set_charge_mos_ctrl(false); + } + else { + ret = set_charge_mos_ctrl(true); + } + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_chassis_charge_ctrl cmd[%d]", request->ros_set_chassis_charge_ctrl); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "chassis_set_charge_ctrl_result[%d]", ret); + response->chassis_set_charge_ctrl_result = ret; +} +void Chassis::ros_set_chassis_enable_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + uint8_t ret; + if (request->ros_set_chassis_enable_cmd == false) { + ret = set_enable_ctrl(0); + } + else { + ret = set_enable_ctrl(1); + } + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_chassis_enable_cmd cmd[%d]", request->ros_set_chassis_enable_cmd); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "chassis_set_chassis_enable_result[%d]", ret); + response->chassis_set_chassis_enable_result = ret; +} +void Chassis::ros_set_chassis_poweroff_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + if (request->ros_set_chassis_poweroff_cmd == false) { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_chassis_poweroff_cmd fasle"); + return; + } + uint8_t ret = set_chassis_poweroff(); + response->chassis_set_poweroff_result = ret; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "chassis_set_poweroff_result[%d]", ret); +} +void Chassis::ros_set_load_param_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + int16_t value = request->ros_set_load_param; + if (value != 0 && value != 1){ + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_load_param[%d] out of normal range ", value); + return; + } + uint8_t ret = set_chassis_load_state(value); + response->chassis_set_load_param_result = ret; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "chassis_set_load_param_result[%d]", ret); +} +void Chassis::ros_set_remove_push_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + if (request->ros_set_remove_push_cmd == false) { + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_remove_push_cmd fasle"); + return; + } + uint8_t ret = set_remove_push_cmd(); + response->chassis_set_revove_push_result = ret; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "chassis_set_revove_push_result[%d]", ret); +} +void Chassis::ros_set_vel_max_cmd_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + double forward = request->ros_set_forward_max_vel; + double backward = request->ros_set_backward_max_vel; + double angular = request->ros_set_angular_max_vel; + uint8_t ret_forw = set_line_forward_max_vel(forward); + uint8_t ret_back = set_line_backward_max_vel(backward); + uint8_t ret_angl = set_angular_max_vel(angular); + response->chassis_set_max_vel_result = ret_forw | ret_back | ret_angl; + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "ros_set_forward_max_vel[%lf], ros_set_backward_max_vel[%lf], ros_set_angular_max_vel[%lf]", + forward, backward, angular); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "set_line_forward_max_vel result[%d], set_line_backward_max_vel result[%d], set_angular_max_vel result[%d]", + ret_forw, ret_back, ret_angl); +} + +void Chassis::iapCmdExecute(const std::shared_ptr goal_handle) +{ + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "Executing goal"); + rclcpp::Rate loop_rate(1); + const auto goal = goal_handle->get_goal(); + auto feedback = std::make_shared(); + auto result = std::make_shared(); + int32_t iap_percent_fb; + + node->get_parameter("bins_directory", bins_directory); + node->get_parameter("chassis_version", chassis_version); + node->get_parameter("route_version", route_version); + node->get_parameter("connect_version", connect_version); + char bin_dir[100] = {0}; + char ver[100] = {0}; + switch (goal->iap_board) + { + case 1: + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "iap central board"); + bins_directory = bins_directory + "/central.bin"; + bins_directory.copy(bin_dir, bins_directory.length(), 0); + chassis_version.copy(ver, chassis_version.length(), 0); + IapSingerBoard(bin_dir, (char*)"central", ver); + break; + case 2: + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "iap motor board"); + bins_directory = bins_directory + "/motor.bin"; + bins_directory.copy(bin_dir, bins_directory.length(), 0); + route_version.copy(ver, route_version.length(), 0); + IapSingerBoard(bin_dir, (char*)"motor", ver); + break; + default: + RCLCPP_ERROR(rclcpp::get_logger("SmartCar"), + "iap_board value error, out of [1 2]", goal->iap_board); + result->set__iap_result(5); + goal_handle->canceled(result); + return; + } + + while (rclcpp::ok()) + { + if (goal_handle->is_canceling()) { + result->set__iap_result(5); + goal_handle->canceled(result); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "Goal canceled"); + return; + } + iap_percent_fb = getIapTotalProgress(); + feedback->set__iap_percent(iap_percent_fb); + goal_handle->publish_feedback(feedback); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "iap percent: %d", iap_percent_fb); + loop_rate.sleep(); + if (iap_percent_fb == 100) { + RCLCPP_INFO_ONCE(rclcpp::get_logger("SmartCar"), "iap successful"); + break; + } else if (iap_percent_fb < 0) { + RCLCPP_INFO_ONCE(rclcpp::get_logger("SmartCar"), "iap failed"); + break; + } + } + + if (rclcpp::ok()) { + if (iap_percent_fb == 100) { + result->set__iap_result(3); + goal_handle->succeed(result); + RCLCPP_INFO(rclcpp::get_logger("SmartCar"), "goal succeeded, iap succeeded"); + } else { + result->set__iap_result(getHostIapResult()); + result->set__error_code(getHostIapErrorCode()); + goal_handle->succeed(result); + RCLCPP_ERROR(rclcpp::get_logger("SmartCar"), "goal failed, iap failed"); + } + } +} + +void Chassis::cmd_vel_callback(const geometry_msgs::msg::Twist::SharedPtr msg) const +{ + double angular_vel = msg->angular.z; + double linear_vel = msg->linear.x; + angular_vel = (angular_vel > 3.0 ? 3.0 : (angular_vel < -3.0 ? -3.0 : angular_vel)); + linear_vel = (linear_vel > 3.0 ? 3.0 : (linear_vel < -1.0 ? -1.0 : linear_vel)); + + set_cmd_vel(linear_vel, angular_vel); + // printf("vl:%lf, va:%lf\n", linear_vel, angular_vel); +} + +void Chassis::timer_1hz_callback(void) +{ + bms_fb.bat_soc = get_bat_soc(); + bms_fb.bat_charging = get_bat_charging(); + bms_fb.bat_vol = get_bat_mvol(); + bms_fb.bat_current = get_bat_mcurrent(); + bms_fb.bat_temp = get_bat_temp(); + bms_fb_pub->publish(bms_fb); + + chassis_ctrl_src_fb.chassis_ctrl_cmd_src = get_ctrl_cmd_src(); + chassis_ctrl_src_fb_pub->publish(chassis_ctrl_src_fb); + + chassis_mileage_meter_fb.vehicle_meters = get_vehicle_meter(); + chassis_mileage_meter_fb_pub->publish(chassis_mileage_meter_fb); + + chassis_mode_fb.chassis_mode = get_chassis_mode();//0-lock_mode; 1-ctrl_mode; 2-push_mode; 3-emergency_mode; 4-error_mode + chassis_mode_fb_pub->publish(chassis_mode_fb); + + error_code_fb.host_error = get_err_state(Host); + error_code_fb.central_error = get_err_state(Central); + error_code_fb.left_motor_error = get_err_state(Motor) & 0xffff; + error_code_fb.right_motor_error = (get_err_state(Motor) >> 16) & 0xffff; + error_code_fb.bms_error = get_err_state(BMS); + error_code_fb_pub->publish(error_code_fb); + + motor_work_mode_fb.motor_work_mode = get_chassis_work_model(); + motor_work_mode_fb_pub->publish(motor_work_mode_fb); +} + +void Chassis::timer_1000hz_callback(void) +{ + speed_pub_callback(); + ticks_pub_callback(); + imu_pub_callback(); + pub_odom_callback(); +} + +void Chassis::speed_pub_callback(void) +{ + if (Speed_update == 1) { + Speed_update = 0; + speed_fb.car_speed = SpeedData.car_speed; + speed_fb.car_speed /= LINE_SPEED_TRANS_GAIN_MPS; + speed_fb.turn_speed = SpeedData.turn_speed; + speed_fb.turn_speed /= ANGULAR_SPEED_TRANS_GAIN_RADPS; + speed_fb.l_speed = SpeedData.l_speed; + speed_fb.l_speed /= LINE_SPEED_TRANS_GAIN_MPS; + speed_fb.r_speed = SpeedData.r_speed; + speed_fb.r_speed /= LINE_SPEED_TRANS_GAIN_MPS; + speed_fb.speed_timestamp = Speed_TimeStamp; + speed_fb_pub->publish(speed_fb); + } +} + +void Chassis::ticks_pub_callback(void) +{ + if (Tick_update == 1) { + Tick_update = 0; + ticks_fb.l_ticks = TickData.l_ticks; + ticks_fb.r_ticks = TickData.r_ticks; + ticks_fb.ticks_timestamp = Tick_TimeStamp; + ticks_fb_pub->publish(ticks_fb); + } +} + +void Chassis::imu_pub_callback(void) +{ + if (ImuGyro_update == 1 && ImuAcc_update == 1){ + ImuGyro_update = 0; + ImuAcc_update = 0; + imu_fb.header.stamp = node->now(); + imu_fb.header.frame_id = "base_link"; + imu_fb.angular_velocity.x = (double)ImuGyroData.gyr[0] / 900.0; + imu_fb.angular_velocity.y = (double)ImuGyroData.gyr[1] / 900.0; + imu_fb.angular_velocity.z = (double)ImuGyroData.gyr[2] / 900.0; + imu_fb.linear_acceleration.x = (double)ImuAccData.acc[0] / 4000.0 * 9.8; + imu_fb.linear_acceleration.y = (double)ImuAccData.acc[1] / 4000.0 * 9.8; + imu_fb.linear_acceleration.z = (double)ImuAccData.acc[2] / 4000.0 * 9.8; + imu_pub->publish(imu_fb); + } +} + +void Chassis::pub_odom_callback(void) +{ + if ((OdomPoseXy_update & OdomEulerXy_update & OdomEulerZ_update & OdomVelLineXy_update) == 1) { + OdomPoseXy_update = 0, OdomEulerXy_update = 0, OdomEulerZ_update = 0, OdomVelLineXy_update = 0; + + odom_quat.setRPY(0, 0, OdomEulerZ.euler_z / RAD_DEGREE_CONVER); + odom_trans.header.stamp = node->now(); + odom_trans.header.frame_id = "odom"; + odom_trans.child_frame_id = "base_link"; + odom_trans.transform.translation.x = OdomPoseXy.pos_x; + odom_trans.transform.translation.y = OdomPoseXy.pos_y; + odom_trans.transform.translation.z = 0.0; + odom_trans.transform.rotation.x = odom_quat.x(); + odom_trans.transform.rotation.y = odom_quat.y(); + odom_trans.transform.rotation.z = odom_quat.z(); + odom_trans.transform.rotation.w = odom_quat.w(); + odom_broadcaster->sendTransform(odom_trans); + + odom_fb.header.stamp = node->now(); + odom_fb.header.frame_id = "odom"; + odom_fb.pose.pose.position.x = OdomPoseXy.pos_x; + odom_fb.pose.pose.position.y = OdomPoseXy.pos_y; + odom_fb.pose.pose.position.z = 0.0; + odom_fb.pose.pose.orientation.x = odom_quat.x(); + odom_fb.pose.pose.orientation.y = odom_quat.y(); + odom_fb.pose.pose.orientation.z = odom_quat.z(); + odom_fb.pose.pose.orientation.w = odom_quat.w(); + + odom_fb.child_frame_id = "base_link"; + odom_fb.twist.twist.linear.x = (double)SpeedData.car_speed / LINE_SPEED_TRANS_GAIN_MPS; + odom_fb.twist.twist.linear.y = 0; + odom_fb.twist.twist.angular.z = (double)SpeedData.turn_speed / ANGULAR_SPEED_TRANS_GAIN_RADPS;; + odom_pub->publish(odom_fb); + } +} + +} diff --git a/src/segwayrmp/tools/drive_segway_sample.cpp b/src/segwayrmp/tools/drive_segway_sample.cpp new file mode 100755 index 0000000..a9568e0 --- /dev/null +++ b/src/segwayrmp/tools/drive_segway_sample.cpp @@ -0,0 +1,364 @@ +#include "segwayrmp/robot.h" +#include +#include +#include +#include +#include +#include +#include + +#define PRINTHELP 'h' +#define ADDLINEVEL 'w' +#define DECLINEVEL 's' +#define ADDANGULARVEL 'a' +#define DECANGULARVEL 'd' +#define PRINTCURVEL 'f' +#define VELRESETZERO 'g' +#define ENABLECMD 'e' +#define CHASSISPAUSE 'q' +// #define CLEARSCRAM 'c' +// #define GETERROR 'x' +#define IAPCENTRAL 'v' +#define IAPMOTOR 'b' +#define PRINTERRSW 'r' + +using iapCmd = segway_msgs::action::RosSetIapCmd; +using goalHandleIapCmd = rclcpp_action::ClientGoalHandle; + +std::shared_ptr drive_node; +rclcpp::Publisher::SharedPtr velocity_pub; +rclcpp::Subscription::SharedPtr error_sub; + +rclcpp::Client::SharedPtr enable_client; +// rclcpp::Client::SharedPtr clear_scram_client; +// rclcpp::Client::SharedPtr get_err_client; +rclcpp::Service::SharedPtr event_server; + +rclcpp_action::Client::SharedPtr iap_client; +uint8_t print_error = 0; + +char const* print_help() { + char const* printHelp = + "\t h : Displays the required keys and their meaning\n" + "\t w : Increase forward speed by 0.1m/s\n" + "\t s : Decrease forward speed by 0.1m/s\n" + "\t a : Increase the angular velocity by 0.1rad/s\n" + "\t d : Decrease the angular velocity by 0.1rad/s\n" + "\t f : Displays current speed Settings\n" + "\t g : Speed reset to zero\n" + "\t e : Chassis enable switch\n" + "\t q : Running pause. Click 'q'key again to resume running by the previous speed. W/S/A/D keys can also restore chassis running\n" + "\t v : Iap the central board, please put the bin file in /sdcard/firmware/\n" + "\t b : Iap the motor board, please put the bin file in /sdcard/firmware/\n" + "\t r : Open or close the switch: printing error code\n" + "\t others : Do nothing\n"; + return printHelp; +} + +void changemode(int dir) +{ + static struct termios oldt, newt; + + if ( dir == 1 ) + { + tcgetattr( STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~( ICANON | ECHO ); + tcsetattr( STDIN_FILENO, TCSANOW, &newt); + } + else + tcsetattr( STDIN_FILENO, TCSANOW, &oldt); +} + +int kbhit (void) +{ + struct timeval tv; + fd_set rdfs; //一组fd集合 + + tv.tv_sec = 0; + tv.tv_usec = 0; //时间为0,非阻塞 + + FD_ZERO(&rdfs); //fd集合清空 + FD_SET (STDIN_FILENO, &rdfs); //增加新的fd + + select(STDIN_FILENO+1, &rdfs, NULL, NULL, &tv); //非阻塞检测fd为0的tty读取状态,rdfs特定位置1 + return FD_ISSET(STDIN_FILENO, &rdfs); //判断指定的标准输入fd是否在rdfs集合中 +} + +static int scanKeyboard() +{ + int input_char = 0; + struct termios new_settings; + struct termios stored_settings; + tcgetattr(0, &stored_settings); + new_settings = stored_settings; + new_settings.c_lflag &= (~ICANON); //非规范模式:每次返回单个字符 + new_settings.c_cc[VTIME] = 0; + tcgetattr(0,&stored_settings); + new_settings.c_cc[VMIN] = 1; //读取的最小字节数 + tcsetattr(0, TCSANOW, &new_settings); + + changemode(1); + if (kbhit()) { + input_char = getchar(); + printf("\n"); + } + changemode(0); + + tcsetattr(0, TCSANOW, &stored_settings); + return input_char; +} + +char get_keyboard() +{ + char keyvalue = scanKeyboard(); + return keyvalue; +} + +void goal_response_callback(std::shared_future future) +{ + auto goal_handle = future.get(); + if (!goal_handle) { + RCLCPP_ERROR(rclcpp::get_logger("drive_segway_sample"), "Goal was rejected by server"); + } else { + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "Goal accepted by server, waiting for result"); + } +} + +void feedback_callback( + goalHandleIapCmd::SharedPtr, + const std::shared_ptr feedback) +{ + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "IAP process percentage:[%d]", feedback->iap_percent); +} + +void result_callback(const goalHandleIapCmd::WrappedResult & result) +{ + switch (result.code) { + case rclcpp_action::ResultCode::SUCCEEDED: + break; + case rclcpp_action::ResultCode::ABORTED: + RCLCPP_ERROR(rclcpp::get_logger("drive_segway_sample"), "Goal was aborted"); + return; + case rclcpp_action::ResultCode::CANCELED: + RCLCPP_ERROR(rclcpp::get_logger("drive_segway_sample"), "Goal was canceled"); + return; + default: + RCLCPP_ERROR(rclcpp::get_logger("drive_segway_sample"), "Unknown result code"); + return; + } + if (result.result->iap_result == 3) { + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "iap success!"); + } else { + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "iap fail!, error_code[%#x]", result.result->error_code); + } +} + +void drive_chassis_test() +{ + static uint16_t set_enable_cmd = 1; + uint8_t enable_switch = 0; + static double set_line_speed; + static double set_angular_speed; + static double send_line_speed; + static double send_angular_speed; + static uint8_t chassis_pause = 0; + // uint8_t clear_scram_flag = 0; + // uint8_t get_err_flag = 0; + uint8_t iap_flag = 0; + + auto enable_request = std::make_shared(); + // auto clear_scram_requst = std::make_shared(); + // auto get_err_request = std::make_shared(); + + char keyvalue = get_keyboard(); + switch (keyvalue) + { + case PRINTHELP: + printf("%s\n", print_help()); + break; + case ADDLINEVEL : + set_line_speed += 0.1; + send_line_speed = set_line_speed; + send_angular_speed = set_angular_speed; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case DECLINEVEL : + set_line_speed -= 0.1; + send_line_speed = set_line_speed; + send_angular_speed = set_angular_speed; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case ADDANGULARVEL : + set_angular_speed += 0.1; + send_line_speed = set_line_speed; + send_angular_speed = set_angular_speed; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case DECANGULARVEL : + set_angular_speed -= 0.1; + send_line_speed = set_line_speed; + send_angular_speed = set_angular_speed; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case PRINTCURVEL : + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case VELRESETZERO : + set_line_speed = 0; + set_angular_speed = 0; + send_line_speed = 0; + send_angular_speed = 0; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case ENABLECMD : + enable_switch = 1; + enable_request->ros_set_chassis_enable_cmd = set_enable_cmd; + ++set_enable_cmd; + set_enable_cmd %= 2; + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), + "enable chassis switch[%d]", enable_request->ros_set_chassis_enable_cmd); + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + break; + case CHASSISPAUSE : + ++chassis_pause; + chassis_pause %= 2; + if (chassis_pause) { + send_line_speed = 0; + send_angular_speed = 0; + printf("Stop the chassis temporarily\n"); + } else { + send_line_speed = set_line_speed; + send_angular_speed = set_angular_speed; + printf("current set_line_speed[%lf], set_angular_speed[%lf]\n", set_line_speed, set_angular_speed); + } + break; + // case CLEARSCRAM : + // // clear_scram_flag = 1; + // break; + // case GETERROR: + // // get_err_flag = 1; + // break; + case IAPCENTRAL: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "iap chassis"); + iap_flag = 1; + break; + case IAPMOTOR: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "iap route"); + iap_flag = 2; + break; + case PRINTERRSW: + print_error = ~print_error; + break; + default: + break; + } + + geometry_msgs::msg::Twist cmd_vel; + cmd_vel.linear.x = send_line_speed; + cmd_vel.angular.z = send_angular_speed; + velocity_pub->publish(cmd_vel); + + if (enable_switch){ + using enableServiceResponseFutrue = rclcpp::Client::SharedFuture; + auto enable_response_receive_callback = [](enableServiceResponseFutrue futrue) { + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), + "event sended successfully, result:%d", futrue.get()->chassis_set_chassis_enable_result); + }; + auto enable_future_result = enable_client->async_send_request(enable_request, enable_response_receive_callback); + } + + // if (clear_scram_flag) { + // using clearServiceResponseFuture = rclcpp::Client::SharedFuture; + // auto clear_response_receive_callback = [](clearServiceResponseFuture future) { + // RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), + // "clear scram status successfully, result:%d", future.get()->clear_scram_result); + // }; + // auto clear_future_result = clear_scram_client->async_send_request(clear_scram_requst, clear_response_receive_callback); + // } + + // if (get_err_flag) { + // using errorServiceResponseFuture = rclcpp::Client::SharedFuture; + // auto error_response_receive_callback = [](errorServiceResponseFuture future) { + // RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), + // "chassis_error_code[%d], route_error_code[%d], connect_error_code[%d]", + // future.get()->chassis_error_code, + // future.get()->route_error_code, + // future.get()->connect_error_code); + // }; + // auto error_future_result = get_err_client->async_send_request(get_err_request, error_response_receive_callback); + // } + + if (iap_flag & 3) { + auto goal_msg = iapCmd::Goal(); + goal_msg.iap_board = iap_flag; + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "sending goal, iap cmd goal"); + auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + send_goal_options.goal_response_callback = std::bind(&goal_response_callback, std::placeholders::_1); + send_goal_options.feedback_callback = std::bind(&feedback_callback, std::placeholders::_1, std::placeholders::_2); + send_goal_options.result_callback = std::bind(&result_callback, std::placeholders::_1); + iap_client->async_send_goal(goal_msg, send_goal_options); + } +} + +void get_error_code_callback(const segway_msgs::msg::ErrorCodeFb::SharedPtr msg) +{ + if (print_error != 0) { + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "host_error[%#x], central_error[%#x], \ + left_motor_error[%#x], right_motor_error[%#x], bms_err[%#x]", + msg->host_error, msg->central_error, msg->left_motor_error, msg->right_motor_error, msg->bms_error); + } +} + +void get_chassis_event_callback(const std::shared_ptr request, + std::shared_ptr response) +{ + (void)response; + switch (request->chassis_send_event_id) + { + case OnEmergeStopEvent: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "CHASSIS EVENT: The chassis emergency stop button is triggered"); + break; + case OutEmergeStopEvent: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "CHASSIS EVENT: OThe chassis emergency stop button recover"); + break; + case PadPowerOffEvent: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "CHASSIS EVENT: The chassis will power off"); + break; + case OnLockedRotorProtectEvent: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "CHASSIS EVENT: the chassis motor locked-rotor"); + break; + case OutLockedRotorProtectEvent: + RCLCPP_INFO(rclcpp::get_logger("drive_segway_sample"), "CHASSIS EVENT: the chassis motor no longer locked-rotor"); + break; + default: + break; + } +} + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + drive_node = rclcpp::Node::make_shared("drive_segway_sample"); + + velocity_pub = drive_node->create_publisher("cmd_vel", 1); + error_sub = drive_node->create_subscription( + "error_code_fb", 1, std::bind(&get_error_code_callback, std::placeholders::_1)); + + enable_client = drive_node->create_client("set_chassis_enable"); + // clear_scram_client = drive_node->create_client("clear_scram_status_srv"); + // get_err_client = drive_node->create_client("get_error_srv"); + event_server = drive_node->create_service( + "event_srv", std::bind(&get_chassis_event_callback, std::placeholders::_1, std::placeholders::_2)); + + iap_client = rclcpp_action::create_client(drive_node, "iapCmd"); + + rclcpp::TimerBase::SharedPtr timer_100hz = + drive_node->create_wall_timer(std::chrono::milliseconds(10), &drive_chassis_test); + + printf("%s\n", print_help()); + + rclcpp::spin(drive_node); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file