From db2c6b2abecb9965d2259fb0055ae283652c1b51 Mon Sep 17 00:00:00 2001 From: Jonas Eschmann Date: Wed, 14 Jan 2026 09:47:47 -0800 Subject: [PATCH] feature: Integrating the RAPTOR foundation policy (#26082) * moving raptor bump compiles and raptor mode appears hovering with RAPTOR seems to work Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing simplified rotmat runtime inference frequency multiple arming request response reflects actual readiness adjusting to fit IMU gyro ratemax relaxing control timing warning thresholds for SITL Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD adopting new "request_offboard_setpoint" in raptor module replace offboard seems good mc_raptor: overwrite offboard parameter separate raptor config addendum Raptor off by default RAPTOR readme Loading raptor checkpoint from tar works. check if load was successful refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first adapter not needed anymore ripping out test observation mode (not used in a long time) fixing warnings bump RLtools to fix the remaining warnings Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C embedding Raptor policy into flash works again also printing checkpoint name when using the embedded policy cleaner handling of the checkpoint name back to reading from file ripping out visual odometry checks cleaner more debug but no success bump rlt bump pre next rebase we can publish the no angvel update because we latch onto it with the scheduled work item anyways this kind of runs on the 6c still bad SIH almost flying saving stale traj setpoint yaw new error. timestamp not the problem anymore bump rlt; SIH works with executor shaping up bumping blob (include tar checkpoint) cleaning up fixing formatting update readme * moving raptor bump compiles and raptor mode appears hovering with RAPTOR seems to work Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing simplified rotmat runtime inference frequency multiple arming request response reflects actual readiness adjusting to fit IMU gyro ratemax relaxing control timing warning thresholds for SITL Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD adopting new "request_offboard_setpoint" in raptor module replace offboard seems good mc_raptor: overwrite offboard parameter separate raptor config addendum Raptor off by default RAPTOR readme Loading raptor checkpoint from tar works. check if load was successful refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first adapter not needed anymore ripping out test observation mode (not used in a long time) fixing warnings bump RLtools to fix the remaining warnings Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C embedding Raptor policy into flash works again also printing checkpoint name when using the embedded policy cleaner handling of the checkpoint name back to reading from file ripping out visual odometry checks cleaner more debug but no success bump rlt bump pre next rebase we can publish the no angvel update because we latch onto it with the scheduled work item anyways this kind of runs on the 6c still bad SIH almost flying saving stale traj setpoint yaw new error. timestamp not the problem anymore bump rlt; SIH works with executor shaping up bumping blob (include tar checkpoint) cleaning up fixing formatting update readme updating gitignore * fixing format and declaring submodules as cmake dependencies * adding uORB message documentation * fixing comment alignment * Adding option to restrict mc_raptor to not listen to the trajectory_setpoint (use the position and yaw at activation time as reference instead) * bump RLtools; relax timing thresholds and adding real world readme * smooth traj tracking performance * Measuring trajectory_setpoint timing (providing stats in raptor_status); reverting accidental .gitignore modification * More ideomatic way of setting the path to the policy checkpoint * Reset trajectory_setpoint on raptor mode activation * Adding internal trajectory generation (feeding trajectory_setpoint over Mavlink is too noisy). Quite agile trajectory tracking, good performance * stable flight * Update msg/versioned/RaptorInput.msg Co-authored-by: Hamish Willee * adopting message formatting conventions * sort raptor.px4board * Archiving RegisterExtComponentRequestV1.msg * Add message versioning for VehicleStatus v2 and RegisterExtComponentRequest v2 * fixing formatting * making internal reference configurable via command * RAPTOR docs wip * raptor internal reference documentation * Finishing RAPTOR docs first draft * adding logging instructions * Fixing missing command documentation test error * fixing format * adding motor layout warning * raptor minimal subedit - prettier, images etc * Improve intro * Fix up Neural_Networks version * Mentioning "Adaptive" in the RAPTOR documentation's title * Adding clarifications about the internal reference trajectory generator * Removing "foundation policy" wording * Fixing new-line check * Removing redundant (evident through directory hierarchy) raptor_ from filenames * Unifying Neural Network docs (mc_nn_control and mc_raptor) under the "Neural Network" topic * Fix to standard structure * Making the distinction between mc_nn_control and mc_raptor more clear and fixing the comparison table * Removing trajectory_setpoint forwarding flag from external mode registration request and from the vehicle status * Trivial layout and wording fixes * fixing docs error --------- Co-authored-by: Hamish Willee --- .gitmodules | 6 + .vscode/cmake-variants.yaml | 10 + ROMFS/px4fmu_common/init.d/rc.mc_apps | 6 + boards/px4/fmu-v6c/raptor.px4board | 95 ++ boards/px4/sitl/raptor.px4board | 89 ++ .../neural_networks/raptor/method.jpg | Bin 0 -> 563707 bytes .../raptor/results_figure_eight.svg | 1 + .../neural_networks/raptor/results_line.svg | 1 + .../raptor/visual_abstract.jpg | Bin 0 -> 208973 bytes docs/en/SUMMARY.md | 8 +- docs/en/advanced/neural_networks.md | 120 +- docs/en/neural_networks/index.md | 21 + .../mc_neural_network_control.md | 119 ++ .../nn_module_utilities.md | 4 +- docs/en/neural_networks/raptor.md | 221 ++++ docs/en/{advanced => neural_networks}/tflm.md | 4 +- msg/CMakeLists.txt | 2 + msg/versioned/RaptorInput.msg | 18 + msg/versioned/RaptorStatus.msg | 46 + src/lib/CMakeLists.txt | 1 + src/lib/rl_tools/CMakeLists.txt | 15 + src/lib/rl_tools/Kconfig | 7 + src/lib/rl_tools/rl_tools | 1 + src/modules/mc_raptor/CHECKLIST.md | 3 + src/modules/mc_raptor/CMakeLists.txt | 21 + src/modules/mc_raptor/Kconfig | 12 + src/modules/mc_raptor/README.md | 116 ++ src/modules/mc_raptor/blob | 1 + src/modules/mc_raptor/mc_raptor.cpp | 1077 +++++++++++++++++ src/modules/mc_raptor/mc_raptor.hpp | 283 +++++ src/modules/mc_raptor/module.yaml | 43 + .../mc_raptor/trajectories/lissajous.hpp | 38 + .../mc_raptor/trajectories/trajectory.hpp | 6 + 33 files changed, 2269 insertions(+), 126 deletions(-) create mode 100644 boards/px4/fmu-v6c/raptor.px4board create mode 100644 boards/px4/sitl/raptor.px4board create mode 100644 docs/assets/advanced/neural_networks/raptor/method.jpg create mode 100644 docs/assets/advanced/neural_networks/raptor/results_figure_eight.svg create mode 100644 docs/assets/advanced/neural_networks/raptor/results_line.svg create mode 100644 docs/assets/advanced/neural_networks/raptor/visual_abstract.jpg create mode 100644 docs/en/neural_networks/index.md create mode 100644 docs/en/neural_networks/mc_neural_network_control.md rename docs/en/{advanced => neural_networks}/nn_module_utilities.md (97%) create mode 100644 docs/en/neural_networks/raptor.md rename docs/en/{advanced => neural_networks}/tflm.md (90%) create mode 100644 msg/versioned/RaptorInput.msg create mode 100644 msg/versioned/RaptorStatus.msg create mode 100644 src/lib/rl_tools/CMakeLists.txt create mode 100644 src/lib/rl_tools/Kconfig create mode 160000 src/lib/rl_tools/rl_tools create mode 100644 src/modules/mc_raptor/CHECKLIST.md create mode 100644 src/modules/mc_raptor/CMakeLists.txt create mode 100644 src/modules/mc_raptor/Kconfig create mode 100644 src/modules/mc_raptor/README.md create mode 160000 src/modules/mc_raptor/blob create mode 100644 src/modules/mc_raptor/mc_raptor.cpp create mode 100644 src/modules/mc_raptor/mc_raptor.hpp create mode 100644 src/modules/mc_raptor/module.yaml create mode 100644 src/modules/mc_raptor/trajectories/lissajous.hpp create mode 100644 src/modules/mc_raptor/trajectories/trajectory.hpp diff --git a/.gitmodules b/.gitmodules index 4061b65c11..86cb85c961 100644 --- a/.gitmodules +++ b/.gitmodules @@ -103,3 +103,9 @@ [submodule "src/drivers/ins/sbgecom/sbgECom"] path = src/drivers/ins/sbgecom/sbgECom url = https://github.com/PX4/sbgECom.git +[submodule "src/modules/mc_raptor/blob"] + path = src/modules/mc_raptor/blob + url = https://github.com/rl-tools/px4-blob +[submodule "src/lib/rl_tools/rl_tools"] + path = src/lib/rl_tools/rl_tools + url = https://github.com/rl-tools/rl-tools.git diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 4b2c95eb34..461ce2d95b 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -6,6 +6,16 @@ CONFIG: buildType: RelWithDebInfo settings: CONFIG: px4_sitl_default + px4_sitl_raptor: + short: px4_sitl_raptor + buildType: RelWithDebInfo + settings: + CONFIG: px4_sitl_raptor + px4_sitl_raptor_debug: + short: px4_sitl_raptor_debug + buildType: Debug + settings: + CONFIG: px4_sitl_raptor px4_sitl_spacecraft: short: px4_sitl_spacecraft buildType: RelWithDebInfo diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps index adff4e963f..24a3f81ed7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_apps +++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps @@ -41,3 +41,9 @@ if param compare -s MC_NN_EN 1 then mc_nn_control start fi + + +if param compare -s MC_RAPTOR_ENABLE 1 +then + mc_raptor start +fi diff --git a/boards/px4/fmu-v6c/raptor.px4board b/boards/px4/fmu-v6c/raptor.px4board new file mode 100644 index 0000000000..be07cafcbe --- /dev/null +++ b/boards/px4/fmu-v6c/raptor.px4board @@ -0,0 +1,95 @@ +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_ACTUATORS_VERTIQ_IO=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_BOSCH_BMI055=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_LIB_RL_TOOLS=y +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RAPTOR=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y +CONFIG_USE_IFCI_CONFIGURATION=y diff --git a/boards/px4/sitl/raptor.px4board b/boards/px4/sitl/raptor.px4board new file mode 100644 index 0000000000..b00735efc2 --- /dev/null +++ b/boards/px4/sitl/raptor.px4board @@ -0,0 +1,89 @@ +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_ROOT_PATH="." +CONFIG_BOARD_TESTING=y +CONFIG_COMMON_SIMULATION=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_EKF2_VERBOSE_STATUS=y +CONFIG_EXAMPLES_DYN_HELLO=y +CONFIG_EXAMPLES_FAKE_GPS=y +CONFIG_EXAMPLES_FAKE_IMU=y +CONFIG_EXAMPLES_FAKE_MAGNETOMETER=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y +CONFIG_EXAMPLES_PX4_SIMPLE_APP=y +CONFIG_EXAMPLES_WORK_ITEM=y +CONFIG_FIGURE_OF_EIGHT=y +CONFIG_LIB_RL_TOOLS=y +CONFIG_MAVLINK_DIALECT="development" +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_MODULES_AIRSHIP_ATT_CONTROL=y +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RAPTOR=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_PAYLOAD_DELIVERER=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_REPLAY=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_GZ_BRIDGE=y +CONFIG_MODULES_SIMULATION_GZ_MSGS=y +CONFIG_MODULES_SIMULATION_GZ_PLUGINS=y +CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM=y +CONFIG_MODULES_SPACECRAFT=n +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=10000 +CONFIG_PLATFORM_POSIX=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DYN=y +CONFIG_SYSTEMCMDS_FAILURE=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SHUTDOWN=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/docs/assets/advanced/neural_networks/raptor/method.jpg b/docs/assets/advanced/neural_networks/raptor/method.jpg new file mode 100644 index 0000000000000000000000000000000000000000..935da7683d46018dd3062f78c4273ed6b6628127 GIT binary patch literal 563707 zcmdqJcUTk48!);71w|1B0Y#dkBGN>fbPy2{0YQ52Js=Q5FIGeZR0O1>G^O|6q=nvl zRa)o)5<gPG2A=zi|69{pH*LpVRLe;M@rk`*TXfkShSu zISBDN$nQFU9t4nx7=nZKD3OpJJAQ(g2=aRvI637{kAtoZytone#m=3%!jw$^roF8Wt?j z`|AbvmHC)Gj^4bo+#icMvW9WqP$Y;?OR1b({qEiUP-*^}dooEac zL7aecqpUbB3DC%J4t{6&a4_<8=EfJH6>z@bAPXW6 zkDSCcTxzEB+;?Z^G_qfX+ybOr=O<>rmX4ZML-+d}$Q3zgzLvJ;U*Wk3&pa1rH@m=| zRC4Z3OZLx;*cF@h^dLKP9wAsUNJp83vaF>}z=>KIj(PO}?a&LKQd0eeg6h64i~Tyl zpJvSd#@fNq7mw_mM!w+TlE$Jw@nZ+D=LoYwn3;}v3AFBh@%qQ15^5JQnM@mX2aSxH zQxJtE8U}+1{!~%h5=$ItKk-oBvi8!4CY5Pu`?uK?eyTHlKq6C>TbtHDeV>J8C(DsD zqeMp55^2_?`R8@0|9w3!T&&j$6jmi`!jg`+UE*IS98k>py3@hk{9G^<@ zd9N=#WVD4nen~SRFY#x&^Ofacs@P3!75gC^R(%<1^@kmD~LU@yX~jk*UO zNq=y@?xNRLLRmJrn6C935L?MltjfFPDmQ^)#pQzwDoS3*@@Cs{fznOvOFnRa1P3EZ zdF1WHN3pW9iO|%po^U3fCncIm=*~VIL@rbxnWYm~g6MiT#B!9^X9sd!U*+~!q@1N( zoL3UpPL-9{6RigkbuFbw_o^`EE=Wb=54foVSLiEdymSoW!7M<^^B^l5yiPw{S+ATN zT_cLZ%AD+Q(PZC65Fdf|w3mUcQOafadh;jOD93j^Jbiim7u&s-EoCtf=Z2Z!G-wO$d9w`6 zaQqF-;rZp&ljaew`080!m=nL64Xlb+4IZw(e$6H3soYZ`6tt(_IhzsS9j&px1)N(Al86mi;3pG#BUNRWbOFNuP$p!@IXslWZN$4^|j?MMI|wR zA}+BR2bI(EsSXvpPj8+4itHZeR}}P?r>W`bk=DrX__XFUG0D~30F}viHydbAX^=_t zilS4BnHUQNQUfkiyw>-`YZU;T&c6jo2b$8^j!QusIFbSM^;asZK{oloo;|)X8v7Di zLTl&ia303MCajMLCk02l`Trp3H zb97;-9jaJdzAz=nhU|L#A}!C8ij!WxLc?hQpEq-%aBwH6eaBxu2f0hjspCQ4S^b32 zwSdfA8*7@n#mak`J3*sYc(~hjU2KV?n-D6!I7SM?-}4o(ywB)=gPv+@ z?b6T6=ebO$NzH5QJaI+Cixc)u(IZEAxlVb!{?pSC9IFvZ34KoQCUVc?p944*r~|T+ zWx|gL+#G0sQsnxpbk4Fb&BOZjDQx2}D@Q>Uo^=K!6zW24sWH;wlVD=9s9VhFDDR8G zZf{B#yB6HcD>ra3K1t*B$Z1uMEl9)l+;hD+R>lRm*fst|5kRsetpQmsi6hb3RA3<6A0V`e&uZ-?Vb-o}9Xtub^^_=8dy{{l`iPtyh^>Xp__H}8(PF}TJulTLVU|uSoT=)S?@yy@^z52mw z4b-@JQ`-h&?l%y!c;;ngFRR$#p}M0Mae&P|U+bx=1zFLVJ|Kj@j9Wp$f56jUZ-b#2 zw2^g-MdxHaXq0iv@u=t?EY;ycs|aEPG}i#qIvoglX779g0#Y)e=o}ZPixQ`X;ezlE z0Xq}QC7@?fF2k^-)q|(RmWQ-gXVl8C{?(8&xNf~7=Gtb)FIJ!RYw$A(SvXRS0xM(T zfJl+)-wKb}vkU2{Z-^tyAFfDe_!wzN6xVpiAIAJC=on$HVP|d@_LLtBw~UN{mI0a-g6 z(0=T7Jkn=ioZY!QJTFe^vWt6G%01ekm;?GG^f$L`f3gEkpm}Z( zCC)MuO1^SAsx>I)g{7>RwJvPwv8VkzQ}#Lo=kpHTHNEeRENh zmaD9g8vzzUl1|PK03y^l|Bp}r8IhLwqho1;Rm)oJOHhG=9M|8xSLOwZ>XRZ`MKr^m z1sxllMz?Vw37e=)7)AF{>fg_V?k=PwBjVIG%Ij9f-v2+#&FsEl%CzoEegFFFqHoLX z_cB+~s;qF#pIV|})>q}3@_j*vtPX!s`QyFk6H?9ccjjJFi7_gL0F_-%sNNvM;T z2|>fj+TA$PY5&r2pVp$jT`TW8iIX4DH4_*kx8K2Wo1N7XO_(z@>7kQ;%Xd>XlDuSa zu@Hrsrj3X}05hPGKo?NmT==ZSBch@~HCdZ)Haz|h1-D}#aR^ErUepMZBpg{Y;`^66 z`@a!vSr+};#jb}QdnTcX;HiOF1&v7gwqpwAO2sgMQxlEc3=hhj>83=fMi7~~hyKEU zh*5h9T?wdZa3sG0gc70Wk$ z=LD|8*E+FUeIJ2*%8e{wmH|5=tP64Zcy>Um}PMg-zvNI{^9w z2_j!JUE;0{5J3k;`xJLw!v!DVP2%Vo@i(V7EQxVa$1f+zo||w1 z5UqPNaF-a`%EC`!)ZyG#sjihfy&>iEbGnra?^K5uwb|3++MiLT=h+R0T9g;5hEW$) z`Kx=hz;peTSeu87S}Q%R277ny$wG$pVZGu8cHQ!G8SK;jJ(!xr@a|lHd5&KR-=sM5 zLJ6SW+}X9VR$DC1?9x)fP!bac%uNjMCFB`GxzVZdj+$OlPB75go}XS<1R!!o71IKY zPt`*=Kh5@HKnB5%Hl(NzU(=e^OLvc?jWKWc<5Sru_ssszKN6vJ59zdYQ_kxUHR{Sj zqubJ4<;!Y3$%QF~f9alMq><&B0o8acA39$6{NW#cUTHpyZpT!A;p0E6|H#u%y|SNk zOCbH0(MhPqJ5C@c^WTcq@5fHRJE|oth)>A!Y>#gG;w%5LVkR^*cEH@yt@uX_fp7!= zPy9Zu%XWh{o=^qB`&WjzML!o~>|wJb=aG0eSR@v7Cc$**JRUZ{Ur1xTPB&+p#s69N zN1kklF1F2=P(egaA1?0;Tu}?_p2QrsIeG|WHjDl1pATWab?c8|z%0bx9(Wx8&$_=# zkSMrsr>gH?WiZ1Xe*~?hTUzs6IsP8Ou_B|2t^TtqXi|*ZeV_ib>W|WcGT1TNAm2Y~ z0GF-57DRg~Yya>Mj#2*E5SQny*djas@5-YxuU#jd@XMnT?s^<^Hn+{|R*D2JIZK(NPcp07S(mE*#uBU}7DpRP@2$`}ZKOM!&4H zMfFSE8`BG$_K(q>N=5937#Yjkq-*Kd>TO?+M)^nr8hlxr|LzDrCgYu=Bv^d}f}6(q zJ*9!>=?Z+)zorbC`toCMug`il$6LH2udqxveZLUb?ca%_O}&zzw#UTXd&hIn%zS1j zms$CVo*P~r=6pOmpjGveRF0Kf^@-JiJHLrRcN z#iZ%_RN1qKq5GEctq2%QciOlzwQ>D0#0r5ANJ>Hi7R+5kc+gSyZT%!8<;hP)2JIy@=O;WCx2Xp0CEbj+_U^}12W5_yiY4R> zzTO!a1}MZCD{iDc@wqr`&Af@^&^a4%56v#4rOS`8TSbcd`#N7^FDbe_;#CxXG&Jsd zlaBJX+)PN*UL7E$gZ%F0d(0ei%ui-dCoOdob0iZ)?^4#hD=RDamdSRh1UG#=mR$_N zzK1-#+Gi-sBJ61~kTuZ}c3<860MSm8>DRIq(vmpgkgB7=-qzWY=QR1b@N|?Nh!m#t z7VZFW;V-f=>O2KVK33?xo@hf9Mvxqy73|A1BNt=39*t} zw))2E0A;lu+~E>CvIJb&*m!j;>nSS8c(>ebWnDE!ZoUC6@0jSnLCS`$q6foJ=K`c- zlgrxUL1_O}Gxy=)17un`k zkAf3-f*02|Ha3x#lA_*~;u5^(>Pv&T@d)~^#|HMk!pASJ^|hYu;*F33h z=|>#&ac$mb(kKNrbVPQtCUtHFJcM_HIFJFJ-DA=2geK+*P5%aLfpdyNKaSvoy&5MW zakXJ5!&Y{$B&l5g4d}c|2yWPC6}XmlnRu3+I=>(^)^s5SxlNtI9b)d~HN7h#F3vMy zp#5-?y?htl3%ftKUEi`VIq#WXWxE%XxoA^11R&~$5QcelsVhScF0%bOt{N&}s7Ueg zCHczqt+yD4a|6sr&j+uN#(kYI649H*nO|QH=kK}UT0i;T)i%?| ztYf_zJ$;Zc=zFL|$l7y#-S+qPy$)Qpa{`&NMwn{H<+~3KDt*Bb2{BMB=f{CeVY<)N ziZcy|R4$hHpc<~}>Hh}eZ3;PbnL1*`ydK*iH_sgK({|51T!Q*Sw14Vcb&pNElE*fk zslnFVXksEgb#{wh9cnuw^7OcD3vOs!I$qxskDg3hm{9Mnu&>IuK$owcc8w+~d?s%v zZ_jtxM_8Ag*gahcvC`1{ps4V=#!9%u?)KV+v88OZP&2VrD@R6LG0F4ee*Q_doksKd z-a;xT`GRCQLYI6=qjjd7RaP*RrNmr6(>NdQ;uep8C6eSX6#&UGGE&OGx&5nQUcaKz zNvUu8tK2S!wjs+pAqGZ6@rP1!Tv^I<>)_zPdvD63&A62FwfYkz=_c~Jl&1nq844Vf z(2j_WD!@Xn;;P6AYNeZ>n{GQf-S+mSIIYytdP7u#j4HJlH8C(-6}@Ej?lUB~-c_%F zG|@(fWHe9UNAUJXl8>3+e)R{g-GV5uPbCz_AHs>`Q~>ewwPXO=`AI!@wB%ZnGuOz6 z^Tp&c3JUXC>>bQ&84ekKsA;>(cRQZ0{qO?BX6ne^z3Gc_v1<=WnZ)~wZ%YEi%1Oa< zSGpb)7J2bUK0-z?0~ZFX=&W4-!UdRlZme02FZcHs{ydZ&2?-xEfhY`O&(jTM;rKQM zC3SId*-0FfBClI6IvFHpQFb%FM+|b`COyq!yfE1QmQcGaw5_m8X|%k`r*j=$v$wnb zTFS>e-zQ35+-b+^m%vjXzGS1Ywq(Wa4s(v@;Mh9g*X>Ll(76sqQj5WLEFKO37tjYo zIM%KS+Cv7LjM^XGX?r3ZKM%~c8QatKRVjq_r zJSn{~6Ox!_LV0S}92|?z@+H?rNPkDE(Yh7*+GnCD`98PbxVT37^L3nIBsiA=^A_U#?Lj|6>q{ueT)0N$ zuMRO87*zTAi0j)=RP~39d^U45kQlwx9z0}|H^5-ym)72<f?5%ta54@r{ZPGk)oBFm2C? zDAMu(VlB;TQB>SF)esTX<|TQ~ozD8F+}xeu0LQE$K!zxX{N2t$U;KD~{8`rw zHa!+e?+tNq!-+I3?$VU)ft6aL9g@mZCv>AgLK9t6>)F{=U;6yl zbPqGqY{e65OORh}o1)cV6@k<}G6Lsk+~%id){OKWccQR^bxB_KWLG*;Kb${g$}jgsKBL^Ti*MCN*dsgl(U@M#>y;BsKJM1Z z5`m7|Oz|Lv)DVu)htK5=du}I2W<*1sCw!=Wf;*X@aDRM>%;^jt1RSXAy?n{-Pg2=s zjgg*%ksECGF@xa=FxKS@!U;MVgAy00H?;Ei0z7Q;oD$Z{cvoD)Y~d1FZRd%u`N!mr zYl+~RWqof>HF49{_r(?dPQ+U6YfV=pk!?h8Q-yOS!5jFQLnvpmB$y^7()H32iHjLB zFE;a%3r2RoB~^+ec~68wSU=5ut17n*j7vr!kW-teTC__)<4?S&Yh0KzaQvfcVJAR3 zZCv=wRr^U*W8tFU<~;Q<>L8(S#kREW@bP59;b0h%-oJ9b531G1IVQt4<@k_&I9DF- zz&B!MtSwAt<|^|=I4xN!;}=)`r!}t}9~EH_bB8)T;+S3Yp6mb?H+=)@%-3@S{f8UX z?ZDmlg8q#SkK6x*njXS*bYaomH`DA(@~ebscWX@Jb~5ogOyaD#V-0%C^&$7S*x}1?D2s65%K>8X z+_n5|IuA4SbPDNB4cbB3f)C3g9nOmzyKC9CHI2JrV>?2#)p*P{7kvUZ${iT_QPlvk zhN{)FPgWo!xSzGNzq7l$kLZFX83OB_?x-qB93+2ZXpn+Qzku{^&-m^Q4IPKTCXKQD z{u-UfE=qI{_ry8$J@QJ==z&;D4{_u#iT77b1lUsKg^tm4o-ponKW`n0_INJJ@y}WaTx?v z8t&i#F_Xf%M3_YJZ-A2V(|XwCUChv~LOGF3d`DEjN-Ean+BdUOc_uY|4&jG2S;krp zUX|e!izti0VDu((Hy^Pii6_9Fm6Jw~*gUmps)(xqfaFZT;!IYLC7)(Vlvi}H(+BkS za!$)WU~=D(ZUio~gNKP=DW?@S6+1sE_sf^>y5R zQc(&<;$uYT$FI!mym;v@A6H6J$+HtiT{&%)BsAC)@|Vn!PG2eQ*=bDTLdcbRmF#wT>*TteXRh8cT2dw!Z<{ptrIoJ5e*MTeCZtLaxR2Y?87!ax`kx$4CzGL|E{e@9*0ll>6MyDHl7) zXq@?R8}Fz_lTVFa+LBNgPW*9$v8^%bTfS@YF$gf;PBJ`A%s%?+}+Wv`HSNJ>YUgE_xTM{jXsg_Ho~IvNio6iJ&Z@mT{+_(mM#Hl@b-&jp z-i?^aexZ4z8ok-LABVYx_i#z5UDix20KoI-*50pyRm+a(k8I)TeTtKex6|w>c%x=` z&@SQ)sl+D-cFawGDW&K;2RWd>DvSTJS_kD0aQfkhPPF` z3R@O$50M&w2x|H^XK}-;`oz(;V9&k*89BOnZ-+w5ljMuG$6TTe^{AbELH777LF%{k zc#NO(w9|2?WaXD?*w}7d3eG+<-OIb(yI$ zrO3$3=}{Q*pAB6DrBPFT51g{z{svZq8uIBz=TCo>V-1tbTN}=Vj@!?#yqjg0pRjn= z#jF}V!au+N&&Zov^x~DpY-QC3gNcrJ2iW(%Aog)4>dL3{f~X65c3XNm!FRQE$~`lF zp1o+-a9pUzOjba&sDE|1X1r@yv|_Dl>;1^;36B1vS0gk_cTWaTzBpLU^^Bsp1YbDB zZ45VcXzMi((8K8XtS4REGjL&oM*oFYIAavT`QTuCJMSHR1m-zQQIO4)kJBX`Cp2w( zz5pM>8<^y3nFH9^mEU@(c&!r2!j4`Yc@5grHBa6qZ z*{LhUWc|*$8`>fB#=J{^jRA~&t=+A_)t9z1^j{ArX#5Au>9geMNCG zT3mp`agVhYjkNDAzI5l)Tlvh9sRpy=%--5J?U8etrA{qlw9ERa)uq%RX`o_pu>SiC zRi!1%WEl5#o+)iPQ=fBeNen3e?EMi>9Su#w8utW0G<|=(*^E*mk5(-(MpMQ_S(l<} z!h={jVC@BO-;|f_hq1Z_T8@pO`OC2`^$`n<=i6s>SZ~<8aHN+Rf@Rn)D$*{lNUfaV z4)b)!oEDDh!az%;(bWqh55Ua<{Khzba^OKhP>Ztb+b*yTO0uX|S^|J9W@tU$p)dty zV=*|QU@I$OCI-mfvZ)C3%$jH}%C3Z6a3|M5^!*01Nut81LmACNZhv|twm$q0N^dQA z;gzLJ&-}jMBi(^duq>mk=|p`L@b8QOU$+77|dBVID^vmiI(wA0;Nb>6ok!cc}_X zIMs5>KELbkbfuFkgWHtE!h4>{N~$nYcFD}B0Xr-Bc;vg*3a&-@(&{b5ZbxJHuIaDG zs^3kV8~+1^Jac3Mzvjw&BE&cJj_VJPzb`omy9ZFbz3+5=@E{hJuSC_2j4n{#YJCm| zSbDMHEMqfM)0iPBhL_zQ!?%Z4(F*7Hn*+!nU4a-#oA#^4h+%-UifWM?0*?WJ+3NaF zqMY|FlIJ)N98Qd{_~L0t%ov?#=( zvvLbdEz}HqYkj76f`b>Aub&BU(`>$-d@+=~{%p-htIKG)406wg+a?hgHxk?PGle}? zo_#dh(u}}b5~6n(K0GYDG~3zvW6xVqrvbG<{NdGwEo}9~qgjvTiDJ=w_XquX8qe1F z10`9ssPuD)m1)u0b!5KJw2K&?1AuQ2wdW*MdKV5$Cpe^d;6b|yZdP-}98>z7u+L(v zs#+?or%$bqAb$R26K1lWwc;mukiH z(NWOKsaPtGhsg2fvs&VEBX{GC&0hlWMS9*(4$xsM8+5jSnoiu=`ZTcK{U`~_6( zT4#lAl!ADkF9DC|zL_}{j%n{g%>!yey6gpZbmQXExdYR8YQ}(L=81jYD_&nV!h;%o z`j`@s%9L5$oW++hF>2Yl=_UP*kn|VoeX*H?C9~}kp_p$VDyh=r4^b)Q0AiB3JsKHd zRx5A05;>CjwU;kM&UDEs#TN)}z?@qS^Hv%NqAAkz->%G?!F9Xk7F0Yh;tGmhu)dm_ z`s8vkT9U_2U96w-F#xG%@M|3~qb(`A@%^RvX5uRM@J;Fb&A_^pPR2Rxw0uA~vSj<9 zPf%*C8XO4}Uf9piSlAVa&UnA%X)ezk=YmfnRz<~};61$aj-=o3Yx$Nr(;Xw@W%8RC_D8_;a_L@6HV0YmT#PlxPG zbC(AJVx8ukpE!WQbh_O?7dTNR)~~*dWLuk#NWWy^@I#bsk@ZrVBz@{BAK|!f?wG_W`j`LjDZAjxXwY_U&ci5X(+7%znco?B7 zfb(AAly5jQNHog(G(9}|Mw&QOj4tM=306LL5jYH15D`b@ynlgyw;^-~3k?-st@k%X zKA7=|KdtmOfT~-%s&OZ9cG`HcfKHdTuKgDtj=%qiu1Tt^lh<2#TYmY($WW3H*T1g{ zkdq`^lOGon%?Z7yvQd`;%Uyh%>qjMj=NwasCUf-u#f2u&n+3JH>am+UW$O@R%Lm5l zVP8NJ`60`b6#25BRP>c8wBl=?7!5qdgD!0PUeUSv`!84|S|}gk`azH~kKv@!3qmyg z3-2M?=-K}EJZtWX<$UlSex3KcZryPAQW^}A!J<(Qk3xJ1Ps(JV84fHIeB|YAY&j*oC}Ok&h~G@z zME9_4P9a**o2Ut=wEBufW*j_!B)W(96KeBq15OEIKYi>8tH{U2AUF^FM!{1xk9K)G zUOVfJG;M{wqV;S@TMT8-dz}}1^VH5Rbv?VzSopzH+(^gu+TFyY_(3@w}_y9BhqfLr<_vGam{DkQSfk2Jd0*X=c+~VR7b`?^wICfn};+ zECL{YWPw(<_Po&oQA1bbSX!pQKL1Q^)v2W`yp@qnS3i`UF$Xt0!S$_~!GQPOQwS}+ zs4p|8^_QpGP>=7ee{V!+@m4UxLP<09)kp7A=qxU`G~dS$2D%RS*Q@r4X@dnT48a-@ z177|mgy$T$X`!)@M}kB@*7V31ti#zONUQgg#=2UPg?nEG6q}hyif!0czpgADfY$f8)!^j|H6jwyL-9AL%1>jC-v4C zuZdlC(EzQt(k^&bI?YawaWz$>P^9f?0C&pvcns)3&R8ejPNMSP4-dn4Cn9gTbdWy$ zIy{go4HxeMT_pUeSlmsvGj4Nb-#|DnT?I>cXoxQ9He4@_LZY;aviK-Z_Su(5YEbP& zj$x`h+_tNy)nFYh&a9cXsRkO}bj|&0ylgRJ;ByFW-7Uk=6l4dY0}%_)SQQpd1&;`Dgm>p|^U#r#_sG57`D-G^JHxI>z_L{b!HtmnjW zf}7bn;|*B;6MmKGsb1`Rd@}+804qM&#uUvfJG%xkqrz<2ch}vtht%|;!Fq}Xy9Tzd zS?#4RpWOO|Xq43_JuL-X3<--X0J5DG&x3UPEN&3HOWyw*us$5~e=gwL9bR2MJjbUp z$EUoIdaL2~4tpO5kS$JnKnZ0F-+iId;yHO7n!!XN4oh*LeR^JxVc3HiWEACfBz(yi zcLyMw`s5ze4MENU6cUmE8Z=!5R=Ag#vtU=BmFY&Mpx-(}r;uT0YL+HKf#fQAEtfK) zo!Q%qw07xap#HM@tky+a>2y>uD4K+rHlu4vHGb^>_&a9JW=SNbsNa`d<8V)Z(D^D{ z0j6=QBTg~6IK)+=kC>#a*5GtX=#hyw7nU85sT7NnPYVz>Gt3~YEKyMKmSRC zt}_-<(IOG-6C!325!jV5!GD|28y5}#)VB{a3@r8$+0~y%NMB4VAf%%9I*PO z*5Z8UNy)(+c!#i3BZ~J^66IG9LUrlZWVG!cH&Y#G=w_pjbwjZ77lgdfluMoqzNsB~ ziiX-mtNI9wxPkvWL0%;XE#`TxChk&{28jE_54amIU)_Bdf7qH-q*w1l#d(A{wjcD} z{=}Z78&v`LPSf|xVYgXR+xOS9lGoYZrp{G^9SIvTkY7!AT*`j~=Jn}0$vb0}>zq9O z^|P_fU-`N6UPNOB^k27wZI9l>Iegy#T$qI4z^^aJX9pTJ^HzDYjW`P3e7Bf5*rg}1 zu3U;+4&P6cug3LqEVs#C4;B}R#{3IVNBBgtFGSjE>A}6>+LrTr^QoDWVdSsLuCs>} z4x?Cg3=d@txRtt42#p_sF*uma#VgB^N39hG+6wSt5wjgFB$*|JzJJi0=>^E#|CPvL z_eFj=X-s%H=qBb3Rq8U?8Y+)c{Uk10H!-zvHBOry&1Rl#}BsktN#~vSs0xXgSZ{Ss_f%5 zs5$8UnsU?HmIU=I7Yin|;*{cA^}K7Hssh#21;f;*q(sMk0n(GODgpfh3O{L;Dq2K= z(Npo;(?XDwpPz&?WdkRQE^a{I3n}#Z{zJJPC)b4ofGc`--9gcwGcHEK>GEzi_BUYY z={o(h!TF9hS$j=R{zl&n=-LvFa*)RGaAr7*h;VVjrurSqdWh0P+wtHZvJUYSsn(a? z$^Gr6b+NA=(a{q0_6lK}&N)s0GeshDJ;}?iBHzzE2%6h7LzgkuHvyjY2~YO!D22tQ z?3P=I7+4?!Mw%Jedt`4ufcjr<&%SNQE5r;yUe$S3)P}8W*6L^ss#|c3@#ohF7Dvt{ zsbRgEn#SZ*F^C3DfJ{7SnFB3VR}s$jPqpY!P~-v-N1M7B)GH|t7H(di)D>i;D1^84 z8Y3zMwc;}Lgkb%hWyVRRSL2Ta!s_WwQK5PxPdm74U$R;#PX3P&0^H)u@ni@>J0s(V zo5Vwpzo@h^E;$%xU}}A#>FD=frO}VP-RB{qY+w-tUd(hK_ z%c*J;R1gQIHRNi2YeRfB%GU;M=`uX+c*r_imUdONaa)&1hyj;mWZ_|nW2_I=1=PyS zXTIv}P2C%RM)KX7VR^&G{qzOC7Awlvau$s5Q<3X(HyY6UyL;PPJ2g$gvZm_l4HREO zA0@bJA&PAziA_xw3c6E0G@kZQLlF<)2302}c8!9XO{QYxB%Rr(063c(sNqAscH#Qn=sS;v?oAr+-11qDt!>0@E|_ambcTraYmf z4geuu!>Dz&4U?{)M{)yEZ%oERfAgW|XP6G*C1ASG zuXBCAXU)*f-Ctz}%1GHrGg=&EoVns!fF8-xHNP?ef$40iN zvlC=|lu~TGhZ{pdZXP0?l$lRC6kNDd_akFQW$8V5w#lLP8+1ncSYgq5+hk6lT>LsU z`HRZ5r&(=t=u}Gz@$Q!Y2)NNHUaO}yc*wtpA}O&s^K7O?IH&l1#-q0jF#yHq^B%&D z&2)OfZ5qknu_12vWeW>0(v8Ro7Lj)Hzd!%l5QLVbNa|AOy~#D(i>l2~(XbuRE0>PI z$W7J82$}l=bPQyLU)=NTBFyj;qf@-JqA+-(;G}bpmoUJ5-h|ty5D_H1BWp$8){ia< zVl>y72{douqdNcxBKT8>2qFHkGSt#yM=&{buJ8uvIsXG2Pa}8E4b-iD(OVm9LWLeo zrqG6XT@_GC&iYu+ed7${i)A;o?7hba`_4rG)B79wd6ZVUd;4FE7?^0% z(@>9mqOP#7p_aK@Lpub-FPe)7=rMh2kpy9eF#6RnuV%?D`Uz~^V3nMZ6DE#wuOhq%5#Ux-e}vO5Nf&U z|1$c}_r-Ms6BsO&2VZEx^9Kn%?}A&_D;rpDQ;fx_L6li{oaK1Q272qqYMu{E*PT&s zDYGAyaEUN|(KAnO0C#=^_jo;|YBZ8OHoR*qzo=jHQp2V&jaD7U9-a^YEfkl&D|moQ zFX+MH0U6vgk8w#@SsQj=v`CO6ZrD!q^x|`xtD0zEXvGE$_K^n5y5DE%F>pPW`2g1# zK)jM<|0eppuV5w~K>x~&&U+xi;$n~u5EH*~{$jgv3*Tre?e;dYQY*uy2jd=}JHiG$ z7D&a$_>X(#4%;Rae~yjl4-LpQM63BdJ$4;jE)a;1?+8H1dX11PGwt}-mx-=@&GBM6 z8y!Vuyyw?%;NkTfn3Wwsp$3qMxXkN{eoE=l9dM=(npcBtV#sSEWn$ zaFuhMyN#H=py(&A$uZeL5fAuriA!%V?K9h7JGbo;tEAc)ML1mw&+saR*y#A!J_;^B zy?V6j#q|Nxc@&@Pj5G8-4mW%o!}TMP{f!siSCmIGP=&SnNR#DbyX^{nD&wkTU-Oxq zF-yuemGak|ZAY`u)4#(HKoEdPPEtWT`@qfoo66VFFO53ZZyDYeQaY!@``sJWPP{18 zy>Kfz0(>=WUMz(NMm~S8vjgoK5D!mdl0FydI?u{8X4;ECG8c~<^PFaH>chR)-C>xI zB8=}0r&n$}tp5i1BRwO`5wb>VyiMLs$a7tahlefc7QTiBj%vK~N8X*Nez7j-yvr|| z7L1}==>(Uuyl-exQg}Ge+#iR{opBhgMRP`=Mo43?dn`}CP@a;j(`2HgNXMufd7*|Y zxRAIdG~s+8z8CnyyiL$_LRxGSem9f;MTUhl`Iq!xf<7;#Pkc6(vABI!ocV0v`M0(^ zTRWI-Ys09v^!CT3F%}<0U%L$&;>Q3@E*ResqVnp=8Nc=Ze(7-RvuUVsQ2;#0I|&K( zo{}9Mji5*8yNGUv4mf4lpM-OON@VvfuUqiYs7WXP`oy%HseOW5NO4K9MC#wi6d;VR z&6=jU90CS~(mkPJ>NKZaq_YQRnhGzLy}NPk1yuBFWV8q?E<$pSbN`$xc*g%MnQ&o| zJ53^zD=&|@g7}^wXI(FaF5E6#3I{&`koPHdtPp!~*{<#j zuU*qIM=;RG6$13CpBoG+MT9Nwl{?)sDL7F5DqECY?b@#sBd~6V9|d=gwhS))L2yh& z=CK#M+#}oKWAMxcJL{Fyj?HL0cAGaIq`_I~WbQjj9)4XJzc>ft;&j*fe*>_mevh51 zBnLVaBs9CJR%9#O7E_m|{yHWD7->*`9-r0g$mYb1j6e&2v{t9C=I$jI3hWeZ^wxeU z+@E@OvEQzM=0@htOOf6HBqcu2ej!c4XuV*DzRLJB%{@V02{>>f{LbB+J#(+mXLKeo z95%t2l!s%I04b}wm^>5@KeauFvtBer(PYfLv>2%aXp!N&iA0*^3BI$I{GZ9IM?CAziv4PKiCYBNoIRS3b9V z;w5wSDRMXcVZ_Wu!6Ra8H3eLR-k_ z{XEU+I){4dyWTH8JW$NN7A+>VK!*x7OZyyMca>*Sj z0YClmUQF$))WWp_5n^fDcOy@;nqoV9l)Y(UIo*hVG&R&k?cQ6*#^!Mz*m{reK7ZtL zJ(cxpz^@0_CBbpdfTvEX2`4=-H%6_*yje@~PpJ?>IR%_q;bM=KLhan0EOnJHDv@HT zjl&<(0*|@K^7nNY%R<)>k^?Qgq04k-xuSO_k@L^~#vWbiq8mB3b;$ne#nOtaHA0Fq zKJMY17kVCIi_fPA^J-+3d~t4?^=u<}&O#u?BQnB62YXTANDX z+hqVfTKW`47SXi^FXWQ1BL^}YH+fv@bb96114b2lRIsWe8_8cTy9&ts24eZWb>7Qb z-KigWhO&gvC%SVF{$&RtDxGd((j2(XPWqYD4B$KB1kK0)LD%NeB*Udo@?sQZSk9}y zbpoH=W7<1p7SSP=wzrr!y-1PH?b*L}A_}qGNn=gbz#V^=?x>64hf5+$)yo2mb<{@h z_hqb>3XC4wMCx(XdAjsXEIcwj#0E;vZ*euxdi#7(WE6E^`0Y7dfs-HF%LgtSlXLlF)R(InzJ7_6rsgyIZ zE&lFp`RM((kfvge@5k&BW>pg_MP+RVJ@&cBF2y-L1#WI0ep-g;ZHkw$x+kuCuUqXk9ZtsNIs!T+*tL#jt$lyFE9U}= z@OyeDFN?6)fq$U3T0L zNCIX&y9N257;Be@T{?*VbD;vM8S!q%5Ri0NXfs9d%a?8ia0vkrvFSeG@GQ&~N&4Y# z>h12a?Pk2ayX4{^q+0l`&z`kRif(!~@0f@D*KW%V<$*%9Q^ANG+=HPX;S>6v z(fgwNSXej=6ns{JMM>PWz;w;axztd-kJ`q>;K?d*+I>B)YiXUw3EFZ!D0zxiLz`Ka z$9ujpTy;t6!K0M;zg*7a)QUT>e0)Uh+jjHzuymUE5CJ#T=C*k-&l=0J*R=yO8$21} ziYQhTEjtT>R?YAF1T4!2l<_7b-lHX5FgQ_Ma)5l!Jz$o}t zz=`IMJG;{s?r|5+ozVSS+f2gEv9tpNdaa$c$tEj%eLt8lJ7GN@wIMP`*rEANVB~4q z8XSR;%F&D8?jH;mPX7cT$eC9uUG>R5-pU!IR`OB-m$2`g;P-+}s@^v`VzhTZ{T&Zg z&hN;QSCRyWICG_IMU0jKL-0=76}(r}3WdUFpM>Z2|625c^R$kZ(z=ZIgyt!&(iVhc*U~2!$dpn*SUjb_YN>F}_VlWkT|~^8%uk+kJKcX5sA~cE zLY<++=&+Wn9%Gdctg$LQ(`B_9hx6D<_M7A&qK!uNbv6ISp+>76rM|u|63oaqEUx9Ar;l}NC_Jwh?bNC zPhMhK3Tr*`Hp)Or6g4)G%;0sdqp`6^j`hQYLZLdR(yvam`e_5Dy#65r!_zmfhrZVn z7=Hi|Go~ecMQakLL7551L=RyjhzoeKASv_WKB=GWz*xwWzP7+{j;2wt#a2KAf61ka z*9Q4a7TnwDx|+U4Z-H*;Z=e$Z5UKOSJ5X~iDkez)K>v^h*Nsr77D?-;b%Hv$51kPb zcyPBD{u9iT#6~8}gds#`UAXIobhZ@IFN#yE84N`f5z7$ydQ9l}{%yum-8Ki3K#>7` z{Wl3o{sVS|g^AGVxSCb763j8D>oz(26Av&K4eo4s$4S&U3x1xdzoK6{e84~7t8$|~ zO-=X>vaOn!EF#Gn9+)K20bHP7Hqcn&3WySXYwG2Q;{sXG2gD~xyLJ@#eSs^wzsM?* z9aru(R=Ne`Z?$8S9o=Qg5a1>TWGbQCW;Lf^`y!KmgpiKH_(b=+k~~R(u30@?k7oKM zeiYo7*Zz0Td};+6z-NOnYksY9))+S(X~YXNfnC6)bE(3kv)2Nj$V_(~E)3tbtxUQ(X7 zRXF#3I;{N3naEEq!lqyg32{bWQO2JD-zPJk8xln$YX9;pFB3jsnxg5QRq zkI#MY{eAOC$|h&e?4H@(>BEz$9S6)M6AkWs!Iji_R&(400aj4tTt0h#agg`vCzdI*)DNL<|h49rXqRN}2khA2v$%ImHgfhYR@GDK~o{ zsK;gQYjS2n(DvPzOeo!&7h9e)y!&u!{DbX27lj=e9QRd3&AB&w0lA(){*E_BVktTE z{>HVv3_BrgEMthM?Bo*zTUVxI$knsF$q?u8ew75SRpl-$?B~x3n1(?r2S+17BMYpZW9U2WN$=R>Mn8Z3)Ejd#CobV&M-^0y@yg+-7NlrE zq%1d&ZXRA^f@q>xCFH43>&>4gSAsE40E@ZK{ZILYZMi1{ElQm{pqN1gz?+3{lr4e4 z`y>itWRBGlzg^kwfqgn>Vcr8bl}@2I_*ZV|5g&~QXO+$qA~w6ECNr!rv&WB^{s?N- z5z{i2MvVy&IE(`PloX_~NG1URrJULZ+~~lA&$irjCQZrMw9hzMv5JfAo-l8nO6QAw z(T9h5x%jodDP2>1HS*w_nYUPfKtl-Jl=8%-bve(@-9 z7n(U8a0~%5zlq=0!Kt{jze0gV3QXhd2Xdq9Jyql+lT@CMVOA+{50A+?$@RBiQ3$1W7I6J(0p5qXrTu89kCd^}}W;TUk$Aj-ln_^w33Kn~keI zUPj{48VBxzt9RHJf%yl?{y=W5tdh}v7WNC0CawzzY3hIt8ipFKeYfBgOLNJrPs`A< z_H!%p7ZIHOxl?V1zMXB-QyC{Qq^;65H*$#}D$zQ<`&edy^mdSfh?*P{=vj<|U2oY# zj6uP!`(43z8Xp5esU?KY-y3*oxV5&OxA_)Dm|&}fm(!e@mSm5|HzU* z$1~hay)HhzQ7kUU!0wjYC0x7yWY) zp8!th;bp~q@M!zVmie=l`{ybp^DQ$CbI3;sjn_rH7s7{KlFHr45M7r49R*J9x0Woy zCBVtX66b7p$14?Am<-SQ1ie|1yt28ah0pWl7%uB6)tFnwO&mu0TMlR|*;P9^g$N95 zaz%t%0r|JA=z|C8z9yKPA{OTqOV=yu$ql5a8D&_->B<+m#g2OY^dN&yJaBdc_T2J{ zp8IkP1DfSIU8T3SiHc42zbh6p{}5L~sdo_VJOb?yg*mVc zY%2_!bs3PZog}84P4y_^SGb7j^zzKT+Wcm{%M_eGV)9H?yvPCC#y%&L8a2?KD&N$Q zGQPplqM_X+HaF9nJ21RFTWN4}$cEE*GA!BrjIK+^z6j3FWCHrxKw)OaIKe6DfHp_{ zAA;Yz;U1$KOK!W8FL_00@5g34MVIC>`2=tt{oeRl8*hc+3DX*jV6wI`;P=%?6^_yN zJm^s19Ag#-b^*gQV7iRQFOmAJ#<}#t|NaZm5i{Sm{DLm|#iQ2&v2nt!)+#T|JT9dS z$mN3^f}$vQ@3?6Z{W7z%`vN&bU2aj!;n!cCiUN6@9Hghij5qf;TDSC{up&KZkeN^V z@=)CnXk!eC)Ys6F(0}F7Qmhiw5-=$@;`GiV^{kWnogY9f`E5kM*M-6imAN6n6{nbQ zKe(za{b@_OgK(&k5oa>ogEaBfcw&S4kN*a^n%)hs$+*12Bha?jOG`fz*6W^2x5jw) z23{l=zL?V-_~2F->M$_;I$4M(b6$d&)-hwVe8@G}ufF?d^w3c?6g5faCTzZj#Zu1ILK0U9m6t$(jH`|c5CmM^fowuO zBFyjU?74q#8wxoWVQ?IxOB}B+FVZM3PiN)H+aDFbB+-YL8!i)ztHk#2Kkc2HW6raI zNp{r#GZb>xnN#WkS!gAdoS#8dyC!&6mgkBNFQK+ljDiL#$SxYJf%t}c!2KXL8z6}5 z2*ecWbSb&hMXE1?cnzE^oEz48>B0!}MaK=0hal)fW}=J&MCXSrM$Pg$l@5jChPInu z;cUB}ZTp35XyX@TQ!y~N`V%Do9ZG1sUqmCXv}ERtDl3p6Z2_-!b#Sm9b>yh_*9GBe z+G zKl<<<^0ujZv-RsX5Woqf6EC&49dHrS6>Mqu+O)x1Zc0nQQ$qwq^tzJ7c3lzfHJKHC z<-FtKVT&2DQV^vGG3H(3_MbY2o7<&Qg>EQXr)&Ue=wM_aoOX`BQA<0obq_TpgK54e z|0;8i#M_wSz{3G$e3lD9Y90Os$t(|!gY%W!@=d6azVlFkKNaD7xPv*GeSOQDy3vwcJQeT zM^yhN2VkLuZ|Ld8=&8RHVVl4O2}fw0-wSA5{ZXImF4E86r_$y$oOvtr_GK5FF88R5 zM38kZqsR-<9nZfNvCkEq{tvGJCN6ZLrl9ge=T#w+%b9w*!*3J>g>?dL`yhJuisx7D zE7T9?K@x)$=W3zk@B0;H2R9IO2?5u{_Z5$uYkfNYq5k-N9kL&FXQ#V{uY2oPboG9g zMn``@)Pz_)$7MTtRIH2bi2nk4T7F=}sx)n8;~gftY3!!u54G_trThJ`p`s^mvRf4@ za%7b5FMGAZ>@;!kl_Pcg{k))}K&N6?9t0u_wyVza=UMxmQxBapE+fhIOyy1TR-@nx!UqrPZ1 z{iTv;q)9~Ek?uQJ@+*LQfh^Wpw$!2dT!ivXThgIkH#ND(hQ=EP_f~Gdc6w$>_dKJ+ z#NKts>I;}(?uYvE2%@aFJ+*841L5YfEqlP+amHxjQ{Poi_gbGFw#Q^dT-M2%=I}q! zH5h1T*fT`e>Y>&2puxdF;*C8k%wdotrgToJTIyESXTjpAv2EqfA2z1;WsLAkSLX{e zzoFM^Enw?*x2(S4H{4!jdvWP?2}yPD7i^WKycXJqd&?S zwgqwWhQ|ingJNGK<00=UUzzPBCHE=yi=9c5qBRM8#;%D=AiwQo*~#s;Pxnh0!Ee>hW;e@a{TbF!2g z;#^88pV;S&vsccKqi?%be(2X;a?dDm$S8!HyX`(P_ORy>G1p(XN(u-xMOyyA)5G&9 zx*lImMSs;o^nUZIK>=KP6hE(G7tS=^SV?{nQmu!ofzf{{6+&`UD zvfmBG;_%7@SI}2lkytlYGpR1-|F}i+d>@%Ht-?^@H~nope67Y)p3gJd^K||JW9;gB z{g1Ef#KyIjDbrpEdJr)!zQ1kL$U(*1d`uS?R=7rA!zT+^p#}CQQ2`fhtzNeb-z&TM zaMwuBde?`DcW?b2gx?%`ctW-R;`9HKX9FpIE^46cT8OWxpgKzJWa>+B$~l_>X)_>m5}(w^DYR zom;EFt+Ftk*J#=U?8r2xknTnYP}=ZS!Q>q+M~){G^9;fWpB69yE4ZcgJgLIOXAoU| z?xB~O?K8g*an{Dks4@(n0&93pZA&9yI`5}l1tD_W=)|5p=hRUtYT--#n z<>kNr-${wT^5an4AES z>Xh9fRAY-<-JA&sx~EO>(8K)2Q2{p%>T$l^@p(!qCmuSq7sh=_wTBt0(z_U~FcovzkuWw9AvIME7D#E;I~k6TWe!_A8MEB=BcbgcB9Q)rkdx8b*^>&;wt(8*6JOO0 z`P@pLYv-?gX7?KG5?)8>ZRO`U$y5#8=6BsPl7V=gPuB0c1y@4QLc@5UJ?py_D(i!B zQOFjD@i`?)EDJLQqGZ65-WP53X==&lJb^FT)nlUO?77%nkDs);p!+iUNblaGu}z*D zL2KKR4Kj$n9-So$Ok9@p5ghGT>{>o`mU(^3)cFO8Uw5cHtVuu(Tao0jV`K8~Mo2DA zu4k^dR7n5cWp?n1xsa=1ayWS*Y~yv(u3yl5$)2}7D|6uVU#xD8)LxQBK->Y0Ip=w9 zZAlieqYkr@f=}(`?wKPFO0r%e!7m$hoCfG`D`~S7SUKKkpnQ9vztXbs+leg`)`^`+ z1CY&m%Nb#K|M4N~V=Tv}IH$Xg(DowQfLM9eIx$FoEgn&HzIQDB(r$im^aJ;jM1vE6 zx0-HsiMB7C1#Cd?a4fYQKzDm45RObsSnW`}h#ghZKgQLKf|$K@sufP1vVu(_>G^k~ z2x0`6jIJuj{n|QKZ0&I%70K55XNfcxR>Go<#0X{G1VP~51#3|KfXosRk=1H@iki3!Asa zBU!~Zc|lj7w%dlP#<#lKTM_?6PeaiCPmC-CYYcBS8o3aw;IzI7Zo@e^ulZqNvT>&6 z?Nx~=wpmC`oG~D7?kAX{O*FuZG$<(1Z9~Q;Rx8i}{AgR*@t9a9xwg0Sb2Uk4R7ACrk)B8p zb)I2v3GL!yWR4S{k;cQwLg9B&-ZsNd&Io3Yn>i6TenC$Pj??$t>nQGn-O`;pcA?WI zBjNPWFh&v`gV;ooW)<*0W?kx7JU;v;LF5gu=MM+epn97sL*D&4fi68;8~?!PNqH{w z{Z->s&yAZ>!a8RycC-7=@!kTd6T~s=sOVCquywxB^j4pLW^DUYE>jXB-6X>^2~#M5 zMppP4Ji4@Ra8AK=)bR+!2s>f2Fta2UmfCAQna?wK139i5a=jH{&~xy%?s7REao-&r z5j5y?6py6i9Fq?#1YvQ;%2V?@L*D*^_-|fTLqFnbfwiD;Bey19v?GKMsxLM9s#yz1 z4+~}!qV2Paw-`p)#YT?oPV=fNp6qE$z8xUMlhlJuL+ssi zV{#wOS*}&`WnbRRZYF~fKeLs)5FGxZBw=x)u!mzZydclQ^OVth^E0Fs6`L zKRG>8gjM>_kNxAUAb5jqI-hkHDXq<1elf4|S-Gu9)$XQcGU7&2JEia*OZJK7w4DdZJHF0BXQaI{t7Yv6sH6+dIc2*n z%UJ~dC|zscFwD+uU^ixUvD7(!zea~`IV*Y)b?ygczU!9jFS&SepAK z{r<276KcK+KYUa z>>Z9_=hnbMUov@G6!~s^4WqIel%->2r1x_|LlWJG-~CSO$R=Km#z%m5^SAfMwKg80 z3BXmXhqTD)HR-gd7~c({&SpRz&*{fk`9CgLg;Q5?`**eO_8Jd^Rvvmiv7=GXTYARD zB90H`(kOCM9EIq1ret~4d@Ie!AHLt~fxJwn+&R9&yI|bTbt$$-tph8zS`mBX1W4Eh zwB5%`kA<%HuTtVM>n1CfrY+$v`RlEMObFB?N4Xk963`4}y3J**ZO-YDyGlubYoUTo z7dEb%?(MW4_96W0MZ{69aiP5~arl zT92@j(Y%~fGK;iSU+Q>{n_7=muZnm8$pSJn(b~eA1i`9ff)-(Vg8FGfi1}I(3X*5f?CRp)(NB2GM^!cCM$9SRx5k zC!6t!R-t2L=Y66O7yMEuRf}XDy|$EBbee7WQ}ggNQJAS8F_T!7Zmj??usMiF8fa*i zd}LVmwOBlRzCwO9q@^UG9wgPI9Y2gAM(;c3Dwsu@j_hIee-9bx&sF2U_MOqyoNG8l zOAL40t{Ia+$dWf8bm-o7Q<5wwj1zkgL5dgM1g(9H2l|8#MY(VkK8A&GKUeF72e~ht z?rQ2iI+(;`&kYo0sogWnoD{XJ?Kh$$eoBPWUmqQ?I-a{zyHXYO0g^*^W~Sf$%&()c zEz5_4g|_G+Tf=?|#2T)mIG2>+w14d+Qo1PtC+cSKl+iCt$9PImS(7;6DB0`ZzSq1I zWMQVt()3FVm&T^6WH;n8%xkPbiIJoUGMmgP*Lbv4Z$u+z@S(o<)JO%1IYC3tCppK^|=637{QCq4aNj*{wG89+Li zmz-~x-!%%EOUWM6Zolu4@e%5B{b5!*bEfZ>p&KQ!-g3#VC~O!3aCm7`{K+vOb`s4J zMt|w9e@i`R18`I}Z6F#!r)K9}TNP)Vzsk+Qcqi5o8Ow03h(5xMkJqQ{((c%^(kE>< z`4?H!TT3vXKtJNN`4E+upsu=Auh zWDOTdtwCGkZ26^!enDt;3Ib?pFm502f(#oDY=ZgNcO0`;67#xZed9*}hXZR|MjlHLC)3Sl_rBtKhJzD)yEUuzS&cNsL#uUlq{T z2_F!G3_4d>SmYP*Ssn`Xv;`%uX_`%^-rnn38LC05Qn6^s7}5uG@NLpJb*OyeNNodC zM4Pi){6XQ%8Wo2BMQ}zKbR4{$OU!l&=kv4$6Df?^+mJIB%v}bEQ`VH6_Ka@io+8Fk zp5gH^e;s{@*+}N*$UyM-@y*c!dvl%D^ZMYSYC5m1;jP_d+n1!$MTo8L%!Z0I;5!)j zF0HTb0gH%A{(E(wF4dCAg_%QuOm;ksh***z?cXh&8`@V5{Yak9(5-QSw;;CUHTXR^ zLF5Lrx};fwy!^#J-3z?DMHWGJ;^5XkciBF9*=Y1Z&^fH8Z9#rIuf^(|%U&ASu!$Ow z?r6!U%uc0h+PP}*x+6n4dIwfY6AR-#Oh80tOzie6t$I_kII(Kz+G$SsJx8sJv@5s8 zCri(=@J_p(+IBc8x0=?tI5J%Q5y6Bxr+P8UK?G=hkcUl6qrcKD7f(R6FHEgsq!|3S zdL2_N4j-VT5sF^LLQrk8DeUb)?hxBSW67wg0b!a9#wx8Q=V5t8>CvUL`5ShJ-W6G= z_m&?&U>fDi)O<`3REdB(?n}s5HslD{zTd9KM3#Ybt0J}D7v5mcpR7Q4&|edJ+aAo5o^VWVU-}pOpxv#hFM_5iT29PH zN{-JlI`>!nqg+&~X+6coM(OW?@0jxeX?4CS(Awx@9CSpWJtCLi4N`W2$K@ny|9y%K zQ`mfxhq}sLm23?WAVj__R1U^9R43G{XXug(ES2tuT`jL4&?S#pUU54?8!yv@lZKv5 zOnr;p&YJHzyXB@!hc!9x3*c56l;@c8@L+FUuVuVIgZ zW!KvbTuD$$i6IRs2%@^K?K$%y;O|y3)=Z^SndS0{WAZP zd1%!9WbTwNSKgK?i>>9JbdP#psH0q2-iuk&HHNR!$-sHkaq>e;pY{X2AtSMMvzy?q z=i+ddtgX+B>(PzJiTcnU7PBrIju7ObhmVD}yQXK1JX&f1B`8LV5h7;>PT^cAt;H{Q#>mV5oQx{((Ym228+k9}Hr6=1G;c&j@m0i>vc>flO$ z^$ukEOIjm+gq*Z21oqi+Kzb0I@A*0?Q3Td2)TQ3JQ-M0#dQ+f|_Sf=0>owAN@`L+L zj>I*{6x;VQd0XUX>(a#jqOIYAvs7(%HS~d2%~SIc+^IdeE_d%_%udEf7s#tgawOy& z+rr|nH`&qlQ?*_<6Y9EuBA`c6jxTWC?IFB<4?G64Fq(}Iy6xpuiXC}9yI=w2Ygn73 zp)CSo`dgQeiUj06Z|!GEh90i6Y|7W*uvYn@6LO3d2~H7^rXS81sbgTY|*goS0=c9{7roocMv zcj$HeFh_Bw)cSzeNp(ilBMpebE-Nn=V&bust_#GI61LFalWJJzYxcl%97rW484l97 z-?m2dBWU;e_bUiw@0+UVeSt$c;$C{E6)TmwFwNJ0nWvnvetL2h*{Y!m9O}=zYvw|~W7N%f&FNSdm%PbZcZdfGT)p70p>;k86#K z474r0P>}f-bfT|tBaWdUu&)ekR^E>y5ReVWePwei+d1PcLzIchTmn#^i7%7k_smpP zt=1El5L>tV*PF?5&@+=6u3Uy7i7%N*Uq7wNqBN7RGd;~G`FTr$hZPN2jF+a{fO9k` zBqUC{7`xT#Z7ZtZ5PDQN>Ah8%?+_46st5Q}+I5vL3~c57Kc#H>k| zpWE*zetM*Z*t+$9zUfboS4;G59YWwo*)`)Np`UikVi^!{ceMg}>}l}epq{?v9U&>5 zOcZvdR|V~&XeTu#gsdA|q)=Epam!?idrXWlJKPC{>fOY4+c_oaOS}9vN@9 z`TaZK1oUhS>EC9WN766tJJE-r{lFUY&N-8WHsp(MqSq_TBzD3wLELgoOpMnG34(bt zHPMHN$jA_|ZJTZ`bj=`j=xK7zX$`Ul{5kV$%x8Imvcut0-{orxbh>64dtNdgaD^Bc zQhZE&>h70p)ua54!vA@H?e0pRrr735WS6|_P@U(u1rgR;z-?rr7yHhJ&(^B?SpV)L zTdnS7_YJ!QkM8w$62${f5!5vubkHT>F%xSPn5QTGGR%`N;K$9I1L}GxR4i>~j~*cS z%#iLS^r~q!^!i;Ea*bKyx5T@TY6<4t`i4yJd3^BoBe%j2VbNE_DMz3qp*U@RH>>|I z<|vb+T(|Z7Gxzu@mc233&{AoUFtvpvw$KD~ecfV??vjG^B3)9KQZ=oa6&VnN{K2N= za1g&jTnDhSf^SwWbh^?nii|E7Y&|<1Z%NyDcbU54^Tawrysw$5_AYciE zrKrqF-Vp0746+`gP?&y_zmL!EGPIm(-z5iiAC+5@5p2O5qkxo%nQnZ}mS;tIl>Eh=i^dc}O9VTj+z z{p+2zQDm8Nrr+G43)##W;Uu;ArcW=H`VTs7B&8a7CN~s&cuei83zZ2u!Zay+&0u!x zaw47#yA}}UAjdD`p}y|(*hkGIe^nx!NF%w) z>aCqFb7P5Lmp8PaYX?Eg_iUQ=a)U`XW2(mrc8K(d{lVX^(wfE4aBxhRNO~D^Vu3V^^(00j~EyqkU zoZg*nHHIHsFnnmJW8FD(D?5{;#snR)C5BFK{SK zFP7+i#Zm{6kehKwjd3Q#t3|4#Fa63LLj**BZ+{MSmcP&Q-lJ|8GrRJ<8O-DWeD|Eg zU7qX0&>m%NuN89S4%Xw28@=?C=SqIl_C9%+5}_D$+u7+|*DSS!l~XBfcQo9Z0|Kfc zG8v?{qmWhEbmi0192c_mVrhnQ<~;`vTyLY}Np?D5nQ-&LisZ>s)ombzC~;l^C^^`s zg^iVdZ?WW#uAX32U6Teo11jc6AD^xV1_X7% zJv&5D2ekApZh3nYr(~bA@+H`ve|3l7CW6%?0?^>)5@g(jv~S`A{>cC(pUE9^W?X)Op?>;A%8m-WtB&=xU*QDNN>yX{}?M^yXPtxKV)YdaXz0Sf`*%k zlXeu!_S6)dh}|`C$<$nY*hTMf$Av;BFNadRIUH-!9VJlveBLqQQR0gS{%42Xplwpk zdOW-93$Nvw7W6&7Zr>S-(OHTVOeTtbHZ8NFs~T2!l@U=bw4V66lgST_K3DOslg&J4zvn07t2 zrwi9CBNks-S%KIxDA8fG)rOd%Z+T(}&>J;%>XVq+033CI)wMYiB!&VgNiT!z8LP$)7jJR2sk{=ch?nubi+v(J+=%N zB95>|@hFdu;9_)GU#jbxUM{s{ujw36N?7Wzx5~=Oy8HV%A9|P&Buee-9Cpq?q@A`l zKyEt4<+J?UMQ)nuw*!jrcvR)u)q2~_fWI-u_gn}pRDc-ssTTpD3n<<83X}1PcztZp zN$6!}!hr3u5V}{OtdU#d%D|g^SJC5no|pH4g6tP7fn^Lsk7Y-oe+VmyTBt>&_`>)i z*AcsP%ll_diQmoe2}P81w><`MDPUpiU)65|WE(Ab!C5GyHs!jm6E7#3UVW5^-&|EqWa~I^GhhKtW3Ol^gWc;^ zhR{a#)?l~s@5ps}?$gZvDJ`SR0)OU|#d%7CwOz)Le7Q_}7VPZi-I!;REzLxE){5wnJ zF6pYOmB(B(<0;DJ}lfGtl<)iR8g)*q#(|B@7-jhQ-(6UAQQ% zeHMg>mSH3ZUT^?#L?jYvYu(eX289decDmi;ai*;Ulel21wnK};A|kb|jVz`ykEBzv zf@hTOD7t=Q#$6b!!D6j}fnLo(>*cMO)Mfn5<^Jnseg4;iMfYTV&NY8BIfMY(%PqVh z5s@fRQ&hzY`ANcE(Y7UptG`6O$2z#`8&CV{S@1ZOEa9r`*S_AHKuUhjz@e@uUMP`a z)_xN6s^NIvFKFm>5z`%d^dt7NZ!sm+61+K2LuxqGOz1Byaz>sDNMH{BrkFdt@Fllp z3fhsxy{y_wM@;Wt06g&~&`&6JUaUAR3T-RMl*?Q3jPZo&!MsDztpZgs-CicH@>THX zL<|W|@!0Z9pj}2+Z`&AQ6WAxRslMF~Ps}$2vP4YGovZs*1Zy&KjUpD3qNI$?1bKKn z#Eg1#e2gPu9D2O{>sAxQ^|R3TQ5BYf7kAs5j`ii)*6`KHGCSyja59|*IjS}1KWgH{ z$$Ygspjg)GqX3Zwa{@ z{VZnZ)loL7cC3W-ZOaz)`GHefnEhcL(*@Ez@Gq_Xt_vFLV(`NeM+k#&=f==NV2#EE zBvHg6@|)|zqQ6B0{Ni}V(>nuJ2zRW5tEET)tIn6kK4+{uLC+GE?}=e#6Z|&iV?07w zCs8*{z!<2|*k;-kL6G=8SZVHbC~ey~WdClswqxq-M#bvkGVS83R;wVDlHhT7L!t*Z zjhWd?7Df8uc|4apmBc37^Z2G=#1Z-!laqC;*b;(%X59W8E2EJA{ru)h5TNYY=R`Fat3tcBKjo=n%WJ*~~XvEvjHt7ujh8a1`4 zUiv*VK#AJmtyr=t;vD)|HQ%9H)k^u+e!a4=%!lKLqISKNXn1Z9^2mUOoYSG&;xAVi zBZGTm_Hw)Eu5FX~5t{U*H8TECp`q;hiC%@wNTJdf2A1udBFWLO<9t)f+y?))3_$;c zgYMD1wo1Aj|KW5%3jW~+MpkyT#K6i@mb^BRK;k@QAEFsW8#&OkGz?R$gQ2>1 z?BrGxM8?0hJ1H>Sc&TK08C9(tJzzOW@TeRz!S0CmQo-RwyG;%A(ktF>V_t7lS82lI zmff$Ud4M`i%YWh=HYb2v@m!cxA$C*4O|QlFdQB<)nFL!o+FGghsiWujlcw1eiVLOl zSqV2&2L3WVTPZX5HT5dG#_k*0BwXt~PYy+s{P$&yl_~2*{&Ol)8LLd*#s6c-4A)OY z6nx76_DF)QG%51Nw1=d9JYx@~D3Iqk(s&hibl-xT*l&iA-#sE9>z>UtVUB(B`>>?P zj7BCd;vLu8q4(F_AbF0WR%tF&N zsJ|aIH11YwwzL^zjes84lqZUB7&VX>B~+8LGX0oV)=aQXPIvB9Pu_=dO&wbP5nn03 z@AT@kgL?1vL>McNaQPfpZb`Q2&F7tt%^KXcPE~}0asp@NnTDOA`wvd{f{;3cdBm3_ z;MZo0psfW3>a7j#;~PAOGz3D*3j(#zsC)V+psd^rL)6CH=GOg{TL_^<;J0Hoe?@)> zLH#>WEVoM~jhA^yRZBB0x6t z+8^7m8W?lDn#Y9MqSTnO15L~)naO@ERYo9^TkM|>r zT78PapR^m{37d8Zw2qN$MvX1VZjO^`Rhp3}RaP@iTs-$jTqLiNe8n951g79jW2-6`sD~G$me0dVn2cFhZPERpb8J}*73C%$Yvj;Tx4rm^S=ap^Z^^a{| zI!!Q40v-Fseg3AurTT)kh)}4d0LPvufy)*AZBY{KC#Z!wnw%@!D@}%Ua`bT=3K)2w zc)qfoU}jb->ZWbvKSAM3Z_IJ-gmsT-70kuQ7DrwAb_y>T9(sRxk8X2Yy}TEGQXrG6 zN!e9eJ2u<`K3u*SPoJEmPv2S|Zc(MMi5Cd}gR!>3W1bUzw5CpHS!8B4jAk{@iXttr zj`{C_d*Y44Qag!{@C}%}UQCRhCr!D&bt!OJ%U|`+d%Wpn|4Bt~w`bz9a-&bfUv@J# z@t3!os0JH0!Hml&=I&Twp;}`fZ4H_5TqgfRl)e@ToO_jZ@i2SQ;|QZWlj|o%<(Ktn zwEB-56N)>+y#v*?d!dJ+XVAd?VF^B<*rcMFI z7vr0XfRpFMq!zPSg|wAi<)pv9b#YlUC7o#i`bg0rpcww0zl%0)=4rm1{JDjt9FfP> z`)b=FB(1OhoXf^piew1Fw7A>tqVm*gJ>)5PM=lMIh;4}pG6|ovznm(GiOCf9I~#cO z{Pp1DCnJJXDlM!tR1de)`rNF}wVAWw^C^uk&AR+)W^VOl;y{Uk$c^I6=>1q0m58yc zuKT0rI<>xOrTb*vdPcZ4$j#rOO=*+B1$1R+5Ki1Wqudhq&lv;J;kcT=)&!YOji8!zQcxm8#UbIs5#RF&{Gagr1Wk?TUAx8BL_;9nIs zl>o^f3Gb6lWJoTc_LyV@JPiJsqj(dRADz}~9V>l!74;>QLuZ)%W?0x`9Oe!(zOB@$ z=ngd#&D5yi>+zBKWQ_dttgt|qa*UGZ&ejiBeSggnq-fx&=}uXG{i0zirY)oB{^Hkh z=W}_XDwsU?_Yhmg&HxD?2Q}{)*WJPMW~(*63hSb;WyT>vU)RiNz0O65e`7=I=kGB? z^o!&gOsEJ)3>wwG5>>eJt#)b6Ab6ylaD<;OomToF9G=oMn`A z&$eYu{7_yf+H#d?ri*DpFB73DdD~4e;xkMmPj=6c-lh2wt+|f~#zZ!MxwH)CYUrqR z*{PW1>=X;?Hm6CgP|R^Bu>TSTrt#H&4hT7<5{&-{=x6#sYPQhLoqX!c);% z7BSCwpQUD|p$0-^fp^=4d4$|wl*I~Mu|F78!91(VbdrW)(XC3y`>PGws`#viNqhoh z1i-S;6nC&gz%UjI6JNQOW@-bHKm&`g-J9(-af6$l?5CrmVy3>Q%g&+O-u{rlo#OEk zPAHJqz+d=2qf-_2o{}^Pf3|n3bx-3{5R-EIy!=mg$5zCY`>8~NYC5sk`PxF0ozi>R z!k?Q&c7)lwQcEjpikcX|hiF+%Pk+FkQC`F;0fb+c@YBdgjhxWN5fJ<3NyydjRAl7O zxQWTGjYqu-tZeODs2n+b06Ob(%(LyA@D8ubqwo)X?zt*LLv;Q?4=6jDy+hG_#Gt>& z>Jh~Emh*M@Ahm}rAd8n5m@OPRdz%>*E%zM$)OR@WrHchA8axEr!A6e{iVqICgosPM z?TJ(ljYfbAcb$>asz0%}L}e?2@yWd<;=JdCae6VMeDFn|2d=Xc&gXQ#Nj0=0=;t0v%C- zwXyN-bczfoYr)W!3AbnOI@prt?dzyHA7~QIg+R#}b<7lbB3V6Y0mNImr}b4NoN|9v|M}v?%ala-1*3N%54o#!!wNYRU|K+8QPeejL^$ascqzv zK>Xm zXh_WD^-eYyEn!pY;cm|hSWb7H11Qt8WXD+FP*u0MZ6h8&bp7puJ!sn|!}acZ{NCAp zQTb9Ar6bQvTNITMABO9l0n@=0c}vceIt^RE1gj}6TFQ)-s?hmJ--zfQtv7N6Yy!=C z$+VAhXWn!0%xZ1UL64hR%M=iewIEgt6DqTwp+6byx+6e(&*L}|r{_RgF84TU>1jH%ccI-MIjxKhK0ETe$G zY?IUJcY4?VuAM_S z(U`m5_!h*@ntKg0P3(+~y7eXEEX_+qA7T-y!#9v?>szOjljJuxT;UY^azf~6rKfK3 zMwM<9;!LSJ7oS~QCy=(~jJQ7a>As^mf04g^H(Xa75BshaJ==)ccFv~+JuJ3Zn}!+i z>>d6E9RU?R+Z>EyYYk*WNzsZ9xy}@X2Amv!u(*H z_g|B(sz5$F>6xUoCE?xjp23^LVVW#^z>$ZJ-TXp*p~vIa$goq=n7TWKW$8Sb*JD}h zQRlUTLB{s2WIUYGPD@2SKm+9B;Z7mLi4+P&cK%VmN(~y@gs($-Brev}4H~<6JY7kO zworRfUt+BAN8at4HY8EF%k;P-TrVCoZ&P@J8kjbrF0NfUS#eyafwzYkyzTMSvHm{o zjn-@mqtv{@u83fTE$nuKj3e}%5pj$2g05Nt`zBjn*6mW_m_|UL>OfWORboeX@yFw= z$@%%bFPz%gP8e#jd-s^MbvwP^&Y6}>o>S7@bTb9xzy&C24uIMC4RloJ19`aSurjf` ze!lOWXB8T?0E}`g_=(2zt*=Scg|eyWV>ow%><;&+k}t1-4~wF!va+~di0*D$Szn@% zmneiEy|ZJ#AZK`Am|oHL^E>etL$QB`?tJ-~gQtu~&-#;b?$%t&wu1f^1%S#ney+}` zO5TWy@4-6JAovsyysc=!)J>2F+;mxDn#Yg8C(2S1m8dA|v^`Y0?`G-chP}GdXeSoF z-A@SCJdIYB`UMVc8-bQ_T&C-cUSDM0$mc-W0KK%FxhBCQwEoCm=EfyIX`iXDtaZqk zXbFc))=oX&{iFsu3DYDGj}3Qn+dh`$dU*a_myHq9)?s&MimAYGZEby-jHi&6oni0_ zn0ry>p^Gp*I4G4H{R?t!&Vt>}FbB=ua{cJZta9Xzy7IEcjjVpUGw|;k^6MWGC7d@WuyoNs`Jha6JQQ_Oc@>^TT&Lm-pZWqVx%k z?aS>8X1uOlQ97AzilaE5ZXd(G68+5{=>m4WU;FLuL~WtRBQLe?+gXu!qJNy^v9aMr zSSF`UTls{*-4!nu(I-Cz^_pX8YmwRWkl~se9F+Se!CfjVD%~sLl@+{>59#?a1XRP= z!bF7E%KG%ebG%Q`9FFjzEJJd;=CePKmo2*19@h=@i?S}-WwLuIs=k{D{p*F<;{G|_ z?kRb3T?Km9`$Cxomz-x77T-0PD$m_j6-8@yIM}yzg>^+{eL8nF#;p+D{1lWv+5}GP zTQhA`6Vq>C`r+By-{OxE9h~q0rJDn)DU@r(=#c{V$J%pVXQzQTM^#qaCeK!*s;Qy% zEi$S6m(niO9ugQCQxW~W_^Y-$2R)%p>wYJ(q))r*H#GdY@ zkn*%Izg;gO2FpPGm*$@gKlH^6TXlLatnXL?1p8kAY{OQiyU@#*oUvIh270~RcKr{d z29A%JB7?m%kpjo<_7;!SEY#w;8$!Izz*`<&0K7Xy!x z2NlKPo&j0b0Rb^+w0cw%o8Jc9&4s+-zHX@R0pFN3Z_X-bt*UC~Q|sKNkux;F6}#n9 z3W~k?K9HoyyTlduuk>8CQ<)(6kLb@S{Dsq>kDTd;4@t0ff8O5|*xmD5(TMkx#@+es zDcJ65M;+K{m|v~CscXuqWCftW(~4P0LdA?>2ascU0-+mY`{N1Fm_-kJ!eZq64#BF@ z2U)!O8=(@9Sp?(;R1q*3ue|Op(uaW?R#Cy$)OEDU z@&_!b*Lmkm5T-{~R;DpaD-=B013U)4N_4c7kQ&JIwSd9niP)f*l&6nfNaXP`caQP0 zQHq5P&aNWMjr)&2%)dKmt`-E?Gb?}K7YRlDgUH{X=y?wpuYK6?(s`)4zL)xgx&48? z5PUE9f{(m0IEw!OQ{)5d{AH$kKJO;XSX0gZiuhHjSwB%Jeqb4=vKZkkH*4KM4fkPd zl`2?B9uh~uViw7yRp-I>M^zYPRSXh|NmM(q66Q@L5>_VG8gYw@{Vq?8#+SMO(b4O7 zId_yu6=8}p*+1}jSy?Omx&6OC9F;%3Zdnb#>gXo>o~jd5V4C#JDnrl_**oWQ$Nx3! zpnk*}a4aC=Ytxez8!RR#NE?Vv2BR-+tV%R8Ml>V~6S9znifJ0aj}Qsii6wxvi*{gW z5qY#&coNC?)~1&jLp_y{o8*^`P$Yi5idD82m5tfVLIA zH~X@#j$Qilp`}WJ3Ar#umgqjw<3fA_ueCYR-PCzN-5sXD7k=S3O5@zW$4Z7n0Q7q8fnF4Lyr6l*q7mzdVG2?c=Ux;-h>76>|-+|3@)_a|QG9KS1zehV|2l^$iy@L36KOI^s3$zGgk4 zsre7;cOHcc?^!*uP}zkwe80Q(UB&6$Swi%9y+?iLe30nB=>~A~Yk&i&mAG?VNU+W{ zYGzBYwc%?LM#T}<|ko^EKiYzd%|^Xxzy#`Ml+&CKu})DLXVp0$Q*tGzaEGi zU0(f48c4NY3NN!hn>r2L3()BFNY5Y?p$0dLBa)g?@bOW%wF!s$ zKS$la@Aa>5Ok+w5_qCpB@g7|cv_L!*yKy`GqIcChZOvWlVm%J`G*t`g9vWJ281L8^ zlj;?BS)TCyK&9+|0TZTG+#oVrAOzkiN);`rtmQ@eD=UFM>tJ^wt_O_~*BTaiV~V5Q zG#IcejSs?jUTI%<71Lo!T-;d7Er+wJlzY}CWr~i$w7?S>!4mrZuv^g4$^&`|f8XxO zl_J~CErixcx9heC#M)vnaz}OWV?q^Y_(YYWURZ3OnS4=bxQpk#!i7xDYJg6x=OV^)B<<1c8l zsSWE4IrL8p{ioDV0X@+O)|xSOyl(4^d31ikVOVma->}PACI1kNA{~zwbrY(&aOUKJw4KfpEcNZUmG-d+vxhIOso=(y=kVnowHNDi635 z%tAnGnFuWEP_LO?k?uNbfhrsRU)aRk&eC!fXXx%CpKDVEhkKr6&j?cff9$<=SXIyW zFTM|r0#ec-5*C7lbV>*+VIbW|m$anEw}dpJG?D@W(%mTCAl(8Y-6bG;_epri=ktDk zzklw1?)|RkIeTVaYt8K0Gi%n=-g8=uDJa(7k4@jUK1a9k*t@HQ#eD3K;hr;(vbGGX z+JmyYj<((BXIy?-a=HI1sQPIvdK0~>eNK$2r?Aq-^7P% zb%pe6)Hgm_2}#bUT5BYCeY9LUG^7f9W@%SYQgsK-(PSKt6{r?VlvE#-HGJC`=U zVXL3sf9mM2SWjRJQe^hTi7};sa<<6}X z{L)v*W**k;vwkDNiRdMcdN*%;`%r86Zouwtq_?r|*Z-f{C4acFOC!hYp*5>E$nqO- zI>%sLz)CmWuPI^i_3^50PQIn!c*xFU$8;qq%;1f*REUc!;jY)5`_?uc#ap#2{`P2b zFM>h`+lXf3ZdU9UarNA?aQx?%SMS}p7wK*Bz^UWm^L1ULWf7;JBN^?-9s5n5-}Q%& zanNf0?K$2{F~y8&Rj9CL`B`^H*~$u2&97?IKT`_EM) z+rR6Zm|ZVxELM~MAU_f(G}IXODODrTlwin=A!p5ODA1z*4%15uMr||oTYGuG{Kp=0 z$%&4skGu2_hCGP*c`$4+&d-VN*{Q-WduNxP&JNbY;y3DFPY@hJrA>3Jb`%{M_+xiQjcwV0RBzi+6D4yfxH;1FMnyPx}+|s?& z<)29X(=?SS&ceS6{QL(^nB9Q}cT`P|(7>NPXAUnrK|u(nTZOS~{P9|!e{PJe3(l-I zAAMOV;+ZsG91L)KL9+42ChJ1rtJ^HHnWCA?L=emp!P=B0ry}R)@85BXerS(Kp89^E z@WIOZrBdE;1qY(*gxyN!*#}3DM3@gnf}?&smGJ!x1cE`?7>18e3g-WuiTcn#~_w9ekeA3jsrg$89?;-`cn<0K( z=`{I7{?&1bD}~C!hiR{=58I@ilartcTJCYFuKY2$oEKUH+J`jeyE4rJ0tnScM zl2BM9rOHwH%m5nRj06dm9bE-8bB&nYB5soKj`5@GPaS`5uTPt5(kQwv zoe8$D-uq(ju(gqGpF+wWtWD|A<8&Km)=_WCsja{xThn?PD@Cvx+Mu9s^xr*M zf-^U<0!k%NQgpe@3-@6GShlEkegkhuE6Qq}*?HY=zWTN>7n4C0+1zcEKXB)lXnB3Q z#TZZg^=PB3jJxmG37yc8M1fD3-u+{-ZYZxIm?Yx~l`exv5 zAZmlL0aJ(}4eYi6g!X;aTC^VAkG!0D6fo zi_R@~-w^zus;tsg+;h0$i3)`ZKcB-qpHliJp+f1sH6!6byl>YO0!+8ZYg{gV{Pwsp zwQN6dflccmK5Z7cf()i8@*`fLYjq+K^r9(8kgoVJ5gi1-R`e@kkF-WKNF)rQp9!Ho zJl?6FHZyqwMakmLlkDUCgoWT6DGxaV{-BNomO^AqHjNt61bXH6++#w+)gB6zywNS} z`>E=2>+$H@J`ck_XI4Y;V3{w16-BS_+eainvO+X0SW0-26v1gF5-=~4aQVL6R&|A< zf&g$!U8G#h^q$R=}pK3;xO;kOJ#oy zMW+v@+`R)SUQ0wF82tA}dGcT*`vT)Sh_|%76(@=Xeu@z&^f`>!G(4o%(v=YfV?7FT z&1{E-5TmB~06ScwI4vB1Y=Mcs%6HmcIbzloZJmjik3RTB+E5m;x!G7~s#m33s7JSG z%Nj_`A8>0ABNQ5z2$5z6*CcBp6F`;jgcdKq3&D%%x}5r5-JH zFaV*eI2Y*Uxz`Ba`_X&dv7dI+YPrdl@w(-^&L16J&y>Z9{TksjVtDx>Q~3u6G7G-z z9s@FP+12^Jo(K@f%lAiXzNiM*HsJ($LFOZAv3h-Pu$UhXAe05z9<)~&=pOqOmTRR< zDOKy;>tU-h(&Mq0Y0qq`M;yDKkQ&Cu0!H|kYyh*?A@4vjNTaCwHB5%rxvpQ~cY$4K z{IA6i{sEqp2uCn6HB)*_i%6agMhfZkC3M@@!C{!S2haN!E8Fi?(>Suxe5d)*G|t&X zPN%T+oi;Ff*J81_0TleVX$zfW@1s0WP9QdGPU53W7ccsFK@g^f|45@(KkoW!b z^JyE614UGaTI?zzjU|&d&Rc@lNiDO&Kfwgmtxa{1ky|mvmzYR}9Pf2d{L1{Vwee;*HGdN>h#hts8 zhc=>nW9|o+oD&gZ$leq}l95t)&V5Qa@(Wk_UdmUy#g5C5zr=LVuStM%s8w9UnU&Y8 zEZwZ<>!QA0tcCw=1|k)3L*>%yJYib|*L3XFd!+Q0p-?0Phu7?u6Q7!ay9qPRNU$XH zG}n%#hcV+B+*>`gU$EOZ`(P(^@E-Oc#0du_0N{yL9e>@hB~JTOw>eZYs4U<)+8Rpi zNAc>)-1RAl*y$M1QU3}?Md}(LdqpER)v7H$lI4O&lI(rqpk{+@N7;3;C3HFfaBWEl zdur{D?++dRW~v#pL-Y2TxQPquYI15O|=fV^648 zRAC98X}BdxwPSQP;B>{Kq9R>Xd41HUjOd`M+O?OngK}BN=$b`Tnd+BuEuOHtabaLQ%=QOnLV04LxPVk;1pYdY9}2#}9CPmzF!wK@=%*U<+wYX@AJ=9rw5f2C^F z4n-#f9&jW4>uj_381XlTv^j7W?!&?1Lh6x|7u12DMyaZj3Mq+s&Zjb+Q2;aFL<@Xn z+8xsGUf%DditosOeUB};(k85gM6B;MkwKhRB9&krI`zMJ{@g|o1{lBu{~Ta^mhJA* z^qTkl+KW=~9?zEZjp$e>@;H==DvD0hP|YHo-(Cm)@zFVM^0lcWqMp50||zWUGM1`EX!gyIaLI@cNoz z_K&Qh41v^xHtkRCZi@ahTJ4uVpzbEvEq06xI9*>3-H+@h+jC|cBkPh`vu0kz<=+os zma2BM5HWw2PzgoJ|IJ0IE`otH%8)vGS!*d5o_of-j?V2GW3g%GL}uGH^X|SQ8?ZknT>JtKrfxnw;z-Lo5G$H+3}U8UBobI@jY3Ki-K|(je2Qz(l_c^y zyVTXcXiitSFUic>W@jOL{hCwAWesg2I`&c8P*lo)b8$KASR~LW(~tse-{C(I?hOSF zSYguCu&xn&{ZCQ=)?LOEUL5Rfl>bPB{bX>}LFNt-1FrunY203$_&0%ST%9-<*!bZz8BQZ59fNHdPZ(ZnQ*S!)dsCZH z)*H#fwpFPK4u%OrQk>tl6gjO@XW@mS2=VF5-K&DDvZOZ&MTFP-R%a`Ec z3_g2lao+b+#iH^sT@C=A&MCs)oun5Yd%rm!2c~xMDx1l3Ro&MS#=1QxfLc}FORM*HTJ~E;a6bIpATYx$OCrq#1s4zWb;6FR6k?Q#W znfs3%)prI$4tXc6vse-*fm6OmA}Wog^QtoK;nnEG@8WO{(5)^b=uP;%rF497a0fq_UIm3PR30j(F zFU2#g^w1p2)U>Ph>9S((eG(}=pePyG@9Oupl=(jH2bVdt8LL$08Y*)+$IBg#v*mjP|p*arO zk`t=NMH%0fvb&HV-ge0W{qE!38&vCQ+&k?r`-40r(DJR_5o-gj$@cppmxq?yc}~;= z@QW{4r+$^42ut#IU$zir$QT!woBEh|{%a##~cjoz5o1ed{`HD&( zJNNGQ_9>(Jbj6#gJj*C_+h**JE`N!6dNuE&;N0BFPzfSW?>4=4>=8`QHb1ksYcRLi zf{Fuqb}!+Lu4!?4$eUbsP9(};E=ntCGNi~gIU=;k^XSG$lr(^OUSLY`h6>XU<`B67 zg+vq%>5DnO>MP@`<>Eoo2evs#*r)`^Ggy4i)6=IbcAP4Bu(sIUIgm~Xe*T0cj56UV zZ_C`fw>`96ZBERBQ}k1)-Bz`=cQ`1=)df>lYI|3{ZTsE$%u8$|-8~6HM|H>~0Dzgc zR&8e4*ivH`{X_s(r%bX)`{986CMZTV4{L5jf`;1QtC2jT)^l0*fN6L#Pn=isV}jg9w!c5RfIP-i4kp5Izi%Zbh}?lja8$T~j!??hRHY zDiGtPe8!9lV|95@P4#r*Qt_$%R$s7n?n|z&~X5gE13tm-P&O3;HXdQ93PSmRdr@Z za)JWV&=V=(jC?1D%jnSw0^uU-g8hXOCZC1ldJq2c=we))1js(0f6_?+!29Iy9LLa; zSW$jnf3N_UzIcmMiNNZptKbYQiu@&s6A_4}bf5>~sW2P&uEQ99@|Upgn&tuEw|=|p zJpiuG-ZCtQkb8Ge-3vm>re^^Ek3g__{50uxO9W#QITw(rU%V=*2hmZVaB~3r(@Lk- zIxwnQ^hbDYgEDZsOzF zh}7PP2hXt$oQ7e3FDUGaBp1&_xKD6qM*<1`lQTPv66BitQ;z;D45=5l{;~dX`xpVc zcm~zMe8m!f)&&F?0Ir7cc8V1Jn#SvHfve$;yZfz#Q^w z_hWYlMC+m&gEQRJY@z4~1ZvMTpO~0W^q<6Ga8AC2CHs2e*{^j87>e1t3s(yurUe4~ z5(!RB^2b))zB*r#LC`r+N?pNfaB(a9y7vu+Vv0SNfVlt(qvdYi)7b`i0KAZwe{=nc z3IKRp87p3R+k3lP9_ny#%i|t`nIPLiQ~D@E2r0TDnv=wN{%v!|5p5k30@MEHT8eG( z)TT5Z@rWkVa23HE+AjO7aOiG}8kmUCct9BCZwb1e`*2brxG$IYrNgr~Y@#+r5fvN4 z1~+}?yH{s$YwKHl5~NyQVId>R>{@n7SwH^;pS1+8B*HwvTkr=-2x2mL>{^q+Zx(AZS0CK*6vP;$JVT|SAQwdro-HAPEfb6*f&Qiy+0M7K$8X0N(i1ED?;Int1f;J z(vMI~e!Q5`h*!nzysni=6kdY{+5%Hppn%_>=7K!a6G^&kgWwx4K`SrXakUXP7{K!S z3;;Z~safV4WcL)T7OmcDFb%x!d;1lBhf|mO1jUYM5A}26J@1XTc6G|m&+qb)*LOeH zL&)G`Nkf6|_{i)G*R;q|>%CIXENP7bzu4_M1pnk3IK0~DbBsCX;4)e*9=|VAUFLB3 z>v?%^JC;=sQVRc}6}aJG{IM~^e7JA)ll4R@?^}7tIj@sM5I(jyVq!;*WAm%pRw~OD zL}~|)6JXWD2|qg#zzmjq`(r0I9sb`${)hMfLJ8m^7cMa{ zA*UY~f{B5JT)4#iTVpsa_`kuA;gK8s;a~3y5nFET`By0*!Eu(i?q9{o)~bxl{#6RY zV<_;{l;l6jD^+a9eEm;MG>*To!=r@`{U;A(Z0&$u;;&rD^VwgUtBKDp6_eVU9Gn|aOoRcJX#2={T89>hxCSOSf~JUBWb zjuF0bUvlg!Me4wy$lzcP@HyC;K1%||h7sg;$lZ>-C`15#g%su&P7d~cTRh(zESPS{ z2~N4+m`Gg(s7>ypWq?a0OioV|Pr@)CLG|q}nkp+swiGPQcVEFF4Nr<=lyu#ngrcan z7T5lSK*qW=l3Kq2Y-t%0ntA{rPjXS1=agbfN&szKGq#5lu@dNb(jBlR;PzhYg{>k9 zASdu?mt`rKPk{RCnR0pyC`yjpWu?M{uAl)D?CrQ_-GIgcQmCu;ik^r5rvFZJM7};CYCa=U6aa!0-IB^k>IPPJq*s(|efNZQfxSvU2bS!Fp6)IR`nAEpicT$<` zkHG;GTm*5!AVmdu4@Qrw1@X4Sok~C3oRk(pK1u-YqSmUw1GTa<`Z~DU3BFw>{*wec zKqdf1`Zdp|5x{iyzZ03!)Bi5;H!jxv+sIl zTHcVWhLQ%`3Y~qcw~7fP5+QsSbZ2BJ&1NWQv2WOX1}z6M$`9gOEo3*f7<=;I6&eOe zn1a}={g7cCO-HBI@8+Cdb38+%(?c>6XgNO1!H<)<2DZ7+ebfsT&@h0Zk5BbLm=Os~ z4y-Mk8qo|*-0T&mvUV&RSo(?<#c8apYP()bvzp_o)n+}B93z2ZL9)YVQ#)UwHIVOV zYfh=fbuSs$GEJwNt`iNT(9Rl24hmOq%***@{5=O1AHZO}9Y5H1{LHv13yK8!^E3Z& zUaGlUFqqhFB8rv-xW}`I5=^=lyP8M_7oOha%brKY0DwS;bWeTKFEwA0;)E;f-)3q$ zEmvZa4;T1`>`x@EjGWHzJbPm#sJ#1c z#%?4s)O!vNB}FI6D6R@&??6GvRYc?m=-_-8KEqr%Z`_uWT?ihx(KpfyW1?u$ zUIOJsx;xKYV3{T;r74{cdN!3SI3FQkIh~<)N=!(r=Tr#h6{Qe!2OUVnBu#I;i?*_% z4`IL#EEyDGrl8iuVF-MQ~J3zMiS)9cPPq_a4`*s?5p5+ z<}MUTGo)jyJH@Bgyj7cW62|Jfq&8EEqs9VeO4M_mrwe+*L-@e-V_k<&V5)W|WfmmsCtxn0 z6NUfGQAs-gfH-y?l)#rb5d$FkifrcmyXI&JgM~OcDCn6KBLFzL6`O9|tn<(K^wv@f zCQy>B2Xhbv$ye6Sv3_t;6L@zp^zZ{W0bqG&Yv3EWsHaU5Y*h{lUyn&sgCb*r4o2H| zoQd;r0JE?e=HjR&>oc)Z&nZJ8<>kZkTRU}t|3Z`1Fvz-*2wqS`hBc;)^Bpnag%q!f ztP_A7h=%~nYf{MvjAva%UwxSapM>P`J!_DmdtPRE5ET{XUUt3<4}u$eA2y#sLH{kz zPy%B)IkLso{@Eoc06G6Sz7EXbfXf_M;3s5b3WWubibh~8ffoqHaML=L0A<-=6E%+a zFg}V0iyR|~4^hr{R#Ci`l1y=ah*&fqIJCgffR zb9r5~*?Ry~XO7{#nU?maJQtKNERN+uVWPmOIn0GH=w>4ZxG)T7?fAz7pN7Q+6<7#C zM7|=@f$yw{hA{GA0A@x96z1YkNPs&I2*S`CPtLN*gd&5W<2uD9haVpibj&~w2X#H+ z`Gk;OWR9FWijCEjK*<&qX1AjJ0HCDF!HFLqDNNMN1P6uUTHr1ugtGjSFHQSlDHI{R zzR89cT8O8VF=L7VU|0G{UcI&@=OV*wU3ej5?=L`MxJ%AjLy}04xHK#P5@f2on;1jd z%Js$-C>(%Y&dJs%aT>kTJjCCj6N1A_c6A`mEZc3eEY-Z@_N8aWH3QB7QJkrdn*hE- z5kp89Ob9`k<=uTI{@1g6=40K)^u7lwq;Rg?iD`Q^I zi&K0T2ZbZB3r@eq^(I^9=MpAx%+d;OSA498-&F;@hMxN1uI^8j_S)&QN zR|~8zSP-Kt@){f_mS@Gej}(AB|FDIj7i~aTGarS7KP<4<-86-(4F1vFc}n)`c3r0{AB&}2;G(bY~KWiF?0Jy z+Rt(Z%r@CyeA`xDGob*}w)h77-B0MkgvDFjhF#BAh@1=D2jig2Y-CW8s02-#rIIv)(fAxNAd5Zc8B5KZyumJf7N^m$Tg zi(QT;6EMLK+!(DV%mcHEzq~r1(UFWw0_IY$!$&#}DRFQV^AdnHLIvP>7RF{x1}w*3 z9nPut_4|(3#(do_Fu${u5u8DBo77gOw!_5{7o5pNxaLBN%RB1e5YAdWBYxn=4`2fc z9~e>WR5w!T6tEOg;*2w*mTpKVJb>A@yQh)>bSqOOUE>k~%O4y0KgwTUz1?2U59YUJ@uc9s>oq zGX0tiIza{bF9ccI=baDf_yG10X>T=){);5Y66Nc@9C;tKEjI_^|Mnn%jyjT)2m+0v ze@6c&^#5K7h=YrqO2hyJ3xa`xi-Uy?x|k3WEDZ47ObCFBM?y?WMoz`Aa-M>c@!~Dc zn-ce#xOg7xF|%;bAT9F{YWw2SwBLI4N>@EbTtv~=@U z{?Jl_wUZ-#c~)iIHCC6VWVV0w$3Q7V+E7z=*)CrVuT^tK@n)8_s6uX#rtOlIyZKni zBa8nL{y)1kd}93*0;Rn~UgCuOx_z{IM%YViiTcUf#SA8z5)Es$?~88vk1L`>CEQDZiec+oZi`&S6S4`?_Wy3{U(6Dz-x$H;4|gp zW*N*5*V<{_pUp+?#Yf@6AFHmBKFRBqo}njV2ehK4X!O7PQzzrPltv$4Aeq#7@k97h zm7y`?gZ-b17v)(L3eD2AmP(VRo=Ix3n8bkxTYj1$|13Sm7h}|w%#^$AJNkZ9GE|!R#@}qF6H>C zTs4R*3~w`!$3$35xa>G@f6K4E@M@i1Vjb;BXKlR94@0v&O&3kNa&I zbD({W?z$>i+p8B?w00UUTdhPJ)(zZy6+mD{W!=`s+L$$##6dzBOJHGRxT7WOVvY+h z?bYAFiOuM_6u?Sz9cts0;u-6Aj?>Wb^WIbM(ZXNMuqv&Xb`y|XRX=t*bZHgsRZUS_ zd$&CCW9=aKMQq4o=N&8hy($|^a8n#F~l_fP1SL6s?VK5x{4S;{o z@?A6~xwurN(%s(olZ%;?ly ze9>Iz9oG7Ty6jinP+e#9&i8b_oO#Vxo*Ejom6*L7JhsPzh%C4hj6YYjut<7u5o<+8 zc7@+bc$1@8!aAHg>8yQW>)5&H#Ki?2k8nyQhSlQ~f>^E0UflXg`}pZSnTL`DjYfDe z!?abl%foE5n-r|g12=r#_2 zx>@$Mj5QWBbK4^PKEr79a*eR)=Xh;+9y6^DVLG<+hXS@+;2+R`hBbl;gulm@e(nQ3 z`8lqo-#|#^n2kqfZd6s=y zA~B7GUO@u#pZGmnc*`N;dHhr(^7%xcFJXMN#7;cm+tfEJ`>=6~hFd@n%c78WCw4f{ z(D-uX{&AQc)zu$lN#96@7%cRxH=DDgrm4ay^7ANOej97_PMb*?)=!ePbfS^E{;T`R z)Q`;7;sxWRDFN5irBZuZBB|Dr<=;S3?Lmm?LblaF&J^AB#slpYT|~u8-;pAHJ;xk? zef)TpwCG^)(#4h)zl@Q(G8L(4h}G8dIapKemDpy;Jqp5X_pe?20V_Ezgn5_|k#l)T zn?qUX#W9dDWRo8EW`YjR5fzbo5bb&~0Lq+%Ws2z+_?kw7UzoeNk%-fKz!sj`54f@; z8mbcU&HMN{9ABC7^o{{rt}tdfoO$E>Xl>T!*TM1S?9j>!v#t(iUVQ#+@%T}0-u{_Q z`=se{+3+A+{M8K2J6n(sGH^*0!7G`##K}6mWYY#32xpdOVxHt2{Z{S<=Kp zCDC5;c*@D*tusA=cbR3WKkuOw&4&@S(*D_bS?W){SvWr)CZ4U!U_X%gk)r#aE0^42 z$A?#Ea#UpP;oy_F0OsUgL!wkIj;DJq4qCPs?j1ENEnRqi?F|{DOd!^mI|H+}(|bo; z2a)9ao5-ho;LJqv8+dvAmTTpEcQyIp`^;Hghr;&F+qH6r_ub`gMcvkj_T~^I?z4Tg z`6|>mRIhjU@3}{$^(&xhwtjWbaGT@m`YfI7mtUKGhskTw?7sorqbr6Zo$1btyQJI~ zZ&%pXTp3ydBiN^YxCl@L476Fa8)OyjCHR7WWMzMUqfyYVO&(um1 zqS@fZs#+G1&G4NjCYXcOnZ5Hx%31OUAFem$BYLV#j&G7v8_x@TMB{$Nz|DtL&4yQz zT(>~`4iTd~Zn^Xr?fS)fg+`?&CP{`{FJ*sP!>szj6&1QsQ{pdcbB!du4UPer5{*OA z&TpzkU{+n>k3Q_jBrIKb^2i=)-IXjHKDt)r;)*OAY31$}nh3lfr7uJT8OOLqO3u(e z1kbtli4wb#c&Xs_j9Puk5Oo)D=cqv2lz`0t@8bFh`Cq8d-bNy zC_|o|XRW4re?RzHzHZq%-4K&@drhfIerIz)2&bfRmQWN#7a`-e>!^Z1!IzKOf55w@v_5u5jDVZ7|K?RYIrx)3R+vm5OQ?HE_w};FKQxEa3bREX#2i0aw-D|$cWw4j9jg85^Yt!g>^ZJRyJ-I?c0?Q?Akpmf6ql_>nC}1wrjl1eZ0Js+QI5u^LbQ#BDaUU zmXn!S7AZv@7VbZ)kf!Z*B{5~WZwfPJnAvZj zAH(If58o3Pn^%u%U%8j`NoWmg9t4DAn6sD(6pUR_YKHep)6MOV4ln65rO#4c;9~fc zvgR};URt7s?W-c~S;92EHnB*On;R<1N4SwHLHXjL=2if_QApTw5-CV3Wr@`lvv*`p z5c?#56K1a9h|R^6iZbRA-~<;r9FR!Oo#B__^~_-wCPf!~A;*M0YT}|CrPL>piVnGPJnI zNFH|XPpG9+XG>6XOQgOBG&sLWwlP$jn6*1g~D^ z3&+u9LaI2j0tZgnIgz_fHx;=kHLpjUG?QzZ(T^)G63VnV$%-9G22Y=>0JlbMb~Vlq zc?XysgjKcJ8Qx4VMqMCbw?j3 zfBhRmUN_SH>GaQL&L+S3E~>kc`^#`t2sUW@^{(R?4&Uddm0*$xuy(Z`@508z)r7-y zBOj}^Oy@~RGGS&ssBaRJU8ejzaBt?8dn{L_jgnF3$HQ?ar45wv*jhK>3W|!?ow{!y z##`>gntW$%p7^LSY>}mEwtLxFS5G^_$KCgSpKwAYx9a6KUwo^4$d;wgd=%C)uU~zu zC%-0gKsNxJD9IuwP0~j34{6S*Fk%Qp4xK7Cb{S@_-n-Z!W8p>;XxXs!>sSOajwIf@ zQ*mUJ%%Ggd)mJj~*_1CLpa1{kiN*t`z_Q;f)TukasQ#)Zy;(f zIOaH5C+n)8fK(ho1qb+dMhb#Zb_Fi-N9S(d?<5xPtm>Yz1xw#X>Olv6$vT}dk#pzM z5wSo&9!;GG-a9tzFH{J-BUE{vXiA5MRPs6K$JuWz`(9vIT9~kESHQU9^r_CP^WNPA z;VaT{(f3#;V_26|yoLS1?@+jKxygUx@sKPphdkeA=-sl^jSCg>*z>0Ue8G{Ru)H$+ zs%_Q2WaRT==5#}wOJiBs*w>ds5^`WVvVfTA43RSEHT@jxu9VHcwyRO` z=nunhWAvTkHgk62yRF{nsVL0;9Pr)flB3uCSytp;nO()rV|Tgk7TH9Sm_o)R&o!gu zYwo`7FTnXvdw{I8^qZbS#Swfy}xGa_wf^PEhPtt}Yg60om` z#OdFonkXFCcgBHO&&35@&EDA#b4yxmmHq1D<*+|QogJ_phKrnHoL?46)vk|!^}ObzpM!_TYwf{+qD%PZDyw7lmxE+v%&G`$KhQ_36}ig2<)i!Hm%)^Gieu8*$0& z9rS)yvPwyuO}}`5108O%@YzjYP55_Xr=G&6Y{Aj!nf#CPOP4M}-%_*PJ6F?_QYN*Q z6ydDuBwt1@e^c}LE?E1TnKEy}bv)Lpg3DlYiu-$4)bQt4PW-nI>Tbh(Qt!(?{Mat$;b{DQ>g5NW0h%!0(C?EsJ4yDs7}927AWEACcY-7+WU8z~L+PM3< zUSRhAg-adQV|^p$Sz@L1Z{V7^gKZQW?0t>y>ci&X#gVhqyaD#a-A4P#>%X)##B>l7 zs6JRjM43VT3H%J2y@|HFGOs5(9frC+usX@r8~B#*)ZaKa%90&g+BMu5g<)EAaAX71 z^kwgr>9fTqyJLu%=62pjS;35o8ZpoMG0#Ac(A&wobdS7lep|wKv**9Qypu*8T-H-D z>RMvu=1X&}XSDurOE?ZsXXi4GNgsu7R7VyYK`}L3D=&^VSz}Zc=iIn|KTR$Dg)fBa z!FA4_loDaWixJOYHJ9kba6Q6@I+DQ?)At@pOMPJ&lXP-M{w3v7oJ)q>(AK8)NRQ9A;-)U;ZFx-> z)mFc1;xll0?tw5wQh^s8wHzK^!&N+rJ8ys9uDk*+ljej!eKa{)(*^M^>;ya=Hb4P68!{QvjAqpz1`_|W@R#Y)jeZjd|NIA(`%cQ zIW+S_zG)W0M&{DNz4zb0_ZKOn6H;0HEUU`Tq;ZMGdWERuk@ZrnRHB%5)~1~Lg3tw5%C9-&t|pJ{#2Ry2+l}JKu*5c>RNT2Cuzfhj z{viwZL14I;pr1N^cJ6!dymHndfb!vHu4KnMa>-cD!(p@L)V*q-gylIqVHwG=uq#_% zpDt>q#dtdkX9o9abklLwD{M z?ER!jZy7$WerBR!O=8KhexEPI{2IZ4Q~3}f>8sU`oNMIsy5CUkvAcFpmhnSpWAJa_ ziArLUe7+JU5e8?nehFy^J-rW$m#12m&AEYAfpNFO!1_3;b9nbsNZSKzgxB%zNe6BR z)@sKXv}y!KT_8-Q1y4TN@%hHVFY1t=9hN9Hk;>8nri+%||T2Nc|t$(RKY z>ziz$xEhv_&rQ=+k%W0~pDnC#u`q8nYCQA!DAy?He`Mhox-d%C8aise-B3Mb_ZygN zO!+qBOC`Bfw(y5HccTb_0N!W6TuW?8PWd#Ga~5~oEkq9|`k@3^c&khx$ z^xDLN?@`62vS8KQ+IXSI|;nJ-NuUt5~VFkUmUemf9en zex>clsn%v?!`<(3-@VMsJV;*bz{r}8lDG>poC&;Ojhva{?fg6}@UgM_^8L>Z&rjBa zVlP+sM@849Kj>n%Xu+5v7!$C%GIZ{dTFCh0W_Fuh-r8*?Icv#T`=NU@(}M+t?ARj= zhEYSm0SX`Zd@Crlajf61$z<0$um_F3^+9Ma0` zjh2szue@#+yM8BO>jEuV-(OX@I3g5E3- z_bjc?mKNXV2eT=84WS|J=Us;dco+-jZYs{Poy5!O1+LUM2FjW=Zg zfs@qBd}Rp6y&H`+7P0RNI3)&xVzcrj-aB9{l(gN?jkuw#`$whiVthn?1`t74N50$nsz3Mq(asM?bSweeBD2WN}1TG+r5~blgttEZ=lB zon(jJaihE)xDNS9lT}zHYeXTYKrZp|&yx*E&0vS?@ze5hs^hDMj`fRc7m9!A|76CS zVQ?}a zl)+{BW4cod?^`P|n?X@8WT*Zzn}V;(_ZbHoPz-R9a}SpA7FdA&J@y4p)^4LmoFrbo7egAo;q=wE+|{w(O0oRna=W-f;V_O*X|zMu&l%zoElulgV2^q#9y=Loyk1@6do%1v3YI__b|df0Qxi}Xs}lvwB6 z7JqrV$C)})AHLei`TktQ=fPpMDMV_hNC)e5M_h{^7g&cn=SOiR1i$U^>pZ^lDqNLU_J%D3pZRV$mnVVo3QgKJZtKZNLhyu_frghetWS1AG07Q z`@x9eR50z&Phkg_ICeGGZTws|u$`n{(FkBor=4eIibJkd?A|yp?i3#BO}+Vf2)^-x zewJfOn9;a!ne;YkR-D{f`>2ZPE^M4}qBu9ahpqyzz3Ul%53w@23? zzm{11^pUR5h0mNpckVVz6NIsR!^ZX#T}x~%Qo5>2#Ee`Tng|+!R`)mh2N21m@8)~j zN$eo@R`?tLn0TmYgvmTAid1u2%6XP^3h*)C?bckXkyqp%@F|5NqM(9c^Tagx%6kfI z);>hKMO28dh{&0rvb0W5Wz^sGwYQ-KeY0o~@Vb+|K*aN1;%1qPt`e!zp z)aIGWENM#l)Dve;y%dq1e(tjUI}v{22ac#_duralSbgiL)HT+x?sy{m>5i?8)tf+( zb@h|kV~XRGZfw?~vl z6vi@)$Qf}sGW4UT{zqFc2nkjyy-K4FTrQ`jDTZHUPdc_-Im1?|Pad4*0TvJVL<+FI zGFgPez>W6~e0>3&j9;GGmzl04O26H#p1DgMZKi&}>LYtvU9hDRJfelLQp4%9eZ!ut ze!z3etGWT(&vg}muaLPC;i+HwlG0&POq={-u2J_}qKmESvG}Q3;2!Z28?J$GD8n~}v)_)jYm0r? z@>)@Kq)bQJZ?NI+F;k8B%^mN;b|m}QuMyCxliGPR>g``}WW8~@te&WboWfUsrqxtG z+IIf9uKe(}TNzG+I_bG?x>-eEE zN^!Yvi}AAw?@fx=u)DwTjQ%}>H0Op_1=sbm_TK>C)Jp%vC(8szUuJzZ^hWPFgl_d- z9Ue9@aARu4v9rkfv~r--rKh^Sanfd)(MWVoKiTlOoQJvhCd# zp98Nj4?|2+Z2?ArU( zZ~IjGL!bXZ&rW{>@Mm&>_XDox_9};Zwi_3p6d+y@IJL=dmwo5qFT;4k z`_brfy&k4=<`2^S{VUo2GO`^E2dU;9I0iN)d-8YYm;M)fZygoq_H2tbAq0YZaMv{M z4#6crAh-s1_YgF=yVC@R(6~FHaSg#exDzBm&^$u26ZSs8d&aqM+;PVnO!(bf{rLr>zk1+z?{we27XDUO{5cVSK-ky!+czdtS zGtqEmeIuC(g@3^CUow84D?h4*pK0pX9~*rB2Ls3RPX!)&hee0S>M&QL(p-MMznEfu zEe*w88fa=dXr)1nt_IuArDyXmEq1Er^fT@J*YH};?M%0R#JIm@0=EzR0c-wn(erP2 zCi;P5|MHK1p`+!}qZhYX$xX&RCd?)B*K-l>bn=_WAHCwl>zpp|t*>kE{rzI^N7?vm zM`s81>8{Z)MfPXGoA#|9umTw0D-ra(JRlj6C@m5A56qam1NQve9fbMIt-O|-(;FDk z0voRJDWP9f4iTdnBQ#+gs9N*0mj1~4)8AmtMn2!U0|=D2o9Lzadp1cbNHTo>N-q+B z1-^?PJf*E=VYAOW%&3D)9V<%k{Z9}&4ACgS&ZK(!JLNqONFG7s|DOwWt}R^<82VX< z&82OzC>LJn#z2;q`+4y7ZSH%E`u5At&cduVRijfYz2+EHEsT6M>9FS}_!DQk%hEh>tk$4(ES%8va8jb@C@H5&R&!jQnh@jQrZd5U(T_ZTxH| z!$;F{Qh<_79ss)Gs(2()%g6Tui|q>fsjnWP9?twG58d2>5_ev*`NOBrxuW$}7qWW# zfe^f<_g2xCpAJfvaC9Zm9q7=Eg8VGt`c5EiBJuTdEyo@%jCVNk&pfAf0GIJE$M_Bq z_zviF=XKN}M{&B~kbabDk|sbl@Whq+&Z%@^oL5G9z5#2Ak|#fC*L@u-8h6!*bC3S` z%=N4TGI($rdr}zk6{IeGj{d>F1HOYSFe|o>L#^#9r}&9f5D@5c^f*2f=?X-_ISOQ`A0| zJs07NK=$}vVJJxdBj@b>5&AAX?{!Oec_-J{CZey|Hs$-WwQi>`qH8w(*X`8co>%#w zMZ*T$ICC&{0taFMqX`Ytd%;oP^=6`7mv=rP@7cX3s2zLY3sS!)*EUfohR_C83 zYv|f4lzy!cGyAGZS{~lLFqOo$0ab+8;de`7?GI_G{Y4kKYYgA_*K_Az_31zG{ku@N zb%(}Hv#;PYKZtBOSFY5Xt(C!r>rDYH8&HTxAq@?@S2% z#I+x#TMbz`+MeBB`-4%@2XXVd7f~brsu}PmwaE(2qTkYLo3K}fs?^1i4K`QJTr!dvG=m-YH)itppycbkoEReALt2DBZ|+M) zfS=jS%=~dpbVBagr)JFC?QnZ{^Pe5}C*=O`WP;*jvq^cnkQny0YQpeOS?$(26y zwXPowYXlU9I2#qJ(I~#s^{`~;R<|NFUFnx z`XI~cF5$T=xbeyB%f@M@xy+8--<4QXaU5p| z8q%--PM7-Uo(iAxZXV#r#UY55|8gz0)!=~fK(Dj4Ao=CzT-ew!S_6E!#rGX;bj*CG z`V@n6=Fe?`v^z@DBVLPFc(}~$k1`DKB^s?qr9|2KBY1Ux_rd4HiSX^|23z`ObZUSO zSu3wp)iPpU(F=OzAp&!_Edqu(-#VbV#hJo^=}}+bodTS99E`gN{S#We%bx$X2Y!~q zz5gZS{gISk%r`XbX)Hd#*&|~(ftY|*av2ZFx)nA(2CBtkUY;E?ccs0OQ zzH;*8tko^@E|HlrJj92GA7F?sQ$XFc>=##{C4(Tr^BRjO(Se?}aXFO~ql@AWu(mG0Shz@vcYvd{9Tx_Yc*vGT{YGH3_HEbgj8j&57s z*;xkJei<@>Cyulj3O(%DOfVBGUmR&{#k$7jdMlbSzhRDVjWE@gepau|S9(F7#h zbz5BAL*p_M?%;=+;<4gnx$vOGcyt~)^igO%rll++TyC#_K-Zp%gIldz`NE#ccuNqj z=i#-2HHY{5-P%9#xu00cA(FV!W&i^q!Vm49V=I>jo4%JAdX$#=6OSOi0}+nyV&xB) zx{V|E0hgA3F~rSPmf3;*^-sLAlnzXTb$ec`*;Zf2w-xdp=yeH|w7pgJM#knuekI@b zSM~oFu=lg`ySTNiL%Sy0d_^H6MhrtEYM4}nvk>#UXKJb5o>&zPuGr9?|3&TJ{y{y; z{$qD+;x!1GfJ@i65it@G)5eAjX@UDTPrx?ll$HN3G5T<%Lz^#5GT0K%(opUPLD%Cav!}i) zVpK|NfYq8;_nafqOuMcnxG-VP94Y`0)45wOhh^{%xBE|Z|N7Ex#!WBqKX)hDi&=xm z^!+&^xNap0-EQj(c6nMF?6nm|esf&VpA=!lfAZJ{bg8{@bn;r=vxFbDAwaIho*@@YhQg1Vj+up<>Ri?DIY`^W-?|uL`5)A>6YbVX! zCD8#yFZwCz>JxaJS*?kZl8nb`SVo`xfm*Zvj4hnh#yWDVs&NMrL9b4S=kf=uSaFbQ zVG#2A079BCj0tmU64?Lb_Kafx9flfNF(SgljaYNcdw)r3WZa~+(+ov?jVHu_jc?E)0;hY=A6Ik{I7TK@+%sLa*k<&(T0{ zz0RST6lOKKR%hY?M{0*HK2f)Tx1mKT6`vlC6=M8RdFwiu3x9?sq1hX|(<~+l+pCWA z?)__qZFFa&4FgVhV(7Hrf2$is@$K~(7WiQWbA-T1Jv9T$LvzUa#KxX4Cl;D|M|WlU z&+o063J^_YBy^m44NLqnpHj+j{n)`P-bMHEnbOd3rf+nKbH{%Sy*YPXCcc~n{bH@Jcr_0wSMYuq?~&~ z5DHz*`4vC5a%v7A0euRz|8wy*?W%}TEam(4-CH;0|8jN4gFXRWCy`l|SxoH+{X|PV zH|HlPx}x6!C^)I*(lVFh0o6Y(vL1eL(;zBN(Rjl{S9P&hXDk5`#dbF3&ZdljQ#CDZw2-1#mHq`M5v z9P_PO?`p@cAgOgCFk~P>X!ve*b1hZt6Anzu4Zqa?ck9H77aV$R>I&{PM7;Zl?^Qb8 zlWiWkW6NEpTgwd_*jm!b=)2eb+MNm0E7o?vu;<1SgikzTi#3Da9NMpn=42qnf?LDH zV6rj|GM>-fv;rv5spc!1@D=vwyg^F41|wU!yRHq zrGuMi-Uy}jmbz&mroQ`()wFAl`~yD=Xps76JUAU(_c2y#po_o_|84Oh+r>wEIL>&c zb*mT#%3Amr0Rl#$%R9ehvA42pyv_!`AmsL%N(I04f5){he zQQ^vPhm?7%WOJD&yVRUkd!sq2PvKPo!SOUZ$COME;fSeSwgC09G2NP-Ptoe`W!-=F zOuoIdJN{ceeNBvc$gl9j@pfr1_}o(70 zJ2>sQs-bSYc}=g0f6J{m3~FBri(LYVMVBWvGWql4L$r4M3Rx=4v&x|$#ilSz(}n13 z6R1#Ka6aT6ub#c8pG8rvKtC)WVn8euz^7LC!U;(ar*YN6^U7L12^6=Qdt@pxCWHil z`m?3SBuk-?;Y1U*B6T>ZpCH&B-yELt-TkQI`s_D?CDCZXx76o|@Zs5q)=$YQgCk80 z?tZso4REgCm36AZW$vr|!C`PCW=?Cfn#G*~%wyHhctD7-?q6P~gx+$>6oHJ+IDcN; z(b{v0+)e>2?YTSe-HMpUm+P!+egJjGwrpg11%}B^E*L@Z|%L|hvwH~(2~Je+D;ep&i0?`2o7t#z`Y@2=G2c%JS#%_>DzY}DA>o# z#-rwrtH73Fz7kYuqh@GHrp3I6hV~mxX;^k)f1__jR?0`hK+H|+R1*R!G_eoWNyh?t z@qnm&{7TsvVFP?x{R4mTJ%2Gq_&R+!vFva2Mi^NAr3S9VMXF}5vX4)Y62uY~P*Q?l zNtd*#lJtIIr6{qx3Gd3%{|?X~03;Z*-Z*l=v-`=)taA+)0kmIxG`pYUPJHR*i zbXM5wfRx}jk_))2Djdr6MyRUqXP?OzMEiC=9t}U|ieiKP0)U5D8P3~IJ_zVaswhQT z8wxIHwVKQ&t2on({By`={mu&5|GNXz+?;XNX-g8^JoVE>?reCZQNxk0-`9)g55c8| z@ZC}znVt3EUvmc3Pd-*OGBFU-hYr;EhybZnr0fTiK!>3{kO*q?-T5zj%Ccq{-yv8_ z-++Z{^N%Z;qw`KxPxYkn&l;$_Zj!Bm+6;DP*Y6zqSRww&*u>cmpL9OV$`EEUxe;7U?>zO17$t9cYt?cQs~m2Q{l;X~!1GR?z-;lN z$x-oo!O1?q|MwukyzQAf74|#J@-P9&V)Kte@2}p>CYU4W7J{~C?OJ_C<+6Xv225O$ z@l-3E&Zc|W{hX+YCjG@bEY(aA5pMt7?|=o@AC=9orgfReN%P(kz99Q8qaiCC_FU8= z5OIlxWA0}52Mqda!udOZFD_hPALm#jm^mas-lNk{(V&Mz6ca94BP z`(>UlhRjMgv!C54{Ko=!Sog2=!MKJam~m25NDy!5iX}2}{>ABdO@|GVE%0fwssF=kf>OEQ;|!`qRysFxneh@zP8->#AWdDuchavs{5zqWo6 z9Pnp^_~f23uLECS<)n`4eiFZ<6C=K-RGo*I=HanI|PB(iCMVrCZu$J%#m8$ z&4#-E8Hc@_wYr;0n!KAA`uC&%THybp1>VbMKf!y2QHN2#ad0=r`L7rLYk_|)@UI2_ zvjv3gP;P4hEs2IYiv#Nk8;8OT`7^n*pTZ9Ro@D=8;D2O+Z+!pA(7Bu0uPICg`^f)O z6Mpk2qeyW0uMYEfK&dzpBC_4TA5P8>3yS7cH{M6Pqniv=?%8bzS|!_?H>C1vmy4+C;a=-|KD4H z_->}|FIB`qTVg}2rt;#ms2RMQ5H{+y=n}$~fZ6K556ztKSqL*cL4AQ)BP_^hgb6m(N*R}ib8Px ztNqU6#qA1JvP0k02`q3(RlQGv3f)?dRuPJ@sYv6wC~NxlSKk3g8TW^YkV%gF zLh-Xu^4wm5L$&1&rAXd+{t2Mx~#rZ zs>u&XS%yS37PZ@+?|~-l;;9j(roo{{wL!??BQ7L<|xC%h1Cn|$GUtJZCvHPH<3qVp90e}nn4DrRMF)R_?*McYE;;TEzVc)!{NWLGH@Q9|K|^wRInow4 zb?y=Dg45RZBi2Ml=FRVbkn(i*E6!i*i+qqos99`JqW3xd{Cn&Y`rb3*U*0L}o zD5OA^#9TTmC!QS#_RTt)Smr%gcZXRG>;=rQ720!$VVq&c^*2*Fkd~vl?WRI|B@T5n zH>=ztzT;d*uA#svCRLslffctfP%=Na$uxKLK(<&&+PWf%Pbwnn6A}h3uM%d(R~6Fu zS`qw-yxiCiE0c_XlEoTisvzwajHDM>PgT^#F&7M%#fp;!N0`b&oPRKf$qs zj%hJ7+O7AC8$QvnL#_%$1DRbvI!|Frm8I(6cOsbL+K`=p5iG6=@%pCIOLiruq5s@4 zo6(AYM*Qr>Q$+>u8S>LR%H>~5QXr2^HCtaIs|1s?zFdq+Q><7fu}NEM#%C4WgO5m1 z)?_Qdj06XhU!&iB2hgS49-i+QmtUIP-yWYNq(r#dkH8e0HKIm{QGME0hb zXWr$lzM9C)@k6kFYo>h;z6@EcX)6djMmx99`VPozugtdz1l}NK@+eOzt6vyBo^1Y9 zKYXH)Gn>o&9WWG5wn83uyR)7ee;o)MvJFclh#h^Z~BPfkr(0xC#S`HRbPl7wRxB#(+sk1sCQlES?BoMR~ZZysfavO5U z^HZgxUtE&R<0snCQeJC*ERZw6_RO`Lr)kChOX^f1x5S_&me8!B+ImSogY1e>dvAYZ zLL1WLF>bYAeHg>@uk7z=%1G>o9`Qnwc69WW&-KwhXlAb|@%sd73&S2@JC06n*OFcsJtCdTduT0GjX<>bkZkG$ zYDMb@Mkq?8D{{Ja`z2U&Kx2y!O+B1(uKC66r0F%U`bdrQA-zc*n0&4#kn)(BQ)aP2!_`hFX$ zWU;pY^)4JP>Dt5E>GouC{B2WE1zLRV)ng}|ewn_?iI-j@xBZq1CrFDMzSZQ>Xbl(X z8Z-9QoPnZX_5JfiDL+}1=^%5!BoAV*&unq3D zV5w7x4Y#gHLokoke-jcYtJ9Ds5b=cC@^jJqz@@s~j2L&uzQfS9ScL6myC%+=8_Ns*AbV^+5`V|lhLHUQH zZT@(Dma*Ash@n?rRi^J)q9VBF0Jf-f{<$2l%@v;>*jqryT~JupbzBePFlMg!v4^Yw z`3f>G`BN?5qx|_{Ww&9*JhrACIL+i$ze06$Y_VMj$^I_#lmR|XD>$`%elv3*yi7ZG z8v0SX*}~v}{YzTSerZ&HTIKW>kJA^=Bh}vY?hT|`X!^#Da76`0hv_Jq+AwE%7IfKN zokqtk!wcQ+!T$BRf=+i=))x_Gr3$<{g)Cc&FCd6ved>BSY!e{vn)BQiYxV6Sv{9}!QB8E6CJh0*JD zy;-;=AfW))O|4$dj3n!f*LjU@^pVeFnoF#1j*F>zqg3>Fp#v)Y`%REjW1us)SPIq2 zK4D3Q1G)gbYC{MtYAs2&Eo2jL6y0*B_HNnOXr~+)G^^c%VY`CtL2`z^KU=7i*%S7# z$fQM?f28z zYHq@|GrDy$8a{Kh)N3eoZts_1v6KTnUm{aUTs26m@Q@frQ^C!IygOCwO|td;N^K}RR4QZ9QT$6Kiwn7ymX`%jW7w-ni z2!CGOw9n%_%u+`8<3V1`}9dWha6#FH!J zx=T9u5$IzAowN)ci%~qZAg-icx5o`%71)3$AkCH&y}xfrovncD#{@HQwcrE~b*k=ZLzKB*KLG`bMMw z3r9sd0RSS7&ID#jPOdA1ajWRDDW)YU@6$-3)y|<~t|-l&mLMSDdLOTqSUx}3>lTVf z#wfVAJcA`GFgmq98mub(F+Q6{!!~EwYE>%*dsDqlREb2pq>ThN!N2*KmUj5Ki}mBq zrp?yX*v?RM*vixG?81J6@~il9Vf$Q@qTt3?(Mf%%EtN5>s{?D=Mf0hgO7?FkuiYr@ z@Q{#;xD{*m5tDnS4%11WKY$U3=MH1*aNzN5B)DKntEu{YT@y(SQuBCTuvZ>O3=(sS zVM`1Ok5a^Up~r-25lg0$2GY1N#UjbR^~LKF#5&cWF_9omSTOvYORKW+$mRO6Fjs7- zvRh~PLk+6;)ywoML7U9+x6-wWjNIk{A&Lr92lM0)=$;pt(#f_m!A zp@EkylTw|?;u_^+lXm97odR`( zN{=@y7mbZ(UYhH7DwdC)igPpq9;P0#4W?9TP)zhLV?DwGRkI3J8*_E@l7q=LYEATZ z{K9}HGEsjCZtfbKy<3M1DvM+pps>DK^dV=6v5lcgh<}7k7tAdj#bk8IgdtuEP+ojv z-i;dH>pKmv1$!&Kq_Q(&ye1L$pv^zwqzg=of-DQd3Y>Dw3NZCquv+)(ttEd0`@W|U z;UN&VSAHL+;^TrwQab%9kHj4ByAF;^=U#9LtJfDHqy4W!=xX;Qc~P7SMzfuZr~J^o zLK{X4=CsG)iBNNRCJx*s z9fl2kmO4PKXI0ADV_D&f?>b8gf%Ght@{^QXcgCiFjhaRCbCE#;496C7fiNFils^hF z;rB@!MyVdUtPFv&2r+~Th9EN|{=i;ww3zWQg9Ok8x~?lalM(d z(>CgvOO{}(0@ugVbqfv`rf~)iknSGatre;3)bG%0c-Bjo`jufAt_c}-4;g$Mkk4?k@HjyYQBcv zTm0}f#2dv?X<=p?=?@y{{v0Pfr3fterT8SdAm{lWltH1S5lJ={Aul@Y_9>T)N#zIF z-wN6*hZQ1MX4cDxPpCiyuR5WLl~)?&*M=_j+5(mMOtyXGbP3at&G1hnqf7yUO3h{;kS2wJUXwADV~sb#6iy=F-qVKKz3FeC*^AZt(^ZQSgS1;CdNIuD`6*}|&i481#awiJvG z&RnVu5}Z%uB}MLAvJPwWzkzF7eO= zSR}B%Fw^$vFvkq`E}v5}Gg4g@J;Ud%^Y(xthw;ap4^~$&{hDUV){HxFuqm4KdA1&? zAiIixJhtSC@`F>U2aM8FKOVvaA5SXtogZD)n9+Mt^L#T`Xv)WNYs#jvL#77%>#3d3 z)8@5==(2NZmRw`pq+o;@5TeIsinHbNY}*&g1jmGGh^i{YcYCjCcY}tsn5YFmYE(wN zu6VTCPezZkZA|qRB->1Jqu5DA+kv{EWzxv}$&Cx1E$b+)2=zth^hP6_!Be}GCUQi! zA#xZMJhK|jc6{L%k)8E>CuYQ`-u~wt_*g3tpmP6vzm1X>j z?Rx2#fZd9RX86x)x9Sp2&Hh{>iiE+{DUiJ=3g;fvZ6Y zQ!8P+_fpf*QdBRkvbYK=skpoZk!P-t6Zr|orIR4>bW1H6)pNf$i6XkHn)J%fy>+A* zX^c=`#J40zwXxA36NZJG@s`^X9=*!7gef}<~mnIhTA2@8)z|(Ob!!saw~=5VYP0LwptTw zh1$w266y?3Mk{)lj4~A}6=x<#5!hHZXf$;PbPkWys( zSIigBV}_3KdLcm_?BpEO`{&>3c<(U|l8e>K{+{gtRWO z9?FkQ3?N+#+adP+=0oAD$k5m5UzEyS-iWD@_qrT#zIEk~jR9h1aZB3ny!c|jt|`^! zPJg@C-L3P+!&gG#lY1hT5VdXI_{ZHicqA2+j^)*lG9~%ZmkB z3y^w`l&}h@1<8AEXIDWs$9FanFQfjzdGg~Urd`M3-8c8>1|u0PV4h4s7l8+tRea&u zTz_f5riKB$sm%!ik7RaYyuiMLe-Tdi(WgrAhPGCbAS7&q-Bs~9FU4BUT2ol?E)O&$ zhrhrw$Um$B@a5qVwHEw`rW`Y^vTZi9AA zgbNS#5l>T#lL35}U77(G8868I4mD#A4Ax3aOisftGNx;E_L6tE2>q6YG)6olm$YuQ zV*O{O<8C_I)wS`p?mWHgiUm~Pc>{%yh>#727KdT;9n;W9ObHIt8%(3SpasQ^3v0z< zH{obvvM=gIvRY;V_QyCPCfH~s(FsyUR>jqY2-4+gOA5SinF;+ePjb36YbNMEoJoo5 zg-uy_cG}ejdOdurg)tq?bz5034H_ZyZB@v0Q`|)8e^D+u{g#*kP&NJ*{2pqS9TWGc zRQiz6n9?STfrIT4MXmkiQyz7)0Zp?wP*UoyM={;)6ZouBUgKDXKjEf80DK|(ED_*? zQ_)hB%@vz&bhWMm&z8C5>YFEdf=2mvIqgqbyx2Ks5n@`kOvN-q$e^KgJ}peK+NVzS z9pGbo_F6z8Yg>_#{_4%qZ#C!jlnUWV*u8b5hcFmdVk+J`8vYRs+75goTJr6);X-J# zgPL?43@ubt5$w&-iWO1;)84ANp-(;=uUt6j;4yg3eRdp1ngAWlNF@fC{T$q(g@{6E zO_)_s;U@z^GtRgO3Cqq75j5#KnJi4Ks;8h;$j8l$8h#7CK3*5cnT}p-A${RK`Py$6 zf1uS1ueqa$FafXP89mUuRcVhwFUf3#*lWWrjgPe$cy7S|4W^PvwYpu>>|6b}dLa#K3nOXXbP;;`GZ?bANJ*TvA~T+km&+ zn7uJ?KL{pRxsg2{Lb2KR-(jI&IlqORSVFdsWNtBcGH#Q?fRWsm?~|aPXfF;Uz>w;Hp`(cNU3( zCG9Xs8FHM8D$#2~v55$jn}U2~gx!04h2gd|P*=>Y%-Um#v4}B0r2sg@CFJ%sDQT4^ zjPxre;B0~#8w6ABfTLQ{nj;Z1;eJCY%Nh;|Oji%hPa>!&4%E)iEai6YQj6?ASA6`s zeN)%(c41$e68FVK;@dPTE;DO^~qVkb299Uvo>ORTwnbEmc-Bf{H}C z&~uFTWUQ)71Pnh1ls-@C8c<49epeX-u~nC&B$X8lA#^f!QJR$h=$N zR55vyyv9KXt(o}M z1EJJPisL~i{HaQRMl*7CqoKwoart*U-b|Kj)l{L8`UjWp8Ti{O!w=X3c7<3pJ)CQs zCvazI{hGE>o5PK6Z-FD7NVYTm4xpqVb8&Z*7ecNHAk+7G8%o4Nr-Vp6WDC{%=(GI; zrWd1)%%Z7~oeoZ0Pn&?4X#aW`J-vC^J^E!tFx#GM#b^QV{QKG|eX2Ky$sx;67w|<` zT+3r3+xCr zXS6pZ21S9zb)NVez1t4!df53y6r3% z`}`Ser8ieypeqO-=TYBit9W7#PZ~>@7hllDi%Dg*A@+(>t`G=zFL!Jzs*L58*80lO zfOveMw*o&nsZYjyJFTje%zh}hb%*#I_tH6=G1(zLsZ8i0Kfa_UmWJ4@Ibm`q_DOnACra*BLUN@p`~l@L-G zfu^mR{*nY~OoD<;$8PjV!nBHFUwp0!$dOOV*h?zyD0Ef|Iw~=gHZujq>XmpG%NJ|u znZgguU(LCj%&#s#+7}Y>a+_uCOPqRy+`RV=PfK@y7*MqYuqp?7Md#P>+BP~oV6Z)o zpgCddx2%fe@XN%bAsI5DO90B}Sy;7E0-c%XLbgu0?Wkao4$?lo^do=VeRMwO6J~F~ zl8k{1%p7IP$X45-9jffx;Q^O&cU4B{c7oK#;{CYR$K&aFQY-Pv19?l?I2|;TQ`(iP zjp!s=r;I#2vrIoRJ|;4q64&iOl50DbZKh^80Jo}Y?m1gy2ab@|Z0oW|1dPU-u|C@n z+#}G?M)gUIYnT~{qD+VCI$xH^}t6kp$8LIW@s>WR-B0OrQs>Qfi$1g>(3h3ftX+9L+JozD2bMyF4kA(O4 zwP;)MOu+!*>4I@=D>EkTD=M3Uu)Gg)jl-MG5P%^|9*h) zWm&};sP{S4BghkPwL*e>>*KUOuihppa-J@r7pCh2r2Vv|FBpK*{(CsiZ2n!=z?!-< zl#g!eQVy2WB#gcXSk5wc8>7|%jqpnUFKLR4^{u)0*Qu{$TQ=i$$Vmq^4b;gKu~*sV zl&heG}RX#n9zJs_m^j2Y*^-4|1rUwJ3e>U#+ zN&R&txad2eQoD3=uaLVwYf+PZiPuV`mE<5vDb}jyl(mquX;}l&@;ji!F^-=HAD(io zVq$4Atd965f~m)Ds9_+4C*8{QQWj$qVS4m zvI3dQ>nn0zhrdV89jdG3E!^d?ym`k;#zv?NwYa7p(r-#1M8!K>%xA*-GeTaV^u}Bn zg}(|2&t_mWSucDiQ>LKlUg50aw9nyqtgrRN<+Pu(E-xaq4~>P;!T~6T*lN^^6jBmjVEfv;Vi^{0>6|; zToIZM(!m+>LYG4)vOv;TA%U)@FJlua8+Ibtoa_CgHNdO)Wf{9hJ>=Cy&uss@4lYPM zHyHdGF^suw_2C=gY<-G6sTYTKooQFb<2t#QTH$KkO)9Q-nqn1VDcXS={{EpQ-6U|{ zIEdDP)25l}1Ob|Ese#Dlc}{(W>2rjs)3bBLx(sasFIkk6H}%S%=MY5E{Z>o4ypv${ zo(7(O!}Wyh?{*#B-jnh4Ie6C;EOu}#k7UVXhi(rH%u%*z4$vn7U@dkmOu@)o`J5X8 zHD_UH-`14-ToUDZ{p|otztODA^y?$kKnqml>a&v7)j9r&kWz4%C8O(xAjrZ?bc%B&XKpEv)Q& z+e8hPpjFO>Z?{#ut#q?8it0rkz=0aMWcs@B9I--uiP{b-k1)S-XkoVdO-#*&HID1> zh>F9qDxUR$AEq)_RAwO>pj5mVME`LS)Xtq;#;=LSEaH^Q4@DOxqZHs`GIGB1f+W`U z-d$mn;_TD$CB3niFspB~*I`{B8pSOEOZsZ#1V;BMoA8Z7pai$E{hvbW{Fh`bZ#gUS zGeNhxZFPT0;V1G)qpV13My~g}5M*bCfC!rCw|pdI}+Ui(riweba$%_Rd^YYUomLk z=AqF}FlVj#!PbFPzU?hDQA^#a)n4A@v>Pm!@;591ET3^fc5&8fRJ zueh9w0ZqK@WLgbN?>}PQ=SH&`cYj$61qB(pXMf#~d{Ocpp!q6cR`I>)l(P0%{w%(*Xq-^z z4eXEeX;gFSX-=~u*^9U9W#X>3xz{-+Cm;e^FEiY0lR$Xg8F4T5rS`rX zBdBNN_*Xv{L#!_TDe*JhLAaGC(#gbFG*hC6Qluu58s6{9(B1JIPGNAp0e>UiqD8I5 z&}rQedj+*jv4$4Y2N`-jUTx`K^66`6UsX5~a(_0j8*T8{T`OP5thuaFRUf!fhh z2OBMDN<<{F3AQk^!2akXp?>d?@;nx`W{R*8Uq0Yg`%F@1BHT=Wh>Sh-UZ@WSi_IHh z7O!3>7~jwKD|4TUXpq{A|7FL1#1Tt^^jEw_Gr zn9d8^q%^v0^%Y0MCv-G194!YM5U~R(zo7~6Mgu=V!Xj(S*fY;3XIhWpeZN6+Sq~j# z-tBdeH;V~>cE%>$fGK(38o8ddtVTmckWs>67#M&PhD44GlDeiHmtM`3p}Y7hCE91j z|41oKK-N%{;bq`9bB^9fImIK2Z)RcYTm#y1<;m0mJJQ51(EaTVy|dhPXiMPQ9r@xy zN!%d0?wJv4pAjsF%4hG4SEyG5jQ_M7gO`m!b%XsAbHb!9eZh=lBKfU&yM|Sk1tCuv zL|>*{Bc?sKEC|L{lKCciE|ON?Ich{nKN7|I97{)>!@s$<%Ez!=9jepa z){K?+{Ts}5PbdFzPUm)o%1tl>J=$mM3yA&>`U4z~sZgU7hH<7CiPEALhZiqFpoQ>|A$+exQ$hx@8p-piRXeU|?Rep@ybRcHTb!r~%NrX&Ii713 z$-1ST%K=luXVz%fj$+ahgJLMuIEwHXCtCNw(2pAghiPVh$C10=0q0<@AxgrH_nms@ z%RD>lQ+j@Et_3*aFGe-$Q81zUUkieR31kWaU+_p-fkhFy)z@$%#+@%jJlohObT#Ig zZ%WzNKzTqHgQeMa%#ud->n_s|QAY=sZucJOJJr%@d5n}gbqY46n^%e~;0QPFbSXbIJ&$h;+n8sKy> zr}J#%*#Pa-r0FrWynWPn1f&P@ zr_A{%eERM7|cUurwn&B&sp6kEFtJRIF&0VbsCw>uELF zAoXI~w_mJ`e0YyxcUWhSQnc?eUO)bc7APYhI>}gIfRO;!0C zj_N1aKB4som;4B~x5M!6Mg5kZ+e{tR%d7Sd>aJei{&Pj@n>h(LbJ#oK=P$QHjz6xS z_@V87tU(8@Z2pPWpBg;2JCZ=Vl82&$DKAPv;UA$FR1kgnp_+&=``OUr>eS#T+4|X8 zk6s)`FZ*_jjRrAi zF?12c?LdNN#%uYarA(z~yC>dCNydrJ5hpMq8RYMjUOyj{{z3Bt2g2vxFIGDXMc8Eg zsq+ps_!;4K9VM(NdxYw{hfX-0xw#p;fl1492GpffFWT6!G=tH!HOVzdFHzd+cC{6| zC&-v_-ts^y&diU9-FiCG=$*&86$P7xdz$bYZ)pQ_5yt3hFpeqwjhs$62MAMO2u;y>EHx46&%d~W|GGuC<)tME(`XvrismJ9hINbgc%utHK z#kDt`5%qB0jHQcDyBE(9m$}#C=$}roTl$^_KpjMnL2h=diLt%|-p9m&Hap0lLQL)A zMxTlLWj%27TirBG(1(UduI77bGAe-O8bm6bHrsXMrp%$T^)h|vV5wbA*Jc}`^u`iC z==zW&A;QJb#Q7xo-Qwx!u7s$63i@_CIz^^{4T}NZ0_~$LnG@8lFI^3fmwF%F!q8ZFd zA49uv)*{#AOCR!sv<`N5mln*2KNaZ^4aY80xzd=P<4DgFoAuW!%s+#j&PZ#rDyyY^ z38FpK515|^2ip(ef965*O%_ELmIjD%Y~mZuA0!z8*N!8MzRPNT!jEA$;a+uApLJo|=PavEI( z%uO`W6)n>Jt9)G6dceLEkpNk0@XD4^NO8=d5=^b05l{Qx{_^8Dh6_3FAD&!*?qh3_ zE@&@@m^Ma&dob}XDag5ZKM>gY8bve3MUp=yc!_IU`zc&rx0ms$A(3S@E)=Vg1GwJ} zf;#Jtf$vwR;eLp#cYAf>T9r}btEcd^7D)dOTW=W_h1#!ggVNp1(B0h)(w#CiN_R_x zN_TfE-5ocn<=#)c`n>j}n5u zCKPAQ4~mk*4diybk4XMMlahk-0+mhnKmR1#cEqj1#l&Z3@pf8czesGchr$P&c|;!i zuf%NZVXdP+I(*Py8@C5@0-!ak5B|9!V?~Rkcf*{#M~qP%^LL2)G_Qy$1@yS`k?~h#5?ZjUomgK0ib1;df#BozguQlXCz-&m$by_BV`XT6Mh*)@bkmU zU6MhKVoSf6ANaZFr6 z4&&HC^rOo%XFC^{<^^2B@91t+4;GP088jc_BctITUP;E{={$G^hGq_?txQXN$)zrG zRap>Xh0C*d@M&(ec0+1!Urg$V(jgk%x4FUq;?`>&=R#pPu2R9>ua27Vqsl=~{r5oD zij{8XcL^K^%PcRX|Fi%ixylp0ewwB7LkG4z2p)7ICKRJD*M>>nJT zs)&7~CZ;>rG`~sb3aEp0mIimk|2U^fX?-qv>3~Gr0X_eM8IogDed!P7@=_7+2R9qg zva-FZq9wR9X;Qe1^#&mK`h_(0H(D`+ z5t2DVM;;{?nwmGZ0}(!pwb(tj`FujX;FW=e>WK7swm6Xi|(?nPFooi1jP0VRl#*BdL9Phc5c)$<(LWyQ8Ni(2MErzF>aQDcaE^wk3Xlw9tr zSF8WJzdApR*3@|wiY!4&l|o;AuHFgr%M@7;KlCxh_kbBoTW9x5ds2%6+pW zdNjE6x`34{^s2H#V6NPVzI~`Jw|w6!-&RAum#wJr9Y2BWimaZE|7Y_&lI!_N?aWjK zJ5~#YXY5{Qus8K#roT2?Z4ipngSbLBVe*o_^=H`mUCbnl8tY<%r`K+y?D<=?jq|ND zR1*2!bhjnGEU7EY&T=6*-`ZbXZ5Y4Nzh@32-0H$+2>pUiY2B{6X>ZhD6sacv!9x_d`#dSZSQDR>F&D4H=^>yo-^UPj4Ac8&Xw{-7srOvMx zqr$#uLBZeuMwh`&@9htg@k%oc5tIKa2}kobQG|=v+1v zgPrXezR{cP-&0$oL6^36e^vKxUhG&W8`jOIZJe3j|NgB1W6xUmupYy^oJFibp&M#^ zt4NEYFRPw5CiI(^ZTPpbk?0@6;){RtKRT1!CSp(J?t%EALi4b!dIzz&In52Q15Tfy zbg9&=-6Ia#&=}$^!e_x9i^R+m+vzvd$ls~Bf@nwo{+uJj%bs*npCCUk2DD-ap3)j<^{_4*&89o)o%;7R73+Gy}2W_P^gRBJA(6{MIi4x~?&F#(9(7Pbh-c>|^v&&*m{A$LeO@laVh6 z5a7X$|7qibX624Rh5cIbXt02S5HG4j-BE3ySBubxp&fIV3*|oQNG&g5{ zwdFl@(Rh3%HT?YbbUY$$X>@w+l0s>xHN$#Um`M3oF-9eod{*Lnp11sTRZhn|$gS@$ zz!=$n`zE1vuZ}hf{{-U2evHS1P9{Su@Y*FBG}!q`TydcIGl6_C{5vzr=+STWx4J&&~oEA8ifax+S_$5tTn7_}m3AToiphcM;q!BY!H z`#qB$WZlc$^>}_z7v;@m$(GZCr3*VC#449?O6j;IJI|&sky?d!(SbFO36i>xo2&cG zvQ#y#z2I69u9#cCRD8;|o3@>W!!0m+nN9sDm|Gqu2PGxUxH_SZqod1KB|!#y=PeaPNcV%8tAH$Qm$lC z_3Z}QaG=uB47VZJazgM;T5%vLQ1Wk5`@54kZO5y+D0q_?y^WRrCIZshR4H5>h^S=~ ziS0 z_{3ngJax3^c~yqa;in;?Vjd~8z;=uDv(XHJXFl~wwF+4y;-9&|b9n9<4x#&38Akw8Sc8BtTJu3kIhgNn{xxUm-4U&!7%WGTLnSP; z+H|Nid#9Um37dr9ox_CS_@3gkcM5BZvpRenfhc}K8a_#k!ffpyKOwYNztJjc$_?yB|R)Cgj ziO|!@7oERgz>MzJIy}q*!&j?+!2}1tOu{Y~RGlmR_LUI`Kq>5vu1?MgKkZ{X4ww52 zIf}2kMiRDXW*zW6NbPNBwl0Z6x3xm2f3y=UY1u!x_kUfou0TYu-WqQ;%yE#f)v|ZD z*yDB{3=LoQW-xs#Z5Z*sTYsBwj4&ksgDf4i{JcnPX$6NSAA$WZ7?>5XBpB2`&Jz2J z+O})?+@uBKi?vfW?Nz(fgBL&i!8#n!0`t_U&WbWMZUe-6g(5$dRC1sCJxSfp5+&5* z$vL1?#@{DM@wxrafh+QpG_B#=1YVk9>%jHQ56gPMZR7~|oW%lh`gm+pVob-|8L~Y} z%y7f_YnlpFpkG7bUoc8U$X@45L)Vjdg^71Au|9sGGgn+S#mvN<*7dG_yOwY$sVg9x z<^CS{wAfh#qu08t^yk-i5*LtZwR4unfk1~U)}>A*ybG)YB92(VtwV>?Pt&z#ln0^C zvoYfE8=Y1@lX#uSEmn9uGk>-UVGzd*hoM3G_S84LYC`iid2lK zrBN)=_6{&NXe9V>X0 zXzIWZm1J5AZu~3`OJM};B*$B4#z%6?`!uFN9LfU^)783(k zN;VK9tLj>1$uJOBbjzlqCk`B=UvfT4e`4Ma`J|or57)--ucLETTCeiVo54W4_6|Ko zh*mOS(Nas`_y8a{{~nR}rIU?8cTG>7LHv3b;9-adnF%6>=wS)mXHsG|FM1Yi&~H|1 zU~S2_+4CPh{K2Fx6ygztxf1yt(>2Eeh=0|_0Q7wQvzbW!8m_VzRab_z!Aj}iH8Bmh zDSRV`b6<1%)g)@=AbVN1{8xxUKV|``!RvDQB^z-gdSL&FLBx;fLRwt|c5_d@ zRPCJwSCWI|9l@uQ+^nBFqffMx%K%Nc5dw~4^q79E&|2bnVRv%CGe(jdS0clZc=4w+ zF@1NS3*h*Lw9vFQV50D>J6}$Sdja=4nz|{nEM?X3qlGeTQkeW8BTIoux_nJ@YTgP6ycALR+MLd;Qsj{qiOpndx|9; zPR08f9{uMr9SrO>`M3xQm{#+Os|}yfkO(3#zt!8gNOu4Gefcv4%$4Cx9dP}6^MA?x z6H|^AY0c_oE{1RZ;cf>sTr_ft7C@^Nb^Z&0pZvqJ(E9W~W>6aB!g+e?@Lzg6dCb4- z_RZzrI%B^Mb}J;K3h|iV8q5D7B@g~>-eVNbGcOeDH%+ZKE%$I{!;jyWF!1X#_${4_ z`CCr3@r@Q?bw-i5?8tKyUuS2kw@2%_8xnC+^Iq!#9LlcyfJr7o3_wBaWs}JDk*y> ztU)-r18MqWXSC~jq()i14OnMiMQHWh_%SND&)6Srlm(y}o*4W&>OW$!HY?=5=?+G2 z*kWUFocX#AvM13VptrEZ7gM8J3>*+Wxy{JCM_=0*8KEOgd%(IRi2UL-nclaCi#@*OBm;eS+1-Z`j!53E1h3-b83_-nQa-< zI#>732@UR(vI(YDX19UKGLy*p+jDBeD5|Mif^?8E6YT?R10%9x>{S$cH(iqoH+|Sp1^vwWc# zntsmgL!`NMC41bEt(M?I3o&BdV@_<^2bX}|q~azEPXQDkOBh_5b^F?WY3rC~q&G298Jk4jv0o@HpH%sP zz#+F(=6dO2DC!?tLiuNQZ%qq(U|E`J_{Qwb6IkI}xSC}$9k(>Xy60zcj>eGPOCKW9 zKN3{mj3FC##^S(FV{p-eJ$agTWOCXA`;$@NE9IvI1Hb(R zqxvYS%4Z5DG)YWE|Fs2emp-YZ)Hanc#8{obm&Lf^qgOVjpz!2E@wjkT2_3am0JxhlsEWWln%-2PZ|OQQ;xIj4<`%xk}erW}qcXp??h7N{Lxj@~|Kw-0F8VUN6RyL2s5aJA3TJNZ&#P-7 zCTUrxsNO_R4Iej;JR)A!2jld>n+!*&rar`#d}5KA{1~C26fsJWZNaT==%J*`dKWad zpuWSbPxzBorY^0ve>_jOaX>Z(fV<7R)ZWaSc5+E8pnn1OS-mMLYP?O!Hbd!<<&xa_ zrrRpS5^_(%kZ54g2^Qa5InZ?z>CW$T&v~L0Sit+fhCE+E5Pd*41Vo*8X>E*)9?eT_ zc$ts!T2?(-v8CNRi&ML-+C)FJg|e3Sy1KHt9;mdRilPP)HtIpr8! zGFW+(q&`XK_0n(9r#KnsP4A-J2P!S4)WCqsvZ4$->l+8~wozWp#a@)w=DxzUhRJ3B z{i)0y@uzpYZA%Apo*Y(P9sZ*^@PvbxPI z7&aaYv#l#Pg&%k#h^H4zOH(h$0H9bl4YG1wla0*rvt0UZC1hhI{g2@}qe@b@|I{)+ zSdftE$1xaaEo0&(hwkQ>Z)po_n(@>+`ZyE8z&iP+3FG3e=!GQ0NP=_tZ=F+=}aZKmKhD&r*bcWizo$U0U zRrwY5Cp{`E`~_?10it7)EzM>c*2lef3ee#m8W;F8Y{0g)U)PL$8EZ3d%TpI*eF6~} zu07mouniBTP2~bc23}NW{bMQp9gh2zv6yAjQ8k1U%=Pkifod@)5Z4EC&UTyhHksk- z-jbUZY09?snWPa`8Zu(`LPlHN4?kPj?$4&h-fWH?K_-&8L8Z7Zs1jNCS7T>m7o2q7 zRxWgVH_xdczuB==0Wz?@mLB@qkgS_|Iwj==au)SJAN67>06^G(Leoffr{+rtvTy5d zCwzQ4ada6WJ}Y5Og9^mVq=5ihg^x@Z!8_>k)b;8!uT$3v zW+OnzXlcq)XV|g%h6DDl!j};sGpkH@!$3|jhcr|wE~JbkhhXk?UfU&GUW#5#*jPvN zpu1^sNqv)rB1k)%IX4I`;}sMD0-f|bti#qMKZ*<|o?b^+03j}kS_^V7Q)`9>l4wD8 z>f>~?Z|V=S_zTi5<^Dyr``+z8a9Q1lXI8PE(Bv&%dAYu6Hutv229gNttrU>CC$Yqt0FtW%D3Q}4S@JQZ2;1hV`9`X^8r*PwWz{NI zKT#*Yg;`K!=vpPBWz*)$el@|61N01>L3ZL?W5(!Pkm_GnzCU*xzEh}$%`KmD*eQnw zL|jOzp6d!T*S0p88fc@}7dXYoyF!b|F2ww>FtvE7w3Z|&c^!Qmr1Htdd;~e-4UD~F z3cJmFlrO`MLIpM{F_(k{wpVE|Z7vP%k$SJr@!@2H@t}OYEg@6!bF;6b&_7g5DJu2` zs>TXf4{xinu8-TY?MiN3e5wx>%|0iadEG()IMT6rhpCfOS-pXY_sEa=zEeR}s_)Kt zJ{1NdW}e-(Cq8n5QS^PWU3*;25s@OBa_|DLsGpd}kBBE38~9g_2j`8~s+OH9A4OE^ z5}QV~5`PU?0TM_YCIdQ0mVzpkIO$2d@5=W%fi|CeEur_tA4ky8f?vzLp#qz=IvPCy z`KYLkV{7bPG#XC~VUwcG)Q8ArTdZv0@FT28^qcx^PbI>dH_6@$kN8VL6N%$hY6II> zQ|}$Wj@Q7)5ut}}faymhzb5v$vZ9SmRE-4b1S=;;=)Ed}4VV7l%VjrwZ1HnXS87>Q zaMVziIL?h_h^w-KRK5hKUIoOR-+ewf*Qd3{QT=Y9aO+hKV2D+QCnaD?d}4r^tGWaL z(kzj)LbphM$sgm~_$F@yZt` z>XS>-5Wm5Yr9pf}k$Rd`owX8=!2=$`4t!oFC0B%e%DHt({z)IF-%EF4Q48}?2LPB}Jz zRDGbXXD2*unSiX=sC3#CfXomF&)^GxENnvRxns>$8C-(dDq_Qp!rI4TpdA7U5i5r_ zMEg+bfl>6e*q04-EJ{vx3Tl^-rGKY;|Rr|83pX`N2e;$!f+jw)2Kbe~2eIE4fbOg;4m9 z8*^hHE$wu1r72Lp3D7IZp`j|q5aQ`d4qWOSPa`f*QlGYtUA2}Hq`eiOg79eRpTSd> zB-|cNDaFz@x~Jsox~z8od`{mhA(4_FUDel&VqHe3l!DE^j%Rpm(CqiO*eiRmB@uU% z8fH169T-Dh(yUFU)O|WQdBOdO=?4rsDf)N(a?>JJq1?X?an+dzIIvlPEZjTO_Y1I- z6{3&b78f=ncZv}jcXTbrtU3mOT#1a()V(PLGhwf71l%>h>n z$R?^S8<$qdL0JM?xj>A)MAPrAS4vz+ry#FQJu@z$^-&E%SuT>FIA=jk7_wUcQ&IpV zwb(_RoD}E1*%r#QTP4xZ`_#*nNKV=sWRo!Cw{&Y0BUMb4xw`}Kreba4>YyK!$DnRp zwh+$%t+2|s)CKC`!6{$TU3ZdsmK0_rJHc95QJX2Cq;NovW6IDZFg* zlzcBd4GmgrUj-?eJgLTCoRuGV>%=UZVr4ISThv1pzJ_vCkMos=%? zg6DP)?~65^hWVx9cDbsrqeCO#=?+D)3PW&h>S(Jf0_T2lY} zcUy8D$J@L1lBh^;NlztCO0L(lI-{XIDw899^XZ6M^rPOGqAJml4!K5ZV}Z!!1RK_< zv3|pst*^6dtH1*@*<^FHw|5H-s>hvVg!b-I_RNhLLFU`epmzeC<^>UPoVjz>L^m>~ z+}O2WDLC#8T%(}ly}R;vsPh}HtSmA5X?8k8l0P4>ZG>G?cQA?N7^>~-`+Nzg1@n(mUGgp90r|C22YcFq?f7l!Eh~#&8 z`na|ez*+8=rSB~FEsCXi3`C%Y|e3u2^-vE^NSJy8;RbexSuLdN= z5^)J6jd?Z@^>$uf`TBDCJ6H`VIFLquoR+Xu9Vis|>Hf)izWpj#ISo385FCag_^?GK z0bqf}2G6w;Qks4n))1a}-NHGfy^Ht}?W|#$nu$P`es3?`xuGV-tDWO^mKG}A{QM1t zU^3#tI;528J&&fX){TDfIl1wYmaX}yei?zJG@HpvK#DMjc2zIO;mRyH8eZ}vP6~p7 z21}3HirRQ@y1k{jNBtHy4OS0ohPgbNyRpWhch6Oj6lV(KJ!f=0vjo?+jh zr-&=D<_D*?2U}`I&0J#Xbo~&`D~l zj!L5k2rvs6MtTUb1$#HV9yO5=!$t(OVxG1ms3W2baC6p@hy(*VZ)TjbX`plJ$sD8l-kbS!mMbwDY3%3k9Am}v zh2*#4JJ0v6jC!O$yE30i09(`v7OMtEU4pgr7QRbufAbAB;k<>ju@LxIqAKV%v{`2u z#60LbQw*UiMY1yeo2K=Y{QqoCz5TvvhURt2^EW8+V zx=UEL&3i|<3jqih2wD2$F-A?^<%w(oy;)JFR3LWr$>WXC5B;I%V;4O)k?Y&BaTO7z z2dT6A>3V88%$39gR=sLWdEsTQ#=NxoP+gb7*5Kn8GHsVS24QwflR!t={GOdjSfpoz zNfE26OxwC!7(uN4;GW(=j?Td8CXy`Y7^iv!C1(E=d_uge*I2B z4ENNOGonLU0r&Lij-iwIa>q#&tGjV6-4(-i`$| zg0?63814rKe4^IPV5IbCT3N=Bf~0DTan4*Xt@pX7dh8;BMx(@rF$wJNz3y;UztfG- zV+aM3YIvz~FBo%VlI_bZhC2$W;>jUMY6P1#C_3j@?Y3(e#4GNaLi=0rt_Fnd8SjBt~1Nr1bj(6o6UC-!yqj z!%KzC)j2H0-oE>9m3t9`)J*v#MN7Cv_>WsAw=2sBnHp?(zC4DfLH$;aZ&Mws%H5Bv z!M-?k=fSds%eukwMCO*??x+_vR$Ime#zi{5E_?WT0uiQ8OY<^0vmL#TuuIk=sMVnn zMw$M3SzZaFM`9j)oRcG0-ra&uZyVUciHNOrdl#S?{iPrs@A7J_Q-V=J1V*5PVMDGD zG-rgVR^k%U8PdabEzL2FCKRUkOYILn$OXB7o~&~qsg$z3QwR^T->a}_*7nI0$(}_c z9~5IYS;M3LGnvA6v^+$t>sRe5CIeTqMydG80>QLw9owK}o+1mdYf5d$^)qc-DE5Nl zqh(Vg$i@X^U!PSysLqHN?jiikL2^{Qg&3ERi`#ro27~26e#1j5WzCIpJX$Q{!=@}Y5JqiqIx{BYkfcaDTeSBrF|N=tp~JAh{faA- z7(*bz->wn6(sp@&v--vPcKC(pqPkIqU4+U+ap@bB@naqn`KwGb^vMYfCRrf?uZ)|O zweeza+EqsBLVI^JR+uYU6YIm5tOtjzB%A_)Yl1?jCseSQRlRL8oSo?z7_cZH{>Y6F zT>}A1eK2;eceh#QdN|WmS4|4$4=NFfA**F6`C6f)4~Nld4Hkx@WJwxf)DmSmhXP$CmW33cKeFzb+}dM5|dPD`hq~!4(VN7L^`2tEvecen_2*1J5S)2wJpOt|V(n%l6`g-3L* zCQIIIzR^d~6?Tj~q4F9G2}S|Mx{%w|(G~q~9AC%rgc=e+jd3dVqw%puHMFuu-66=l zMR9qmFLAy`R-tG8A14Ce_B!~dQ6|+nPlaO@r!=P0h$f?w@L0Ckg=1$-?}j_gX$R^u zh)s&biegf@Dy!^_K`+y*;K=veoa^CIto8Q6B>BmLM&XxQx}2d`njAA-8&zvLOSyUa zgOSk~y!#%xXVku>_>2ra4%iR>O`eW*<+`f<6VPfCNQcRWfTsElA>qylmH{5xA>E{e zjZfPAI3n4Gk|-DlO3TMIrWk2K#%>Cw8fNPAk=aZ*5#IF0#i}Wkta-ma7cLf6Bx=>y z6$}#&1Wix{5D2Y1VcLbOD>B<>`KPu`NGphJo+9+N|J>TmxCP(r|zu2;cjW1;SUez3v zm5$K~_o4TA6#idS;noA<=aru#=LVyH51RkK+xXj8dTr9V#gC}<3kk>V(aif@Jw07d zlCfKuZJ~O?5hk(%c|n!;bsqcoFCOOzL)l%lOL~~-2y}Bk!@_bYTvaF zQ9)xlvd>C?%wf~7pIG)%-C}2UwbvtqZ#6-wOx?sWYP~H5jz^-a?y4lqiz2 zSU5^5&7`?1O%${aM!pDn;1ty)Uzl;z1OOr2QDp!}-c-S>Zzd@eigL&yZTq%|us`?Z zAq^q%xnu32eY)n>`N(dhpt+7PJx!MooaW3qd*U%WbOg%K_dYaZWzPWF^jTsj{%H4w z(ol}IS1JMr5nIq12CieZnSq55dvrQT5dT`@wvPd<+1Ki|YMX7yrK+xbRw%tq(+KZ0 zY-tejVeAZZtN`v5VpF=!+jN+jO z!O*>gv|kCtBc)JAFA^4x=$HBC*Ngsc$dynfPVPKlx4LEdFBo$O=g%(fD%R$r8j-}F zov_5HelI(GDQ;Rf#%J#_pH`=Fd`p?bZ?GTVKJlF!IqtZkU{$$;# zAlF|7(nmOqN5BsV#;0JJ)ESv<=TjSJW*{)Q^MyUcyrEk9`oUHhG+pz$SzWkbI5{*M99=V(X2;rzSQVQ~}Ln!$!|SvvV^0 z*#~XcJ|3$M9x_%{%;`{Xj*vAS#a`-vd3*h|5KIcYBpBQ^p4slVht9PEa8?!yQxD;K zObUi+{u;&eGvI$gd z`Y()O$$JLyH(@m4l+fIznqPB+-mPupEpUN}mu^snAKvU$mn2ktMMfD7G~OFfHX6Dc%(#VN5YTCyckVnJqLZg80_)!Xl)?)hkme_V ziK8lnf@~Qzg{x3r%V~M6MB%^sL5(%=pfy)MpD7?gn-}H<0$6K6NkikugxZYEtmDTO z6*&wlbxJ-r>I7s)Yef>~Hz`$XwJ)|$uZIc>5StWU#_6Da zg=xC{6Z{rRm=pnaJ^tFlGsuCz@4@KO>h?uA=PfRp0yluX3 zqHcn?`jtGX102>L^J zOP%(zB;fV0E-BuMnXVvkIL(zEy34OgBTG`D&Z-@a7S==@ z3dPP}U!vET$JA}qwFb)$t9(05gtaz(VdM|5)vWh`wr{Z+^&3*+?}(Eb1&()KUJWZq zH!v*TTCn0QndqB@&TME5&;08 z6Jg!f61cKzWI|G?xMcm&Q=iUIgoDM7ffi@`(5(^oG<)llMYh{4SJFGYe)v}LR(z&L zaD$Zv0Z_fcWdYzpONH{CqTmCgSDh&$H}I}-b=BX4@=?Lmx0WNTK)GHC6Bm~^Y@*Jn zLYsvD?8pP|9i*z|mM=g=kOImj(u_jn^no#@)pNUOzgBQ;-J#Q@SSO3vd%!4=%n}y& z>o8BtKaeP=j$Q509Rj~Mr$p=+V)|bmR{!nT{CU!0;h@lG9+Dg>8bo!2LecTYx!LGB zw-1Ubg`LdD$Pm6zDSBvOh+Vqk2m{r!%Rpm3Mnk~K^RulRC?`E-uq6STk11~RopRl# zb)5aA`Ep>rU+9O2i@VW9jk|b1?Gq=uL)YqBHw+QDKTvr8mPi|U5D!yIUU)QGE8zd% zutMhbSY#L2*IG3qS!mD@7Bvv=ni|c1_-X^IjG51cK6fzz{scDej!aCQ>VJS#=3(O zr{;a*TZTz}pmiu5b^&!LjBGpS|23~z^`Tg7E9g0B2h;MxztrN@abd);)s_!NA_okv z6IF+_kGVaOrC+1r##z?9BdP$!2H_i7)-;{2SmSb{n+#%C6I1Af728MkU3__=ul$?S z@3u%_heaykjI~RoW{FF7zg|ce=aSvieNNPvw}#lX!bKO8{vR1XRX}c zW%yA3bVn&t!>HVPx;)N#yf8Ul&LBwv{wEn=A}OmdaYLT_}nDP#3tje$C%=0eD`3<8yo5K)A9uIc)XI8k1Dv%Y5i@tAz ze1cXS#FZoYKE>IaUGbpqx5g?hTsV*nn9mjEGB)MlUxB~`i|Vn?NQ}mZ%p|gg%fRAn z9N_K4Z;5%{Lqt*AlZpVzECZqU-R+gW2?5{5CSTibo;(&Rnu7GtL>JEbd>TFZEma#| zX7G~3DJT3=3nHe86jUN3uC99x{NJ4I#T~Qd+9<&{%rq=Bd)@B~I@vafdqrR#oianw z03%vE-e0i}Um_C4`Z>DukCh zc#gf$lApJq>#*}|U_=0RBW4|!OA1OFkxpd(w=~evQe24Hm@n0bGWk!Mb zYG2OT?CI~fEYU2LYBm~fhs3+4jjwG3-}*%zdzkIF=o?pmwUogJzguM%B*?O%Z&@*z zRWU=~5}0gd?AQ^vN>1y_kmdfYZ0PjvwFy!mnNqo5U#L?4JcOt8ZizxixX6E8A5&sF zAMXMdWGdlc(^K|I6{$bS+$vL5kEj-FbU&r7l5Ykmi#5X${ITKByX^TM#3Kg|_o9F^ zhsXqXPmr3K;%7u>7W%Crgmb0Ym{hA(Q?Q~U84$M@P1IrTclF~4;|hZHeO9uh`4nK& z)b>XBoxd$`#IRR9*nt#@0j2Uob~F`Yopr1HrXrqMp)~&ehPB2j<-PhC&&dt?9*)?c z%dJ&m0$kuLOAsA)NH*{B_qMs^=?Y~qF}1W~k0=p~udLzt(3`%^!>gbXILxYgsEETP ztxH7o@D6BVl&hhQx4fT%;{qBYOZFFxj@c&j>D)R?7xOJI{IvUqS~Lk6MYO)rMBQZq|+QZKnC=(>TP$f zF~gCXuC9&p^#XN=jF}7^JxbeDf+Ma^$!3HmBr8_QOdgk#@nmn7X{rbV?p`9u7Lg^G zx`A2YnPP*`8i)7%WNZf<4iJ_5zSWp7d`$ZSJP&$iuoJFYh)M{}SYg{ocgQFici~%C zyS_NFTdQ}iQ`$|@`5|Mra+cmeFYTgA3l+X?XEx5C4XANcild zlf-%rGs*r{b#sx{d>W^a6O-Cc!ZA+G5SgSv0|;ljN2?`52^H0HnA%)W_AB?}mTzI*9@L`Y
6I zhq3vO;=}51mh^{ybQEE;+8LmgoHlb}2us7sG%XIn>Wo={MCH6GC`O@AYQm&aaRA06 zqeMG|G7+Itvi7AN@Sp$U)Zg`!LyFhY*stWmdjfwZYPT?!%t#l~*i6NMc|Kn}6O|8I z{VNjsAR|<%hl%ye6#ro7UkJuPiX)26O#&k_k=rI{(_}=CQ$3+axJ)2@Sp$cq(7A*+ zr>)3RuG_Z)H!KiFpcjkAD;kNd>Itk}-P85pCLu5XugT*q#CI*GEezhl9r=;{<=IC_ z!08%6>CON($A%+pXpxY9?wjN zhktQVwbp{v>POwZmf(>tDx4oceJye)a>2fLeVOC$DVAiMIIpaG5qp!cx?112K{DeU zjA}IYn6c}aqU~7Aj4W_pHS9Tmx0xrR1Fx^1nwZT=<~46xI;Rzr_BwL(OL3*@+Mx43 zyo^78>#?E;wowQTt*i6czfc(_*fD@puScAir`QkDBWcD!B(pRpn!1)GpcmmPBMzs(TcC0eXt7rpWH4d~m61(!-Kke*;}zpYtM zsfIq_uf*upJg#bH#^O#d;APd(9W^wA*P+L`jkLwS?5yLU%7~*c9cd(F5kQ zXaAn1@Uj~=S#T(o`To};yLzTq?-Bc$9l)-}(dxbNOFzNQDnrciSy!6+Wv4^!2CV-H=a=1IjN z(?YzpRYVR8+cd)x&l=By_Eh#oau?gN%sYdF?Ii0LlP=sj+`0GTJ--_#SRiuJ%41B2JLW{3p!q0qWN+m{+M}#qv z(eRb_BVsUoDshojJ-nQ}PNKudAS%=5K**Wp@MlYp^SfWFGI&wFiE2xeFoG1T7!tB5 zM2}jZ%ldHL0?Ht4R%W()x)!Ld%W@xXM~Pcu9lQC~Od?esveH_T_#~KcF+1_4R?ApB z$<(mlgg^DH*U+4sQ?tvq7(EVWIB6W^!zD<}B&%=MRy< zhPkTT4t{ogdV=s)(OIs-3Lg8LI*p;%%&T(QqV-&pw5u*5Ja?Sg7_#O>`zg1?F;k}8 z8LBRGHoKj?DLdi{A6%vU8VfDz$PP+t#@G!I4g{4xivK_M-YP1}xPSKsL`1r~ySqb> z?(UNAMmhwf8G7iH?q=v57#gG-q>&VmM%?K0f7HF!`yT9reYOv0!7yvxb94W`ab2Ga z^PjT!c7m3{K}W7WYndK12;;n(*%g^h9LyhDf4E|xwK)k5An#*SS6#^_`UyovBv@dM zpSHwhMxHUc4EX?kQ3tp}znTc>p1ix5i59n3o3EtC5iGFhO@YyJDQgu2c*~5ml~%zZ z+r&94bfo0gIerW^=@oTCZj?Ww_P4ll33Y{Zwcgv(5_j^_O)hX-a`Y-&;l0yxhnLui z_I{`7(ydoH`tCg?;)HWE8}Q^BD;yxLP2c~`k;ZFX=bpOhsxG$L4Oj)a1o*oYCO+Rm zh?Sr8;KMQ}d1U?kg=cArJ;U&-q;NkLr2D?sbM-~7#b;%|^5_(h)9ED_Dzs(!22KM@ zmDIXCzTkpc^i52^H9msd{K5pwHGGX@SByv!TQTga^qkH^UJTz?*^K>03ejON-FcYD zTtWS~F2$McEU|-UltrLLu`M%6O-tTzAOc~`-76rk%FR>W0p&UNORaERWqYD81;w{u zCZ1NjI|X1OGtWL}R1RCVC%u0)ieeF2YcM$T?d+FM;g`C^oa`*bQkU}c_{nwdWC1kK-j4+~c%8L>B@(LJ24 zylQGIrkm(CsXYtan+c1*Pow;Om;7409Lz@q@D)qYwgJ7UATmiLX8!5#XlA5kWlrCd zP~w0VE?tOsONqHqSs0$()4soPsUWb$?oM%NasyPY>C1as! zcwaw^xC7wo5*IL#=T~RFGAKO-RuhX#7IaV|Yg$bKb{WH2{&B&_`P2`d1 znIt`}Re$2!o#}G60Pm(Ro;KJ=d&Jw72lF$damlvc4>d4htqACQ_#FDwlT|@XkMppH zQLQLju!79C@h$w{Gw43c9#T{Q*>41GChe7N%JgfPEIz&Or5YodVdc-F8j8Q5Fxesm z7i-&XYZs_-lJ@Tpw-Rb&`$T(%5g6mIymU3HpidjFH9+c=8017o!qPc(u_y3y31(`A zSwz#Vx-Jw?2qU0tl-CP4f*R zM01oQx2nV?8(Z|+!5X3=2i!(DVyr6UPg#Kw-52Fv4fPy@n%84Whef=igOcP#$F(Aj zO6uk!;>1YT5bd)WvdSWA(adHEIa3a~434%yy@XZTU5YZ2BC1(_s?`snh|R~a$9;${ z#u-dN>w4(U<(Su6L6tjWy%07OE*G$rG={h1wVA3X1w?AZet@_f-csNa=)q;&I!qm!{wIYF7W6Klv+z!9dKm{+cu z>p&ueyV=019&lp4=_krSk16T3NL_Mv5mH97tFVl#aEBkWEQagL(dvp6rCb!q&SS^z zyktz6CX)+`afqJOH7e&*c0~vet+6mc7OQ9*K$Y9Bj6Zj#GYby#Jd6jKPMKWFmP3dk z1oARbNgpO!YZ>9KRv9~Kv&3i+CKeKr&Uu1qo^j6_r^0%Xntxmv%qns1N?Vv{9qz}0 zsQla)^r|>&tymF@KgPq;v-4!7dO5&*3MWYCzT&#@ISH?j4K87Ul; zG%%ZB)HjTm*UiH-dD1$)0Vsi3IXY!s?p;K;cHg59O7ssL9V?vor-}>Q^p}@D-;l&V zEsf>voj02*T6ti<(9B|86na~YnK_^krGV_;| zFjSLOlaH_7cdg*>eB{_J6|2uFNASf*U$we*!;KZQ(uW;gWLcKdb3=L}{inb?zl<@k zOCC&Ef9(R5P7bf(>bzB(sxwWbhaF0-3lVLd7`y;mRaw7qCxSR9ZBJK88+}pU$+=l% zZbmy~1I;Fv6!7ns$Q-%Ji2yTqqFz*oiFgGFFKH{t<=i89Z%fxLcXjF2>qiJ5*H1n^ zN0C+^HYB&wd3`cFyl8jZkrRHb+RvKc92PM596s`3s`43P**>Ur9Yrsn2xz$%jhn5Z z$9sBf3|fWg%Mn?+l5=pN;sS*PK5ZiyT0(?0k zx=_2XUFV!No?j$KP3%Lkb7Gpc()HCCvEkDKpEqO=!gr>s#mq4e2PMeHFkxTM)fljz} zFMF18T*e8`u|vK#z7wA*Sy&oT&W2FDLK40b8%IOdJQ-33E38N;mF=$Z_T3hd1}nOt zFA1;aS7~etvBPbS%2tBQ9u_HVr{*lV0X84vGPZ|SR|MtqBOG65cRWjDO@Wc>0*o*q z%*7_(BfXpgQ5kW2{%(n-wd$nAF4_qdCZuUh45xNyal(+|l>OMEiFv*OVUIneg=;iY z-gUPKZ!kcuF@1&;V4@sVDMPT6h61ZanQcNSscZj;)2y0Bp(@@Oc22j9_9Mi;8Q9@l zq1^n%%w@<#M=Gl85~4Q2Z#~LCU?r41ijw$nxOWt#)i$g=r~BDaKqIa1)g-E9e>4UU z0Ws;jj49RUJBbf#NU<|=tyvOfmV>F@rKW$$D>|Fqsm=i2YpSqlr&v}NBau4mky#0B zdT2?4wXGkzIWcYdj28Gzu@t)rf=>;Ln`{}Z*O<{W>i zV~0@(Mf^8T!*%miPRmrvlEqK5`!(^g-m$q7$w}R<{>NG-lI9|t5qsB&|2k8y+x>HT zDSKB*rA_}D40K!3S(Ij4Wd8il;yhbl>16$U&mz3HwlOP{y|p0fTHLJmEk{ZP z5=1MZHks@obPOJlJ#U1mpOXI8LE8*VZ3{&F7&r{8M24}$BW2PNcl`CU9C%76q^jO^ zemeR?i|gp2!vOs`u#s8(&0d!GwV93$#Gp^a>>s1vW9DtI*_v3wP}~hIf7_9_Ufbf% zQ7qZp>E`wL72nU!!9$kM!k6(7;p6$(F!l)3nB|t&h)*n3EpFjQuDr|{*%mX#8-RrP z!bPO|Y12KFS1m~u%x~Hq@e}q7&}?P>@MJtmjnJt4Jtki}01N==txOJY{@Wpcq;J-c z7jOEaMdb%-RywsnC|u2hVSCH!wI$x2%6QEo z#C-B%=;iwz&D+etG*%2=MCuQ&@F^=Q06LrOr1BL8Radhmj%}v3^4pdf)Zk(NNvrdFMWO>(0 zF5Rz_ubcL%Pgd(IyYut_k8H>q{liD@=aokT)yn1jwf^Nh2!07Vm%T&mz=z_c3y007 zbnJSz#oCo(=n>Kzo0vJk@+i`rfq)(u`oaIweg7>(-1=6yp&T^ZbY0*8A^~Jx>p-n8 z#V2AOqiEp;GH-)+aso3;ZD~tl{^?`~chna=K+@8PhJF%GV0NQ4QRm;K%$Cn~GpD0c z!s%OknUgtAwq)6%QA*9aB66$|YI7UU9VRtey`nzt3=9O>;og7 z{NJ%cBM1z@Eqy%n!Rdu0U&Y?M5&7Sj3#38aGfs)wt&AwL7CT+r6_$P5s(47|+qx5+ zIkxvUd&E}o>M><}6Wo(2wRe#H_29iIson@uF=nyavGFD=Y2Y^6hl0zSd^o7lkVAAXLW^`Zi%MvopubY|m9^X|mfOo%EGp|NPNfP2aVlh;P?O8Qs|I+eZCKHS zEjF??ifk>W@Q8pqgv-6T3M&f$_Pa=0^g7k47j#}j=Wk7WZGy`q60N8fUss$yi3k%I zaKU=Me^p|6u+(CpPnHtj5|{h`L-+B8i`-N72CZ$;XT(($Hyf^N&n>)`Moo^bnmU&g7%+5`%+(ik8fq zdHyg0ERR8xLXOF8Ma_z9BG%<^fdt2(o+%Wt@T^;b+uu;e+2YytEkTw`9e#f_!XW#K z0%UQe6fl~f?0Cc*y^K%{dG3>wf{9&bOWC3NKbVLQn65n43|BbkNL)Rfps0?jH}1FI zK@Sujqh4{J3fRNy8#YaMMKdA^l$byxnBO-DK-;s+zw_+od^YtPIYavtBJ{gIwmfuy zyYBB-GWLD?N7MU+wSJ(^=z2CFKW^;y$#T1r?O09%d;RU#cE=*0a0)hzs+>DbeRJ*! zOpMyew(WOqS>c*QM)-a8S7n8Aa7rA9IYutucXRhJy!CjXxd!0E>~J-9UBb2S<%c&*_9 z7{0+-MHUi2;o&+BcnQm031gGqKLRX06+F6ns=^V`-d-2DuTS5A_ArE~;mbq*ZdJW_ zPw1E+51H(*3>)diB!KyAN2CD?1~xCF0&4ZN1|87UH>VFhhBV=*VzFd=SzTvRrz$5m zv^}O6hRBk$9;{-LIunVUH0RfP7H0dn;lkj&os*oU9;Ca*JDq0X6=cDSnZBWKkQg%%H8`JERUF6NfazCb!?;-u{J=mSFQm>n1yXj$D zL$pBiazjz$(-{ZYDLY%HyG-he{k##-9xE=-5l@!M5mwu&oH{Fhn?n?VRnnQn^&XV0 zh1$dBb(GCadcf=NduV~XVTr&cx~Ks^b!KfB)98t%^bg)IXUi4m$#oVPZrbwUOWxtQ zR@8I1kQ7X(jcs;E{sWzVw83OUTeEi^ElC6E?gI8%b>hI2rIwtJNR*`z_7ZM6JVI*D z77_^YK)B-s;7Ejcp3RCKSiz^oZ=pNSQN#zN<=fZEF`z0Z(Q-agPyGDDB6U$DnbJ*A z4OWX_)B!%WM_wFhG)|Kc~uzd=AZAJG0gg`M);L+J+~jVOLEd(|nw%%Vkco+tWsvZE%_m z+KARn!MYhEpmn0ztnd`IEMD?IcRGOCZq|uHuw~P}F0pmw9`BD$O9R+HPmD>9)D=Tm zR{f|kUJoZ&R`DIxJ}QpyxrATW9Gu#dmiBH}FH;Noav z(Y0(#W_IA~B*FR~WGH3!&V=%Y^3|dS*mO_g zErGnlCr~EKGW_l2{lPxBH~#hPvjE3r31H$q%Jg;m9qWDcgo|W;OUZIdvR&!MwiVt4 zztvHhp0J}ngUjMh<9WN(Mn5=NE@AB4T~ldvO5CFcY8Pbh!W zJhoa!|B%Y8+2g7xN$D|?yCPLk%7B-+WqrsCboCX6D%R2+9pbX?qQ4X*%tv7j^MqvZ z8w0_45)x*Y=#kA043kK@NIFwBp+Xnq?pGF>RhaAK7VYG6P#Gd^k+{>*hM&72QL0@8PlCgAtltWtC_Mv@ffa7Bf1}BAmq*>1gFs zCRlRvAq%C*wCIrMWw0v|jJBP_jF<0+?Q zE|h$8xS_B1E~Rb9#u45>jEbXxW^=Fh)U>Ea@Y7L@jv5J3rVu0QIjonOrx%zq%J|bS ziOmmLxj_k}M5>*aFXKLZ&8ZHWLFG~zM|+N*8@`sob5-H0Ty;iix2>wh8|XHTv^I8d z9~O%z!@*08d^7wUJPend84JC*LWMPRNW$XCwSUk18!tV2j9CA9GX9Xj+&4z29-lZ` zh;g#h<+;2DCs~D>d{ah|;d#zt3=UftZi!55G}VmOz>-K=f2ozHh6U!i1xtW7m|9yW zJQ2-nTt6)pSlY$|DD1_HJ~*VTD~`aKe;G=(moDIa`VMDwCIL+y@fSVi!IweG+L*{7 z?*MQim46siJ{0t{R#OuTq`D?%)MhG;W~X!GQ*%g=i%HXul%~PTc5qaNZ1+A0-f!^t zHhQr}Jn=WV=JOK+=+_&@)vJ&tv4W($op?fvtouG!(i7u2e5uejP)Fw5Nmpy%brOEG zd6nyK~58|_Pku?^qJOozj!z2rLz zQaalo#c;DEzZ;rySbnxuq;otbbq|nUo_>R%(FZqA-iS;E)!FP3X!mr2P6~`%Js&8X z6j7HyJ%{mj7$BDFV(l1Ga7sk|s7@Rq>mcB9piNN&Rv#VqN|>!vhDLEIfd3lj(6sL6 zc9?>LVuG%Gg0eE~aEb9W%O$;j$IEEHw5m$!k}ete!xg`L*Omt#P(XJ_>P`tbIs!*Y zEjs$}Vq>(7i8Rzzt(UJH_es=gvCr#7$62zlIj0$GshTZ^D4lBf4`QD2X7`$QHsRi` zq}7#V1)R*W+^Cyo)(Ca1xrnBql861Kl6hYSFj!<2cpbuz+DBFeMfm}^I%BP>%z z*G6SMdZ}Y+aqkl+>{K9HjzGy{p2Z{;}werE% z6BkPl$82U8BrzC2I0pT91_k5Uw5Y)s*Cmzg*j{79iX?$xlf5YX{8!%1=|I&JFwu8? z=1%g)Cd44YvS^7}T~iu$ljz)4Z&~lwF%}A16UNUslH(RnSNJw%ugr^Zbw@7XckCrdQITBGcJ@$~mxNQU!t?9?iU-mH604_ZRsPo3A-tFkY|6i2LX^)x^f zJdsoy+Muv$RRZYpf+6dR&%6*<7D=Z3FTB_0pP3RR=fib4ug#j%&@fd?yT+r68Ub-x zvPMxi8E)tQuF3$uODu+uW1 zqmx;6r@o;l`dz3vFe^KZF{bZ@-M4*kFa-)s-xYp}R-YqR26HEk`8xoUSrRMTx*I0 z+4l%X@Sl9`F!XsOCc6L^kbqpqYS8pA<#=yc*{l`9qo z(6x@`;3U7dJuh>kDPK_id4UA>NJ-T5e*7ee$8aB!A z?00xZy^pOrC!X}5U7;NduSW>*vV&ykOJ;=(R&6Gq(EmOMhtIAs1d+a|DJRYjVqorE zB_N~0`p}+g3Cdljw+4@jlHt>snG8nUS!msQ)(@Ku(ngu0w@u8b+g8_$CS)J1$E@b( z$GGZ4*EdQWzeLBxn9!TNkG>`PW$2J0?DYf0VnOZuvIp>=ij-cRPrCe&u8H-HI~4YF zTm7JVw4JkkANP*vhIH2FcE9DRU|~>r@QS4C|NZj+(bW*zGT)JnXP@|7<@}4l^ySY) z_>`nKh-Rif8Hwk$n~GY~5;ip3i%o3FwRU2B#a}S2nqO+H4OWbF z2AWhtr(2GPauSDTUuGo$LOCcyb!o-zzvDLa#E`e6A*E~>meK1R1SLvj1?JUSPR|%+ zqgcyyNE3H!k=ma!1~#4<7&b1Y$-BerdZ&(>$2@CvZ5~Q%VR#o`f_J>fRI>T%<<&9u zPh`R=k+@V{?JAs@c|PkybD3>E>!Jy=+#|ah%0{XCwcKF0#}wFB3iM6iLhr3Zf9RR* zk8k}6B{Rs+{yxc!6q2$!;~OFOVNc+D%n(FmXXbulm+~i6zo(L;(T6)iH)TimXRuc= z(G;#OZ|jAYONkZghbJc+r;fA7RlVnQKb6L>ksT$J@P$o=d4pmWs0mqkR>zp?s_u)s zxh%fWF)e~i%=Qk8iy^JJsF+xO$9d-o!IeqYgxJ{7A*ANV)aE~-G@POTr$L`L3@sir zaSC4fwyWdi)dXQ>4EK`_LxCCs6QPJo_cQ$E$G96&7UVjBm{paKzW)=F-3yF@v875I zeoIKFIJ|VH$Lm1D@bDcOB1g~Iyt0taLKu|d8IqKo};A4JsdAZF{DZ|+4 zm>Vh_bQV5iuS{;|M{ebba}dTM?UTAnT$R283G&-tq%$I6-XE11>XFF^cllN4S01|` z+|t@h?#8YsSkZiPfH4f;u*o5-+5z{zgn|}Mn)UC<=icD)uSSj$PW0zv zAzfx9P8Ojbxt1r~0$o;xu5dbw^bM4rY{q!+9*lm?O6C}nsePATZEcgFr|xbWg{BM8 zh4M6COFPmqsxdDk(qV@_IH7S>_AY1EMhud5DK_UP_%(8&(yqkJ9hlQ--~vyJ^ISwm z*h4I~WD1tUz2`OcQ}jSHc1vY!k^CAw-#5Oac~jgn534rM}*&*hRS-b+clgbZ6@bLx58+-_NO^WfDK#eiD`#)Q(rbGxvz#zb9GF ze9a~_mV!ait^H58edpOVdsRJ)je|`Lvbd%QsFZj=j-lIUUe_tT5MBjV?&)$5*Fxxc z4u(hM$LX!wYxZ3}b}bb=!!{~t`Gzw_rXaXVvtf}R_TClWVbAXUEkfW~-3x-iDbE6B z!cNU2CLuw_*uRxR)2ofq{ykRs55(w%B}Qo-$tpIlIH}7{>T?p;109)^Kw|;bycIx} zn|^IwW|+Rvw&d-zqvF`5qj;`w+pxN>FKfvfJZ=eA*)A^XWh@0)G+vh`6mE^$e-hy3 zsBo&=V&oP?p>Qp2?9<*Mtmud76=b+N_;?JvqRkX`)wysaDPTz*LGJ= zVR(ohk(&sjbTlLPzs)W?%X9FsWARse_9Ib`G2r2EZ+ z+U&&c^iiluBqMyJUwUa^p-vo!4s^`g{T0n5Q>406o@6q=L!MTd#*PBiS{kF#PpBZn z%pUY_(MiUB&z}9CP)1Dyz}qIf>fOHK5cfAtp_AiN*K{c`4!HEVq)>lk@=qWCRbNh> zTC65^?DK1m^6v<|8Kcao%hs?VZdV+VE8ug0m$&Xi%c2&c*&?4i>Ax}VDC#$%q#v;0 z-)U@_AfkE zkg*rA-09^f+^!~^*EJeT@Fq0Tn_WwaSdwR7mu7G=z0>q2?R*2=d~R6*X0M=-l61{$ zm;Bq`d)QoyIRo6G$lDr^_`DTp5d#Wfn?+{ab@~l$$(w6aR;_BV2}EN#nl`(}Uay)o zg2Z(v@Tr3dkGM{8v-vI^%qq90vjl0sPvAQV2-ur6BnzApyXuYH9UV*VHOWchQDD5y zx?l0u7;%kk$b6*#YZtIs)U$`++%k8gXl$T(#5;@E(FD!zxKnaQoX#Vh1x{C5;Ov;UvV`OwY#bmCcqSfykS9tHt23sig(IwrrQ zxm#Z$wE~*Jx4{wvFJ9pYnd_9|iS+#PjEMC9HY|KAsrYv7RV1Yd^%1t?7`8)Tji+h> z82bm2p6|4}=8hcnCY(kTxwCE!;`=@V+R7J$7kkop$L~SlYm-M5(+D7zsNQVH%ATiL z6hq>&$Y`l;H5o3Mp3#ij6zO4bQc>Xk+omg7qp(^A%)|Pj%ST`qUj!pM65{^W7 z@ThRh%tAt@KA|sbt{~j{#j^kXQVk^4c17NTzp0xUWADWugKzl*SJ&I(8Ikb48LHY`>u1siouGAJpv@_TNV? z8>~d|L^E~9UhBu9afcXP5a;)BYgJM5srig!w?4%9rkS$v-7NZ?8LgJ4X}xO|p=x>h zC6E2hT#^0{q3IWedf}H8>@au3k8R~4+-doE-|e;mdgB2Fq8Ru(oIg^bIpQFElEC`a zR_&g-*Kf(vh?ZAr6zUv|u=PIA)H3id5t0RY(MnW7~z(xuTDlXE}bnaXhpaRyoJ z4;5?6=-Q;k6K`H#rWhymRW`^OtCn~LN8wh_VyVKlGqyK-S9XN$IKLnskuxtrjAsfa z>6uCxezsr}HzdxmFd2<^@bnQfOKdilH2ELKj^hiXt){C{!VMA9V+rE-*6#@&2)d{v z(!Hz45HCPrqs%iNw08LkrTgz;%S*78!ORy4;0c%Cyf43#AoWZ>>iF^Z%B!ETRXXA? z5XKMWSg3t{@gAV+Y{ipP~onXpM>ofxTrD$zz>3i zts=18GKXL1dGe`bqsHOBbj_Qxl?j8csmBX9)~jy>QMOgtKUAS&r!xg*zM0eGIFYNt zPem#J`(zMiZ>zsdWfYd8LH6Rc-f~hopN?n)KD2&qJOR9{pCT2Z*|huM$P*OPnZcpV zDWBl0E!>76ik7Np^Msm)pooy>Q8794EY%q_ z&*_XGBfE#g*zl|q8lEww!&Cz+suiMBDn)9UrwL_R9;y{r7R{bCZDmLN1#S4OGO#`G za!d{RO;`|3%j2!U!zPzQg83)!I7VfG;jpJ$@`7%yB{f{HGF@8ICWslfV-f2^hu@fA z&-K&=;Cxfqq6jn#AMs|*v89Uk;W=xXQRVEhf)=3^Z`1cE{;KT8RR73SCGJ#ni7iUD zx0_X?&3I+aP#Q&m!XB9M1NUEbWSF*lP7<{DZf2n^kjF^Oy?L%fZfK`Zbxb+Kno6ce zCN#@!L^DMr*@ADvAdyGZ0RH(E5IT;pg!ph*9A*^RedC?JjBe+C^J{sCjru&#t0Qtb zsXCkRw22ovaZ>MSfc)b-QIAPZ8vMFngg6sJLw?Mffg|E*~bij*E^(#270` z#CJGv55=8DRpQ&0M&~;998#L2EVVOxX;c2Dr|Ob_emsgDq8&a!X|);Ms@S#~OQd0t zGyTjQ;>U3VnBQN8mFBD<{Dg8sWbzi)z{Giq2dC|HxJelRT|&%INauPzjKd(>fU5<1 zS6#djy$Q{HWU3}N_pyDfn?7V#ptd>#0k)RS&Uer3px=ox@6u2hqEsEVCvlu>@ZkFNv{K4u9i;@gq*I`8Bh38 z0V<@r#Y8zVD`V_pZv#T(Am>^FXe0W#oz~}aLxaF z!~eajH0!u%L`^!%q`4E{S@s<9+VLzn8owW50!UbT71Ie@KSK3AZ`+>8g8*KR5&HDriPu1T>}2T?z8UTj z1qXjGN}^#_B_zg(O)#= z#LN!g`VK}etx3sZVU+33Msg+88?{YcR&?DEO{oncC*EQb9an2~)ar z;2oLsdkRn(6=yiA%KnHyZ$LM&>FX>zr3v-j9Kn%7R;q@4(kllKdVb61QzYNVN5TYupBeF zaXh>g##7Qtp&>5;ovw!=N_!;MIh}+Bl<)9R2BG^hOTQU*L9k+GMi=_MJs|RH64C!v zWq=gDAY-BhXTJs#<|1VBTS92X6WK5a$tS-P+^nci_zbLIPcwP=e4LlEw z&-{zlFkM$-)h~D!HOnWSd<-h^EY4#M(Xl_FCKW8E7^@zL$QQlp_3$hWyzioB*Zk{n z*|Bu+4i?9oubEt#)vDMU0u=UhC%dP0yq&N1jGlPNmmT=jMuvoWk)1EJUcMEl0ul>Ppb;@|zrCy7s49>TPw`Ji+Z%`FY=bM>?`l|zr6_6L5uS68pf-Fj|WI{j; zF4uNFG4BfD6@pOVw{7y9O|!%HQ+S@&VWb2mZOA%yRvp^|>K&H7UA3FWqhPv!`oC?6qdf|iE~#KEgRF=qKwN7RZZD) zO91{i*ECXV)1+D6Aa}oN6i3!+2VGMam*wO>2>RRIDX`DYi`=(S!C*QhJK{T*C+McIx)7y z3}8Ul^6XN!!iQpAx@qdyQtTlkXjzsrfbFL#o!J3B1izefmQzF@KAlq0Z)9)+d{6Vx z)&8c#M!EHpO;^WLS>3)CT{d>i+meR4zB%a0`x1&7Qf`m_3iR?u-c`0*E?NGUC9lP0 zC!R9^mv0M4lJ5-Yl_3F&>B~ZX z`WK$fpD)b)G@{R!9ioZvM=oPH3>rcE5$o&rJJ{@TLj1qG=!u=v`|JCDAvJOg4Dt^Dcp-};^Gfjn1ySI)efu$jY4tFgg|6t6k;Lh8a7pQp&K_)FPcL@7D8 zEwL?s?Em!+S88h%ANNgtmoyJMnB|0r4#?`sl6(!H8D{9r%!uLRAt7+R;CsA=5*OO7+N`86+iyo9t8Q3BnVm&SUV*i6^>Q; zp4VdL0lnlMznjM17V?l1m4+DysTTHs1w|C^_==43C6dSTqRp-#EhzEFqBZANtJ5$V zM{gE{-3rjrLxNjO;21Op|5_At%1(rcu^bzm8|g>J^^sIh4uXP{{x=(z;^;3)o_Hm{ zq^jAj!V3x==VvN;_bWHLOV>f!GXl0qA19~!Y31y*i3)7wB^pqw3QX2 zG7E*;TlM$1r3_a&O65>!7Y`f~iC+iUIZaLVq_uwZSF6FpdM9Rq!4A&gQ}9i$ZCA(X z-W0B%5Wm;QG~@A#6={!SZCmklQlAs$z z=?06daS|GbLVa;1U6aH z!we<})b#Ikv-T;Q=Lf0Z6VhP$2n?XD_`LC;JFgFQ$C-WOlNeJ-zQ`Fv-t4=Nna2Bjo&reB3Z!epfCxd!3*5NDWC#SSOjmbhc+%8^GVm! z^l&fz876a~K||n!DEp1ydZya5XthhxP~ySXc}M{*q$+K9B~GU^&w0imdtIZ#3I*XU zu+l2oDO!Z1KcW5;A*#xI>ev?6lPjJ?rg`!?6+Ub{jJvt+;=e;TeO>b#eV2Sx{k62^ zKMxA?OrK$k#Pkn{eOJF>0P798W~=x-vU<}j8xFI@n=)ua%CT(4&Xa&wV~oliyZLd! zKne~8O@I>$&cd3lSh3iu-tS^ZBWkcq>zgr$mD@t-z<|@^K4GMNMwIjcZkOFysaZE#HW2?eFF<-@vx#uaJ(nH4lz|aVSX)I=*WzYg_CMj zYDA0vDP@_VCi&^9`G|YMxbBS2Am^Tmo7W=ge~3h$JZp#Cq2{m*=g^>qK5L$oxV?vj zI@df!i5OZOeT&ymoUR>xQ)X!P?bU9bjuI!|I=<|;y;jl~Tjkg+@}(t$yr0M#%FMrc(WUdc4vccXkTpj`9#FBz84Wc+BoGGU3Y zZ5K3w{03w&d`kIxi9Y&$gzGgS)6CsRxCH|sJq+}-@-8R(rO~q)ub&6Xy;oQ;VPdLZ9a9N^-!FfvzcMX@0o^sA^~2=`r?R!i zqALJ(9ZqaH?WiEW;z+~3QvcB9vH_v{FQ}6)L^0%V5f5!`Gk-#5nMBT; zQgP-EB^560W>0>TBB)}Qt3w}c27|$pQ~?;;s*(Wd~Z1|$)w>We5563Bh_E&`I^y@t-yrqQQE^-Ye^3PkJ zUk(G=^ZuwS57zt52-$_YyW(KehB3^>oEjJ%PUKoXQ&LCh;W%C|B^a(0z=_}4e+i;_ zd&S1+UyzaK?V>%u6RhB|yM)JFJ-k-93i7y6IVK?tfh<&Gw~O-`Pz{B)+buDSgCGW* zCGsFmR$DS_H&i)^RGOpJU;pY=*+O)kbDqgY_*Md6bHDz8?0B=2*&y-bN%jHFN05HfJF64Be7em_wA12DBMRiVlVoM(%$ z-dpy){$K39Ra9Ji->pd?gy2qacXtgE+%>`7t!kejm!Yn5q3pXw-8I2E#-ShB2pB@tu0&~8~8}0i21=VpYtf6H6 zO>KLUVLbM*qT>Oya|(qe#fFdhHuf7Z>4hE_#>WnnX|b=dSn{IddlV*uM?`$57cGJg z#frODxZGFOBhp-m88QU%o9O|dQeJ2W|@;1~1 z?Ac4yP&eq|nS`_{dsNuA+RBTPh+s!m7M!3!YM$Kp`fEN_I?sGVFR&A%acu!K&b5Gd zrCqh8nxAlv8~s2=W;+!dJP}lDV0#v%9#QYCHFA88OO%VVWld zn+wL3ER2hCju!uvsL0OCe6sqR^VV@HB76i>E=%(b1WDxHeHIms{}z+efhpLY%7eQC zUDX0(My2!Gcm4(mr$#tL!Od*$Bo&zFj(L3#Om`bZF`#ia@$X5@y-q~NQ2@JBHGIG; zUL0o{!sSvnyTP|%c)ZdcWn5vJekl9#r5|LKUUA!6o(@?*nE2#KC1w(u3f&QuT|#)T z7eZ-Rukn{wRtq?npdA=bPFCgCayOU45{#l?K-Y7WooVltEXN<`iTWxgbtI|b9VH|I z@B4NqT&m_siu^T;y45x(kXWTHNQ(a`>!11Klk%nYS@RZe4*9f40~EQmzgmmWi?K0t zUd@^wT(C>$l`>Y_#=m=?-c8)u5)gRNGxk1;%?I{Nb1x0P-8xLi&@M;WxMW+*mKehv z<;GMQ0}NYa2^hxx*?sz!c6;k^2AtI%xOO!K=6v2{ISj7*G_%Qf{c(?`0LfQa!^29E zY4lQirfdTbTv|uRm!5O0oC6c&4-F;MN!{FWS72RkP_^MR9|$#X26_|fig)rogCOC~ z0*<;|MBBhn*MVT2r3<xwk`FO58UE|9M7la#4S4OMoJh@Vgmfk^~oNa$46|-UOAMdB6$+*Se6b??-_)o zkkrr^^N8Jlq=|X*{rix+< z-K}q{@*~(VJVpHZWV#&JRjN_t6)@y7QGIl?aIaZnvWIgpMEzO2X*6{`J4{ zH!^lOQ>znK4gC6B$?TaIa`s1-`>KIu=L z86s2iQ~j&IvWJAenW1LpL|7s+(O8*jnLTB9m_#E_By#@3j0v*dR?QX>)8m-K4R19! zEr<~@+MIV-K@pplByWIKfM{xmFAJo_C+G=;c+|=mXhE7?9pE8eb@zobyY4?O#?qd6 z{#a~YQA>ndS8YXIcwRjwvf|3Eors*xQ1 zI+}ZzSDINJxu-ILF%{kq9Ygjcacmm#m`pAvnoFDvkC<2<*J9Cep7^hk*ydLTsLKf~ z#}q67f09ML{N=AAQQA5SJSE}ue+5ZYI?!dt`Op7K`aJwUUC{7c`wCh7ZAv36ly5;y zmFm=??TC^-Bf^t5LJ4_rK%^mcGtd8;_m^)*neWsFXm$~S+tkzG_ttE& zTsgF*lev~Xp9&g;)b`P{TfWAn-aaO5!_Ac^Lga@2L*#+zn9b6?MJli`_}Eem^4HJS z^$u=Q`uB^DQFgp8UsrFh8F6%!|4MS z9uP4EXuNY4TAcC1N>J)uP(gcHhN}iqPR&U>FmzUAOVWY#pG?+08-AAuC(QrZZ z(s4s)Yi{MPg?$;daWkq^os9F@!FkY%kU8#w9{oPnMrPV5@)6GH{s-k7zkj=k$xb** zf)~_cml#a_^lbdb9fa77>eR9t4t$w+PW zn*Eq=3uCarcmH7}zDZv>`OYStH3hFId48VYs`ZaMKH;>V8g6Vy8G6C?h%phOVG1M+ zy_bv?B2vc)WS|dRsu{y(cptBl_d1!thvMi%l8aq#H}EiIkB%*#JXBxE0)#XYvv84jwytl5Dtv*_5y=!+SY zaPFyv%D1+2%6`UlI!3yA(cOL6uZO>+Ekv4_(FvyJeu6&o}+%VL6HLG$PAi~iFvqH~w|6g^3$}#b-E>zY@DvLht{0}6XKKv)L zC;;ee%fXhVcNeblO9TFE*mdImkM9j5ey1K#{I7(x*59i1-QnEVW()MTd?}5oYU}xM z36XRr1R$@J7b2LGa}nqGNQVGmHO2J@+Q=dG9}kzO`-=(yuc(hV$5-o@b5Z$yW9jpc zmbADNPI9;?m&ljk`Zi$vUr>iBuG0Vk&gwW8=0HKiN2HyTv%vg1vzUGp7FyRCF#zax zvnja>K+4Z_f0kG`K~ZjinyFenb)W+LB(J*k`NL~a~c$o&rQ5b8h|o90D4*a0y3Ir&=H zu3U`=r^(CADwM7lyOgRMI$HpBT!xer+OkF^cks=vHTS|vSs!?d4TcG&6E{97Iuwsm zW)K092s=XJDq}7+JTbr*yEgYb3aQ3u3|cN_zDe#I84M@rul@Nv4zy8IIEjtPEAwdT zw7s(88hJVDqCBp|<3uXK)>%}cjl*>TH7>YLYm81KGp&+4ZEX}J#3o0dT#U;^bxhES z_;KWL{~do*A8R2@^;s4N6C}^py5z2#s-R*}+~7^#9Q1j6Hz^DV_T&8)`#ArW%_H&< z8HE_Dl2%-x{Lw1dc(FJHy;Z2mSTVXK&h_3-LA-|QN1_lgXx1Pp2Q99^F5HLp%8gHc zOEV!)s&C2q(izdLrHQNEXUzQl&8WN_QS6KA{mc`Y~j3-(-E0N(mvlT=nOK=+AVKq1$lz%QF z$TJpCL#&_KLuNASGe_x5HzDL*@=_`*<549Eof@R|$y0-Rtll+DOUiaI1(4iV2+*m4upYx%A5Ak? z07W|PY(==YW4^Z;GYjV#$V0=1f(hrpc?q_+tjL|=+k47ZS#iH-WT3yGmgO`axSL}k zY>nXsi&d{qD;KiL{y1%%L5p35b0evOy++)>ANGZnN{bdQ`wVpNj(t7v0?av&8SaGB zYhG}NXC`8L^v%pGFzZMGQKbE~+R5wwcHvJx>+)7n%lT-a>ElH1qC;`4@Z{wJ7%$=4 zKLO1j?8@2fiw8fT$pw73(`!3^3Y8_h4n}~s#Ihs7kPS%zTuCl$n;0{&OO50s!UVe# zcLI&shtCFvoFSG1o@oL^dAe(D$wXyf$)<3Lcm(q{xz$i81v`n`1ufQk%{W}r&Mk@* zkKABO|5d=Qo3JfF~mM?$4zj28;EEyM? z8Qpoeg`w7@CB9Q|+6Weons>}I78F; z$cL37j8@$DRZYdc!@ox{|Iw&{$sXDu4^F6`AA#r9oxGRi=-Kp^E4X=6AGlRX!d5RpuqwDMo4x_l-uM9Xyn0<0?OA5yc$+mp#H3%3Ij#9qfqE<|XPohE z^v3IF*aT7JUiH7AM1=!4MLBb7wd=(pP%4h%F4GTxstd1l(m<~46-atNlt43O?K~l$ zwQjT=N+TkZze7su-ZttrGi5>mw@!-MowJf_Xm`_d#a49sRHR16l(LwZ^VVbLBE0vh z!7y|o-)PN4iFQ{la(n9J3qH9b$mbq%aNl3po_DLc(X;)`xhg_C{5V*YjdHqaleFeZ zPHAXitQj!3d^{oGfg=Z#xDjk%J>4Qf`UGw<-YcmKV^3_Ph;**dul)F;|C=+11e(96 zJ6IAz1bEh3#hs>9D!sC-gyF(1#9}H@PN7e1Z49^#x%q=WS=_d6j_Dj!z=P1RJTo(+ z=gMa>lG$lueCV)Tw$A@q?kx86Q^nU}yj0!dd%o4Ek)nqea|c`AC3i9dmqC*5_A91! z2;hXl86-b1J?@fGFOon5`lQesYSJV?v2+?ev~d;-aTd{bi@;W~7FAa?;*3iAS|)%^ z@5*kvcJLpaGKxo}J(W zklMZLczKzL{nUt-tEfVq(ID?f7G$`u;ja7{1aT_yJ=%JGitxh2f_!r}%7c>5p*JoF z3@@5u*ktU;zWKau`4QWwbfeFjZjLb<9(dmhB?owd3SsGBrgbP=cU>EiLT=OQN7U5 zy*vVp3sE;7_dK`uDm2(>pAGjv%#OUewt4I9*kljeH5w!gjnwP;bL+YE?^LDzzXz93 zBks(^dy{VmPj{L={3B-i$@J+Pfb;D~qxQA)a)H5xq0gG=&Es8aWnMwl_o}ds5Y{xa zSMp*P7lF5riuR1Jb((A`nWd=h^@61kdI|AyCAC)=Y6)8~^iT;@8l9j)=c-*O9RbOw zYH)?z0S-a3p~jZvdP(?$f+6IxR6DX9jV-Af+HeW*w`Ztm#@AIdiHKzaM9qnd!R%8p zavtfBaL&evSXaTEgc`lAcbiohddddXe;xvIv4J-sz9*4}ODm6-0vXYJvACZfkgfa8 zO2|rIA>PI~HRuwxnT1-i1^Vc>P=2oe!UzAhkUVn#w<%8QW_L)0Y!Lv8b-bZ;BRb45 z)~>@xEYWj4p&vq4Ae0l&9gkmb8@8|uj#AB?^BV8%w&S8FyB}PgF#Jb;g$o$*#g%0@Fx0C^UG=QleCgR({b?ML>jkDHF{;?hEw)7&vC+jt(7JW;4~ zU+sz8-t9;iI9<|808MsQd7bukVhB9GDyg)n&q$mQ;<_QX0{qz|3lm^LMa4>GV(9g0 zMsy8@!_D&3ucLmp|FNlkHdT!e+>r&d1<))S(M$h0PG??{E8n3qc~VK>XJrbzZfDq=FJt-B8mvA>v=8 z51sf%tD@v%deKrMTjMzE)Nl+WWI;@~3zULyY2ZQaxZ z6Bft!*b#eO?_K z;M5Ej*YYlh(7}hy$$v8Bu+7b=VYgX{k(iE@57ja_!v-%Z)@a8k`HwN%PpzU3z%zu?^T~(;R&U%p$mF{H=e#4i(w-}R7%u6W2K=Xahy4+WH8*BFTn15wT(2?T z#jpvyhQS9X0v-D%OdbJ=NQ|5`90B!aUF0b?az)ss!$t#8X_~{Buu~bt4ddlZqkBWe zP8Fui>@~tBwLCzk7-}?#Umqy|u;m-PS+lfNI~;`&*OBwJjtTw4%Jo|=0pzNo$6i`~ zf&7l6{P0hY1UPRS>-~l;3kMr*>Gn8zNTx1B2MHPrXR3I9kT_AXB<7~3#pSKuBJUIF zdYmg+2ZrYb;)M^R*KkEdy|=PlyxT@3`MLV%^I^iT=Xd`d@0cjLdaHca!$T+7{Kb$4 zIWDg%$um0CG-;pqAmWvM(WK+{^T0Wh6o2a!VW$YxxJ7rahSwq6upob<`e|91R#B&u zwbMV+4Ct85k!~W#s(zk10aQyGlLTcIOM@Lv!v}=y={%|Dae|Y_?5qn!U)OEi)~1vG z;Pv3W4fHs=CND)G9oVk5<4VgSaX3SG!w_XyS) z8iRz|nUJqz65?5z7Vt6Ax|A-z*0nK-XCR92N#%UKRaDkKid>4~jq7}X^!?3Nyz{K{ z)%@{DP&Udca!=skFGE>*`^vuD;a$|xJ3OXdy1+0HfO8~6{f0DDnFp0-EQQo6a9P{- z89nq6m%;6ZPdb}AS0*wMy(Vy(pX^G2qqBYL;!WR)*u>QFCn_23&31*w+=okfm)LKj z`61pL@Ro6zj>-GLerC?Wd*H>I{m)E_)_R!SzbDhe-3I_7cd@Q^pn`D)CLUh(e|?kodoV0(ZOD0&w5#`FGp7LtA!ps zQ&v|_HB>E%bvx6+_^huwE)(G!4#IiRQE?@8Q0}MNtw|)ylDz25Qs}=oOd}ld67nav zBrfphs1$`BPi=Vd8KJ$3j&OlBMPz!gTNRZzoe9!i9psa$>diika!LN?o!2}P=17wJ zX9Jm`WAW*BZ}sR^jHP`KO{KMhW(){|Mj-LA4Pc0&Oxe!3)Bf&rzIM|D zHPl}JKyE^iBy}avJ$z@q(gW+&K@s5mH@jA!A4h?iR@1w*81Q`?lH#h_VA&Ff=-c%? zjCf&Cq_j7rL zc=51!&+M4_<6pCOmRPi^xw7t9+xW~6{(|C0kD`YJTHHrOd2Rd!bt^XMW-JBZBdQuw zW#%1cuKj9-6UlOK6lBFM@7)iMGsH6(YhcTh59}zkN!)?0x_u-DXz%?66|~kd{RVrA zu)fCv^)z_3ilHJGU|&fnHT8Tx{nIz}XT=*giaz=Bzo35EBH#6vQ8apC%x?9~@y6so zZ53X>>)?cu9LY=9M3Fd2!ZAQ~^Ae$*pb4QQFqZ;$iTUu?1{VHeyL)A6<bk+$UD;Hnzdl>C@%NTX!;t`-2cpWp z6Kn2u`*m%k8z?CbaAd}NJTR_)*o5YXv<^=I*UE}6MG(?lUMjM*-3>s_d9Gnp-Cjr| zr~poWQ-;53q4U61FT;8*7@3Sv(RFuU^O~V?giOAJfGfy|F}}j{**8Dq8++gT&s~Sz zVK9aV#0Mx?q2mvFH!;Q9D^{r7sYK7!K{O36Us$Jq%#zqsSDvQK$o5*jlVw~%QGpt* ziPqt3j7Z6rjuR$ZN-|pUDhIg;c3%3~jxg`5QA+yAYIjpWJ~TD8_3D!|jd^7~wU2 z_Asisn+u(x{4E+)yY&nqAeV+6cNPEo&s2-E5Zy6u&Z5&8-dyV6Q5VlX&zmR`_pD3j4w2^aNU%*|z|J^LU zmsKLG&N-AG@o+XTJ*cw#BJ06W^{58l>4zp8Ur!zbExElo1WeE%bBpc`7{_Qt_<8?* zBCtX|3+X0SMq?NWxH?L$NOd~}tM&yE5hlQlpp^p);55-s9R6}Zr@h&t)rs1x`@m+g zg?E5(P}ky6DaTK`LuM0LA3bm`WMW&fg#+mAL^v(Gl@=8trgTiz$CtAs>ou}e{g{)mRidKQP-vk|7bi}c|^PFA>9qvot%Z(-Og`uaTewbikI`5xW~ zyHk15m>=+6QDY14iMcr4`d-y5Ua}u(JniEshp&|SK%48g%sIC2$iHntSB%x7Iejl` zeps0ZUG#FDA2F+u)Yi#gc?FVq`A3R=`bqr9fqFplPeOp=BIJ{-VX7V|>tswsagiS4 z^ksKDE-9g|smsdb{UjFa#^a2|JglIGBcKS1czCbWL_NwV!;`L58sq z0p1%2pDM@Jzf(4S6a6pnXtD-9XubP@{k2B)(juvA`9*g5In@X0s!Iu^Ntjm1=mHg) zFQfT;`TJ&odoMLejlyGjQ08R?W+s zdY3JU7tEPaOQ#8T61kgl?X&v1-S1)+X$LJqR{YkN_3F!rB)2i48NRa}O26>*X8@l_ zy3GN^8l3dX6culrf-NY+2u}DQUsKLCK;_9WwiWra5nlhh_~1de*G(g}Y{{QTA7lq; zv{gS3b;n&@Q_S@`(wv#`A>?juS!dndpHG4j8(k$ zMq^wSK~Y$!AF3T{D878k<2F!NZZdwdCYQFT30=|VEU}CRZ@4`rIr&u3d`aV@D=hP{ zx+Er^h@+9wvJ=Lz`$H zG+i#(CB;s8hX-^3D1y`(1Y8DK*YWj~)_JV0wSMutT10Wvvt~euk_;>>yGQGRN&$jl z;&rMELw~4IO^9QNS`fK_y`Y6FFl8fN^=vc>jQ~5AVk(}!o&;@WmBeF4q zT`>u49oZnsI$xx`Xxu|Mof_y0@SH1l)T{x?xDBS?p#iVfXklk=mP$T2(xN@%#r)Kw zNN4%c`Vhkvu{EijAQ6a-v82ag^|pC&mvUz{Zf)d8A|Grtf|SicZYjVCkHwP`Oo4Jq0>8~rW**=CF^TtjR9wm$^F zHxK(Q42=kUQ0m$)nWh|gZ}k!$n~d)P@7SV05O^1zpy$Tes{1K8l^QZ)+1Oq3aN=$s z%@ruQj7zr=@lox#M*%f?%%+*Jb;Hg`nrlzD8{TC=t;Wx7h$Hr}>4>=UFDMkRmc@Pt z%GikQ;FW$yZWG;!Rtg4lm!z#H^_f*I??T8SsIFX?>?^koQ9`OZr$|uXuIE@WfQ$QV zY>Q5kSi0tGV!Dg&0gKjt)hG{)0l$p3J>C*6JLORYIC;!7AvES2{D+}8Lnh-#;&hDs zSLiW;(rRwy^mCND*EY_F;MZH4!+WLEUS`%RlT9>DswdFPMh~tD!0;!yKUVnH z>LuwfvBPX?jQm?lGn(N`L-=Kwa{3_h6&MY3{Wc*GIc0;>c3WSS)HJ=NZh%IrKX-yv zK!udhUY%vR9Wpf3h^^j7sZL170E|Pf%oj)9w~Hn)p#2Gh+7 z(1Li6mh)Ox{EAiC@H7DRMwgc%FQnv`u5EzPo1cg3{ZS~m=&@SEf^VGhvz&MXZ9iIm zF{0Yk>>htK1D~nYTRNrn_pg>de-o#p+wImfkvvXI=~pL{uVne4nd4E+OYxQ%tRviQ zIOM|SdZPzs?P}AF5?ZQ_6k1gQN?Qgx17=D|%2QfqZQ9zY_Byc_QAjPmg?3Lumu ze26fw#Pv_fYSKJr0Gsb3GC}<-0zN-{7QAl7S&$YCt8;sWvpp-g*8&)p7?EQy_?^{ub23HvDkXN- z{+IO8bA&ScrvhxC1kfrh$3_4mUscs(nsyY>0qrD5uPlx}D!HaO>sT}**hM>w@BNGQW>i)?ZvmA)@>OA0aJyn6W2S7B4MSi< zdJCeWGyjT-hoUJy_U4%nLq61EtpTa*9aV4s_SUbujISyh-Bt7aX9oSLglO}vSzc3yx~K$=WK%` z&-bnKdiMRk0*H-^OLy|g9q<@QD)07WN+~2`Jdrx)9wqKAx?zw$#3cM%5mI8lsdaN) z{~$=Ktnu3h-QS}}OYr9VCXuFUV$`;esM$IXxdfbu-LeY;zcSALHh1gM2!`2l!6wp( zMC+)Sp&%!sYGrxoDY9Ym^FCrGJF>I+1=FJ_8Iy`?*=b>V!qOtw76BV{O#9Ubb7vbW z{ui#@(NiP8S+1mboy)auu+Xt11_x?mEz8CP`Hu}mD=FSPy{UW^3#FH#2w(p#c^{&6 zV+RW?&N|F-y)g!)`g;GzM9adGKjho$oVh9(o_&0ioa;w%tZ|5%rLU(OR`W+qk?ur@ z8Y`C$*M;AaMGPn88IJIX*Mz@&I-JxPw*%FSI~`j6B4vcqiJYAD?x`0VgQm5EI&h%36P`vi zypw{Pb&RZl-!#{x;DZAn>k?I(-5@Z*z^5(vBUzjpwpHfXHYTxiNZn>)F5X@e+OSMF z#Qq1YwGg{5`zuFVYueU9F=*@RNDIZP>4ohrY5h1PM7i$xeh<(vzM|?9M&y@1F{Ec~ z;Q1o2yivdwpAMg6)t-TwjM#8bxu6gX)AfUH6N*XoOli-Z$wPdxNhReq|$q59lzs77Hj%1FO94#u=dM+X>zufKI};RI*P+1(oo6)t(5#7P8Bw%Iqwf(r;Q6sw<}A7K7Tw83`$PGiWTvM3IQkh*H(D8KG7S#jI>K^vgWSBG*@F0Akzi zq~Zz_gteV(9Z`%xOm^+77~Qex)zhc>1ueVEH&S%*ar0*G8v7?2DcX$2$jL6?&k;vl z7mNwyUaqwlO7=v=tyyI~PAm)VF^RqvW3EJglYCzFS^{6>lrrV`!y$)(O9Rr_O;ou& zA&{n?@@_{0!sOqy9VnvfQ`tbh>`#=n&^G`=#15n?*3+sAZd^ec?D~{`A{pMO{ij;+W+Ul=7~+ z%YWk_A2;3HXmeLTD*Qz>B-Sq#j!1;*l_Ot1(t*vw~UarbE;4fGZgJT%p!d z*~%_Bf*nzBxAC=YEv~ES{)j+8s@mi^34MI=&M5=lzC)MSgUvLTGAB&>BChZ2lYwLT zCpgW~k1cojNxev~r|=QF=ZvEN^+4QHA)Oc%yZ;51TFDP_7c=NT!jf}DAF?6Q_}EH@ zr|uj{ZQdEgQiPA5-s}jMumHWZ=7VWJ9kgB?!oC&BIyjmS)D{Em;i|vnf&JiX$R!Bs zAkM413N&)WBP-NWqm*FU*+MjP7dyY8Cp$Sgq_^}hq$IGYIW+QgPl~T+nss*J-AgjL zFO7G+Qm-m2JT9vXD*fggBnx(YWG>9ajJD}VYj4&VFRHW1QYX|ryG%|q%1w_?(02@x zbCI2lmvceb%j|3Ay=Qq3MoX-Rm5=?VNT~jC;*4v<@Qs@79=(<*iV2=65be-ez#UYZ zV7M~;k+AlA!b+5AFg=x{jbKAKHfU(Jn}7y3AZUOBib=6%Qhx6)h>QveGW7Gyz#^&9 zkjPZ6W2eA>tRuJ2sR#Q+FLj^%^=Fiqy05^q8SbU-`|XOE@3i!rs1g@o|J42zvP1&VWzBlTnlUp&>@ z)oPYW%or|)g_+clID<$FP0yL6(Gks>=QcQSuGAcWu3IWzP{?&IXN+_!mJ&L1ZgW z@C`9vtZN?4lIle}wdN~KWt8uRHGj0vFSOBrmhe5Hbdgekb|~3}kvdCZ_fyttEs|D_pEhlP7AoB?FO(+L zxDv~JDrO^3T9>LD{=0rQ{hY<^xh_ViEd{YXrk=O__eSHrpe(JgsIUr{{v4VpQ8O!WbRz%uX;m!OW%rR4NM(MdneT$U~DKF+VwPxmU8szc?5!;`L_?$635GxR4u~qWPZu7`jui4db@|RSWExZb5jS zZh=p!GGfCNJ4GlSC0rg^BDkuJZ!X)qiz}F4T_DX3t z^DTBOBAA&1a1x%Y8rJ3!Jqv7RV{9C`)*At-rHP@lgAMsR&{^T?dT>Otq8R_3 z#&^K{;&Z`RoW?tLXA-`%Wa%6mxY})hV<%k5b;jZN#8>H`7V~55|1fa;|3Cca`1Sws zZb<#R#HjeiG0)Hc5D-DGsGNsHRMIU`GD*QJ>lv~C8isPzmiL^5vBb4gN!~2?NYRUs zz8<4V!Q^dlG@!7V>0w&E82ISQ{+OO_fKe5_aU`b^^G?E!%CUrv`)pV@P<>Og2ei6f zNU`Ky?JDJDREr8DIXK{@xYby{#9-Om#Y~%XmmGDIspA7uH7QPu&~2-!>&4ncShFbu zWEx6mr_eRrI6E1EZZY-eaQCj6=#dDuFr0!&4R_t6D&gnF#bu_L)o#11Z4xoa0PhIh z#(ocwh&Ou5tTLQREZpF1xwMvYtni)K&eDt5Y(M8ZY;%S~O#ZMNWJY^tP=JJM`+b93 zsgct^2W_Rj=fs9FAOI?TPH;Whv>5yf7BK zujv$hXsb_)rWT~&jz9^*%fY~U^4?xp9Xo3+y6^?NpIJiizoX>i9M zIm)(tz(G=jK z?CK0MRa{l_wsKNqx)I$@wB~^PjxFBgWyo}(&;?3Gs-LM^5(hjVkUt={-PXA~A!a9? zpPJkp84>6(`z3M@g(LlPf0JKbk<;=G^!sY9C)`^d<$$`*IS-)bf96M$Cp$N^F6@FS z4Vb?Y@Uz`Rn?o4@??+`S{ChK^av?)!)huDZVr2a`6>G8~T4yz7*q9wNVpX@Er2ET# zCw*@|rdM&Lh%*xCIVtD8g$<_6^yl~$!(b?A5VQde2=Quw6TjXl^l-x?hjt%cl| zf$D#|VJgUfY#WQq8H$;Z1N1MwVu(_-91OUbFP(+%&72H(C&0+XEvg%?(oSb}slT$h zLNQliY%WGL?ddj71OwazTAK@5JNi}+#IOl~2+>AJy=PA@qeR8S=k^zf+pGK*O}B*? z9Jt~ZDC+6eG!*LI{bvI|?tWPvUQ)n(mw97Ty0{k_UFW(dd-8a^+ukv*Ke=`&H7CtT ztz`h}NI%%>c+)6E;;8EmPKk!6qu)`>jZ+!#HJbG!22-#X5HCG^BOQ&SH;m7;wsC-F zLaNn^6N~m*G&KtpIttLTC1}x-#Zm(lGig!~$#Sg5XK-&40+`7(RfX)x@rM2U^w|n1 z5#R}feeYoDPx0&ULCy(k5Gp=DCR)TTNG^(ttyQMoRqO z!v5=9N+7<@63MhVG@iXoi&gqogy{ zxmK>B&%NfdLHBlRK2XODDa@C)V!BNtW8sNcE)%L}kVMBK^BByFZc}eCavCq~Bs%MTkt@sR9O3g(;%t>Zzn|>38c+}`&+k9d`I3woPtGxu2NHi zM>mYUgu;i6HAiTrdw%l>xNK|CEh%}edzr8wuqJ>6ix+-p!dkOiXlAQQFJyQ-MqdsB zjRZ)O(^GjM)b`XNIm-*0GTn1f7=O=wqkJB>`E_9Ab94VBSxRD}VS{F#T`%m3(f(lP z_BUUjGL9;2C})%(&=iKuI991)nnPl8vC)rs-)5*Hh5D^&#p0|t`uT2_eM;%q$F*qZ ztb8SWYu1cRas$v-G7V7?U4k(vkT@`I#i+@Dws)k-bH8310ok)=u)amD1(zuQtXd z2bJY0FxY{B6T>uy#~*}AU>obJ4tR!mNeR8XT$Sv|&QW1Jx}>~RXKUsz$Kz_0G;PF; z$3!5?H#?7Fi@63>$Bd8(os2h^-YyhAbZqruaa13^)VI_^9FZGwzl~PYaAZ=Ji5J~{ zn?s)^09bL!k?s;%*N0*C?Y7`)*YXp-Ur0cQs2F*Uf#PUhpqpuz=}=A|8VUU(vA7OH zs);SAr{)&~YarV0I3{MttcNCo)ZtxDDQqXx^|`6@vGM&rVd=n|fF`T_3u1bv2lO_j zl2=%g(0Gijt7vOOw{y-TcwiSMvej^hAQoKPJ@tD;rXAlB(=POB$CdD(#o;L!x?fxw zlx!l4g_Z72{(`y!bEH?kXo+XXQ5cdRJvJ0+NaVd;#!DaVEYuI#2@sn@A2c;l_h=<` z!5(Z_KM6ioDN^u9@G;^{A6FvS?v>S5oP7Tr`93-&oe? zKP;9r1#^>TXXEarU!%VKowl_f6$6AvgXt$dZrZCUDu%W zyjX~UM#~pBJR^$M?f+(&o+R-2j2nXMRLGT-{wgk*m(VXJRNepmU=IQN`-Wb69_LeZ zakKMdb~#=1zo1tAMppLyD68>$dm|_;Fp}aB+)*eG>5=QR5b3*AysAGW(J&&Lqa#KF zqms}iBnHEs^_b??-z1HuoK;5+w*LdD9(H(=$mYHMEXq1DKxg6G6TYbYq>vM+!mfyR-eG2>pHRH`STml@Z+prgy*<0TZVTQYDUe8-_SS$}tn6i0>BV79`5bXD8kg<;tZK-rW5%f=z| zN=lD!tXb1FYSa*DS$!|N!D}$o$_Gn1Q7iLln~;Xe&MchrL0XcE70s{*H(IdM7FZa_ zp|w!c#!ha%)>eiq%s3seysJ^L={`xMd2&mO}6k5!^6yh7G?WhIzeD6JlZhPoj! z=4RB{eO?)0fl4xzZc8g}gi=(*=V!~B_*1~$UHNRX#3i-RRBEf{G=LxK_nw($_U=Eq zLHV{CO~5mYYSYuE{Xe&dnc5~bySxX_e0YrT(Yd}eK5eS5A4W-Nl5T8kCXT5Jl!1_> zEDSn6+1e#xDtgn}0e4{!IuV6a8y}clXtT<#rRwdaW zB41wS4M&r@a%Y+?yN79f)3&EB>0<|k?x^}5F%NSm*<^+0{Pf-zHkkpM0jp(9wLqGK z#+%6m?m5;-3r37XSqi)SKn-2EsuS6Wm@|YUN@MRSR`dc?wPl#e8G!rQ!l6}3T_lr$&zUGy%l2p9*FZLe5hxj^ z$ei=}d0Pr?u1MZFU#x#gW-XAhR_*X~E%5hf^jB!#_l3**%TZ^E$EP78N&xY#|xgcnNJv~G=mm(-Y1j*!Hqs-bfjrcMKXef#21$!ZuXYX z$&}$O8rfBT?51Z&Z6X zu17L*(m9Ls^CC=n%Np;YX({V8R4(iBe6x)5!Pk+$zagMEubX_V>#URCa#?yw`9X`E z9DB}6y~-|$&AivXc6{((-L}idPiQNYG<`SL0UcU(eic4Db3Q<|QtkL0jg(L8!_y|y zbY?K@5I0(H$jE<3O)|9)j!71i3EhFw7WXh|$mRW`U4y=)3+fI+_m`xt^}~rTFMGR^ z-OCtzRdFP)w6-d3d_zux8Ckwr9T3;%U}mt!G`vMn^{|-R4gYfcKQiq%91@$rab%=& z2j&JL7CF`fa_HuwYuO$#8uM7Z-S0m2H|m4YTGU-S;woX9`{Q?2X7Y}0+io}$jPs1O zC%*_SLLIT2UR!ztB$#DGKGIXGoD=(=zq=BxYj;<4%&H(W(6LJho=@CDX57+&t*63= zqJ~1R9_VLX8)C8l`qdeEP?{T(Ei*8J7_v2L3e20IiK5bcb~;~lsgLE+GhJX%omem5 zoMR`9XY2=?p>khV!0>;R{U+L6(rdRx!7FDk6uIr?HzMlwtZ;#)RL@j9M?~vxU6&IK9U8`UX##j9OQ7m?hC)Dl|osb@}uq$qvElDvk~w z-}xd<>E*?anxKV_C>-)lMzZ-5W#rA`BS%1jdNvbF6~iOn@*>{64l~~M5P;~0_H(O* zX#?hO9@!Pj_KF`DY^@bgr)pVj*{>U&+>c5pVpAP`Suo7{eDi?Cm6knk$G@zb%=Z1H z7^lc7_oZ;&fA0@ux)7=GKYB#oeE-AbjBYYI2dP7>bQyjk0{+k~bTe=_^#TfU0S1ce z&r9tD70M5nW%EHPgkP{Ky%;_*t>s9nk&1A86&duGH(qnM|N7u>B1~5OGEIU;p`3yR zZTGd3zk+@SCSoK7;v-_xCVM(PtL)51it9+zoH%kwjSMzEBhwou^F&Yv@1CEqi^G#1 z3y5dqsot?wTttR0ug6?e+t_r`WX(q;vUNS+eUA*)cTGw1BVIu7hG`CfjdR+bOnO*7 zG67$VS8dCPj=BR$&bxqZUVL3;QoerS%}-9;-sbvd4)5HXM>vXuatw3!kv;8o6ZJf7 zMsi({ovE`)8Skb(V5!`{<+ZSF*%sn5X#jtLqJcW=27?x^x<*oSKGLnln4DsB^aj{N z{VTd+DJ~eR4J)bKs{dn!t?MXXNQ%eYyn4%$fui=POaeeE_PoomkRk^0opw~OvS&%Zr!O#r)zxETAU3_?Gw0Tw=iy{6n15B3+$pk0)AlgY z87?3$#kjLyB~mDfOkO(pS=j$-k9r7>c-+=Vfi-mKt~jIx3dL;CQ)np}_wP8=zo9EQ#Kp?^^=3^Ht=uE@K5P~HWsGK&5R_CDnO5k3j z8M4Q;mt!vT=!cMCnpn;WM4pP3e>e|hDw&E+oe&MmJF1ODZu5sB?;(pBI*3Y9yv8V4 zxEvP^>oe?yN))5O)$wY=AHhD!0P*H0({?KYS9Y15ptU}3(9tFg@8t`VvgG8Lx4$m$ z72mi6;hE>K%;Uy-AFzQxSenNIEid~0l5I|6VI4O9rkO_vJz4?V*e|BQ20B2a0hRRyN-$Zt(qzQFKXh=WA~j|f!|Qr#cso< zuM_`FjV@8Y*t?6uIxv9%+(D zfF@8cj-N$ic4(M^=ieztSPxF3o4&1 zAjl5Cg6mX*%mA^r>L#rDs}bx%3nR}Qc{EJAdx<8OPDR2i3jftah{Zb}N|7)Mu$LPu zRS1X)mi@wBhG_4~$N>u@MMcVap9K8);2VVz!LdCRzkKlnQ6p;aEjZAp!={grmSDEb zC9&?3e%tBGTmy|YAOeYFRLSjPDL&eSZ#1T@zJ>iQKC&caIi`ED0Q4GMr@Hj1w0Jm4 zOwvd_0*@G-f3YUE!d?Ga^7#jWR59o_G5j+V{FDn%)o(h2ik$vK!V+fXRG8Wd7uZ^| zAimFSca{3CJPL2ztTgq+eb%9M@)J&GscLr7?6tKwrU)4M!_l10B4h6r(G17oQUVg* zf8`Mc?xy#6t7nyudUW`Zs4?KwLkgVY{}`Q5I~I%I<{1b_(3$WhL0s)#yhVi>{gsaS zDtM(KvA{oxLW{6|X8sE2d>FK9@BibJYHV zrgfZ|%nfAyd;x91J8e?5yM03&Z55HthhCpeX*S{+F;2oDX2O#mL&nT1%Db0J++0LG zB-fW)`|v8r-*Nn4vSlu#v7{aU4F|7zs9XNf35mK4ms z#d~-bhUVrqZ-cK^u&*-bUofgpCE%;yTYaGF6>5ci8RtWm>i}E;wr#QIv&Fx706b2% zRLO8}JHQ@kPCCZH)p^qVk)V|%T5~A@2qRGsh$i5$EUpi46W~X#4;EadCq|J>Ne*5A zi6FbQT-&t^Ibf^D$SEqie|e!R1$+T4B8;(=kCPTM(X}pTw0Y1ufPi!+&r9ScI2sPV zwUmt9S=9W{k*kKlK@$nJkg^Pa%^m26JaMQ)8p8yk!n=Ocq1~v0t$iZK1oiPEwKg1e zMBYWOG3qBvh8`KFMXZIdpvziXmuc!@Ek$?@*Q`6z{ZA-mKGS54s;CNogh^sTir7@% zIbsdc2(ON+@7Yd(zUE_dV1!Rzm zH0{OgbB4Xha@Ed^0J=ExL;&vU|mYPi4sm&*DEM_zHBl9B#;fIHQp6PgiQfomT5y4obmdzu0U zIkoIUI!fteDeY0rIF*6{{LpN%3}?DISWPI6%YwLl?*7by!es!FP7>WhO^u}wA-CJ1yqp1iz!|6 zj370^q{qMt=0*aH)Xm8{fVSUHXcgErdB)+Ra8hMPWh5`C*&7a!`*|WZWAchPt77$L z?yUNScM~!G=(vl?g(5wn}z8rg6r#|*D`>nxU7BA*Fnad@yI zcpgt6_7ma2(4kWO?Bcs$r_FzMg7wrq#jUGtk|t5XUTL=VrKecsB)pzg%|9GRg%kdr z`hUahf@w~N<`&7DL>}OQa>lkt(FOV|&-{2MLo-mELL-0tVaR8&kigZLBt|mdDpMA( z^i}tFZfDJgg8fF4VYUV8^A7BNvcgY+7{#B!4u5h(yoW_pf!Xf_$X}B=9hfLoDwAP( z3l#Xa5=z1m5fK+PBZAlC>vfGbYwE**hb402k19*E1e#lI&6g|mOXZ6SNz|g!dy6Ku zFp1kL%O?~_uz7PTMtOz$R`QdT8RpQAwG0aFNr3DZP3Lod}Xa5_++avi}9Ob1_(;xF7Z$nf3;*4LhDo$gwYX^ zJ4%Nl8|VFv9enm$O*VmcXc3bqSN?sSBDNhYNsQ}av6xM2!~Em|h$hrI{Xas^2lvPj zS{l{8uC18@_fD%^K^EC?1pa<@Q)ri2zcnlOC`iu#v5=T!QV1;Qve@ zlnVGlj4jr<^6way) zxDKDp4c=+P&QjQ6V;rMG9KvwWr%Ig$s7;l-rDRpc$FzEmJfuy|ej5Gs6M=m%%Uf<9 z;`|c<3S1%mi4f{#Sq^)M8WegNT%zM7w5p_@>3?n8>5lDR62e&oY)oEovN2NTOJW7n z-?yMLqsb*K_|IX`1MkX=G)LMce9Mg^Fe*aLwha=`LGEXCQDZ+J0ld$#Scjzwl)={RA-d0fnleJ1=2G>rap_xPj6 z<=vAwEmP$b1Z;h8hI((^S>L%yt&I1VZ%|p_KaEdY7p^pO?0+5~Wd%_FJ(5?wM%2BP zifrOp3b4miCX`d18d67P{+$U@*LSn!GA?U?zG%6)V{C-B_>DEAEma<|oq|#99V*}A zUoS&{Cx#Z*PB^J$8kk+IV+y~{?N@y5+W9CpY<^-$H!L^yK%ajH^;n27Z}LIH;auVp zB$TaHs}qeleAvq#_>Bv)g2U;)d(51g7g!*10Ley0|G$g6YqVQwdslC>;=9v+z;R=# z*U|rnm&aN>L(N!M`>3i|`~U9sF7?0#eH=i7h4%FQ=OAW!+M~`y(-~aghK30jEo54vX%Rv!DGaQt zmtI0@#bxzqZTg}XT-hAz@VOPZ+G@tlcARXQ8Eagaf;%#I7!M$q1Lepc`8BH2t4pln zX@`xArZWXpa|1?HF3us0-@FQIXPdy@-u08Z@@D+=p?G808ZmpB7>7XBN{|=XwVOn* zbztlWPLe4e$1R!*xhKKuqx8d16j;wIhwF}`62$ZCAy{J|8al3&UD9C(EZExMcV@8~ z2XbY^t#5Oz^V;UBc%KbnK=T}YKpA%>AwN@q#=^2DiJdRYW1$)eQmUD*a-LD(Wu63m z!sUvHZ%G1tmt^KwFjNS1PEnlDwNhC^%jE907JEr)Du%CQnWEdDTbR_jSK8wxPNln- z{ILFCLk9hS_HjLTrcFbzdHATyi$7Sx`5WSS6*ow~eCNB;Hfd>*RXe@BOu(Tn3w(yP zLZBfY|1DES>#lrFGXmO79k#r|d4q5F4&1Ut43k zLLI9A;YR?XLT32%R^tl3T!&mDS}vMRaGrynai{)A~dRM@Q7>cT|s=mY=eOAm+;?f zxrgJ7y!c0E2FCItMMc&R2h{9D8VbjwUZ|{|BWfSYNN36|DcH^kay&3Emi+-kt1faE^?#O)}oGvdHlw`c{-S2-KhnGX~>j7?KmI*1DwERXcqZ(6}Ynky*qDLjN zV1V8{gwDoIYEL{ivmh|SY4DuVdSs(=X5|?glPsUx53`hUdJNL0W~;)Q%;7omnD|~V zH-69zN+dS3i?G!DZ2fSj$0%VTff3=z2BHK!fZnl!fs5pwEPb_$;Oo?Z=gF27_f3PU za7yW_P+janjQ8H;acpJF?SM$rF)h@8_Q5xqku-wu2GLK6C*V0Lj>9{^YGSG_no1=l zKPjsz9v2>x8Q}Xz9XvGl*6INRXS`AtBfQIR^8LQGoVjwLxudpK5uVgXA=hJD%8yBC z7kWXF`)b7{5;6@x&QrookgIpF%+eo8y;kL%a5+GL=N*z8Ce!_${#*a-zNWADBHneA z1-blo0awfh$5h%&)GNrWFOemd_N<;sNl%1rg#1=0=512oI%Jhcek+uPAeE^&f)1X< zN@w?H2$JPsmLS!Cx!zZ-7d7NK3&AnU_RE!a3|kjx8F8S+V(cMyc0+FeFCmZU>HHdI z?q&C!r?4>ZxMozu;2Mco*}ph`$r3Ta7n;+^lx)V_I=IxQ{=M@y)@l)pK8S#|Rs9^Jm>gs!bCG4*m2$gmU<#j0hI7$F$Y=+Cdo40fU-LxcmBF6I%xB zOtaEi$NA6=i?sbIx}1y(a#nAF@@Mdir~D2pY_gqy@%^eE4D z+M5(^7wzCuVN-VJ!$Ae`<=xDUm&C?VGBv~E>1A|H@%LiQ6ui@CujKlHwx ztt)EaVd~4vHRspMUscDwX&ZIo0c7CHf z{P@FwsBALR@@uyd_+6-cT~^BZFe%jh;f28R+32L^5WihxCW?}mS>gFt)YtAsc=6*3 zoXpJW6oh4OnrJwlV9c?4dXJFn^z=>I=kHb@UC1is3ILrJxq>m1s)M4`E!L zU1X|p-A@GW+^uvidcTT=5puV=;LEZ01rr-k7mKVmowBq=?Gq3}`XQt?rR@H+x#kUi z3Yq4@=-HmzMXHhD9Kr6gVdAK=JhvJ(bJ*}f+w%hM)I*j0XXDW3=JKBitO7>>TQPu8 zJ=!spKWu)@7-~x~eGHv$as|DDqed4JEb(F3@jZ6ORDP5ASuRv=o8NBL8zNqP<+H!R zbipEM$dpy)_4bAAp>7;VTHe<8nPfsV!7JWY)fPH12mV7RjIR6f_{WqgMv<1R~w5z2{=htoFhJ4iJg0Oxlm$I$h^E#pKIQkdKN5+LQPdrDS5wf*7G$QaCRo zwz|m*Kwu#E6n$EXW{67&&Zt3N8fgIs`QdVi=hR1PE(j92z=SF`HJaOaL&)1**T~*@ za*prGZX>(i%bw*4(h|8%V1NnWfen_MHllXCJir+{{{;>!xBq7X=HJtZc@w_o!xh`o zs14JnMF#6IwhCe=N&iE1_Pll{=+qyNfkA>NX2#neH%~e6E~*Lq?Q){qHImMqe=jN= zl)$B43uDBm;PBZ`o_@yU`#k5uDTKw$J;Ob<1ufhw1!wG`+=W$}SxudN3n2YbcWswT z;c~<^CnG9`o{u5rN{X6Y`=NR6M@y8J6xo|YoXd%}xDX|cE9d$#K|Zg!Ezpm%CTNC! z)Fe%o=_sQ^l^VQPt^ud*N-}}fEcke60@y+pkJ1NQjuf|5bIIHhy0v^dIL-V(dH|3X zc8{36?5Tln3^>7sRxOVDs_aW8jSk(t9}C&HS1Df&13{0FkHP*V(*tpL41Oo>4#wQF z^+_Optz11I=b*_hi5gjDGIT@*zDmVTh-2dQEPJ8pyG%LEPYjFGDk0)}De19Dza(|W z#%C)!ED=+=8rz?Wsm!qmWz$3>VKaHt^o4A%n2h^(Jeuvh*Rb$!ljvc)URvR-a=MZJ z>0W{I`=l323Iz#v7R!dTxpi##o{fk<5qzG}{zO>BIL%$7uSyQ9p`E+#xIP11T&o{b z5^q!4xHhkr2lfSHH_R_O6ctNxjE&lX+Vfi46eK#?QUZ+BAisB}e+Z9u28qvby5umD3!-P&g4nrYI7Zubn8ta!ov5xU&9wAR{&R>f z>EC^s4KEqSpWuolHF;XPlk*BwwDHVTMCsoa(6Zm0;^;&p&N>{1yN-XsQ){*e3-7y9 zQ?W@yw(5bJE>L02OTxDvq|*w{X?QoL;r|tmo2*9pX|Mn|QSK0DD}nXRTf1hFei;8j z^)`PD*4zH+OF#a7hiGWk{_JG)qwfu4!oRgfm$1^$0L12eN(w8Y|KP+NGcD9xYvI_hbC5pa#zBWZ&^kPNrik9Y5Z`R42{u%u3c2cr~IqOQtxO zrz1a~FohsDQrbd6VM2ADw7^AK#Pe|Nq>QjR=Ha!R3_&jfKQ!vZ&?IctFG*<-=`( za>RCpA+gr;j5=y4i8hK~+ki>X*d#8xwqTs=pi&vq4fJG2F*N4z8iF01aJ>dY)B&f= z_Lwp&TVXp!{ype>u;-Bw#PZQiF6p4NM|n?#6WmSfX+lfsJg5f!%-zgP%ynk*(ynEH zZX+_88HXNkE9%heE60L?n~t3M?mFj26-xnhu7utI1UbN&zdIBXgmm;s>q@QO* z#0NnY3tVJcaka1@18D?Oer}^;#p9X)-gAXB9valsMpxMdy{Uh#7dWiq3?bfl*t|e! zDjE=}$FG1i`3#HoSwG$P82Mvc5GD+lf1arfUOhImxUXu+sV|~%I(2AUe@7BTkM-r? z1@-PS@psD`4t&ATxxvH6$jJ4P^y8k|?Y$PJmu8hbuc^Ah6UKqu=8j#cix#}6K9@~d zBbY1Z9&MZJAy#Wx0^mbpH3OxY~O}F$P=)HWlZ^z7Gbs;&t2fSA&&CvD3x|7ql z*4XhBi!nU5)?iikD^9XRmD$?!C(b6@ujxp9D{A~CNZ)-(tNI+`tm|nn+4v%Jou0Z} z-`m}+K%7ceF8vsm0$t!4&@CZiw-ox!B}iV`(gsh9$V_0IX)pJEjP$g{sIC3s8gfCY zWZkVxCGjk9_sx)aRfD43f{R}vHI3JkdRU$F>`08hx0%^~xZZsM56(BKUh(Qdc-mAw zMwjO^e%4nP>86iPb6)vot8p^OASk_lfUrYwhmJ4|GvOzKaV7}J&Hwu2Y$iVGKFnDj z=PvSDtmqQgG^GU+1@nWg(;i=WiSB;xs`>;ied|elTQ0J^ zrv1ozqp2mJQhvq!3kf><7@MU{toH@WrTwe64n4eH8&{e77<7vBtFacmQKxD30AW(!4d9dbg%?(VhW?Q@9YUx*(d9|W;l3=bYWpl zNp&F_wH2$Oryxh~RaHk&h)&trIL@`F64g9Fo4v%{F@vJYCBJm)I%!_i_OR&k ziWNGJWoL|yO??!a29WSC#(kdx-x0U;Z0tlqfH zPmIbd#u_=o`@sWKzQQ%4tPy8$yzpN-($SAzhc_y6dx z4woqM1~P4D4ytB*i@<^29xl%2a-kb_hPgq^F$xZ+FHYL^AscUsSI=p3C z)(mO_w?;ks&iII9-A#VoGJe~`t_eo)YKRx@sftZ@gL+5!v%hxg>EGee26?ni(+D$) zOY5~<885(5r5vD)#Yaud5+i*rD5%1e7{YCUycTzIWlkjK$ghyJXqddEvu=q?W$L-0 z@4|8?1d3ce!&yxaAvE>q*dC^6KZg%jcuu(V{MvF!Mhp zd2`X@@=(ZGr0aK+lyup{&We9}6Ku=IA9+E5x+MPXh;LdalyxRUoUD~fW*ny|Q@>1u zd|g&>PUYiX^y^dj|EKH|%l1y{#{jy`7kv)=iNOe7q%Z&z6?8@3dVn)pfxh&+_T(p9 zp)tvioTSpm6VjOAD}s8#IvM%vW+X!;9IfaiV-{yE?@@u*J(?+R-e@AyWIO^834y3b z>xH=GodV4g@}xdHo7F*Ve8}Vyc}U+b1vsLPv3W?8ZBcb|hSv z8{=;MbL*D3k2oCUl4Tp{iVUkdjoeGY1 zOcQ$YJ9EGYVk-HN8g#;_iS#LTZ_?juGk(l|d8rh%St`*MiR5M}_32;Ns`>p!?!ZvO zBbW7fF2NM}O8iio@)xw<_crS6#XEXZjT=RYS7C1Yc?2gP{LS5FElxEama_^g)-Mzj}S!6cW<+b~{fJ)xV@yVFAbY%9UZ+5SBC2KWH7`&t4S5%2N+)&4q#n{VATiL~j zxHhm7aq6Wlg%<@MV80MYRs#E#;{V9~7A6B`X<`(bUlfC=Ak!+*dda*aGS9c8x!{}skO{P zq-D_=L2Lqfag5Pe(YiaUQWmp;5fFOXZMoM`+~8~$z3K$5ja>6KOd~|QGI0U`>`5vcEIOj*2w5Hx{XN<5GaV1 z2p(3}pJu6-_j_k>_Y_piiNH7Ji961uB*Bl@N*JW3@q#28FyVPzzxoqF$#dd4v|P=U z`W}zt(qvubKuCm8QmRO1V}6Nc;xu$w&xt5jc1 z!``Te}9F3^}JyLj01Rj3!Lw_4&3#pS;CDIql6Gq*Jz;$G*`5dO9~tPu<fD$X$Boz>Np1+B}!y%NO#%);SY$!L_c#F$4zleL}FV$ETJ zU4XVtbzPvo59x20e{PdA#>Qrg(Gsb|0Gr!%H69lP@| z2~dKt0ptuUHbyTGbrbW#)ouMlmmj6bLu2J`p?`XHjATERBo@fXTlt4+Wt)LVMpm3q z|B)L-^s*~|^93;+_@DBWZZn}Pz0$~&cB7ZRt)d_Lan5od-SOZ<~~jyg_lB}uei(6X4z6J~}X`@UXA zWvVzLZ6ksA#0=KmVE508)0-qr-kiE#mGUNI1=ebWIyKuWz5^MVjLWG(`4OKLF5TWm zStYwDb5}S38Or?j3Si~XFB=JZxgm0M3G18#%Yc}n^uk$W6b^%HH7C=7KmvYrYK*VU zd`euI2Sk1MAyOr;gUbtoi%lB1|W?u2! zv2k}!os9#cl4O{9rotJHhF8@k{ca{$J?Pn`=XXyk$<&dnUj<|&yxY>8?K|SWLagoY z`2s+eWhRTBTb2npT1qJF6A5y+&tTb2+QrX9R17Cc?Ll(SKz>Amqu8p7LYv z?(gZHQ&Xqr64MBEOGvz{9LlO$Y=g(C6_-F%C%<30bFKaFk%pdCwa*sz3TBYMo@53g~P?gd644{x+5Tl3X`pmZ+t$P03_y>)N6Hqgw0u%rP6xCq&2yHeP z*K;fbKR#Cvg02%F!#I|pV(s8KrDsh*i*+m&l;!Nb8Bl6YO~03$Ae%f4XY{0^;34*} zIN=@XX-}&TSUw{SM^ajDP(C(+ng*Fac4_~=kwd3dV8i2toIRqKjg>D=WIUbi&dWuq z1!0#uwsa`ULu=1Ecjy|T!2<~km|!0vJ;L`@lU*$f?A&)w9#M@ay;<5R|A~0$sPDD8%d4pA z6VQ~A!|guneAA}+rce{htMXpT$FSr)8?yKF42y?rXub@i9|_Nb zO8fL)pD5e%dCxb%_$;~BrBzQPn*|$z<1OaS1NwwAt-eotYWJTcknIu(7!J;ArH1qq zH0n8&^E)-mr+KwGYXQ~GP4+J{1(G?O69ihy+l<+<;X81NE+He}3Z&@%DZhHPDaj93 z9q)l*FD3!%uo_}%3Ui*xI$6PD2ps}V%oB}7TR8*Sw31pF9u{3VF06Xl7TvE>ukSoE zkAaqM6C4~YR|^Py$i7q^24|MdCv!QzJ7`tuyV364jUAQpii5Aw5b@7CiP z3IQbAHk<8pX;w;|s>4?K9}7?+iTGwD+M7>7dXH1#O^3aT<3l?86v^whM^ot zoh;fCJbw0TDD=AvM4X1`&!REhNRnu=2_b;1S z#YH}eeL1?Fypo9LzpBIC4>2RM$gc1)TlSdV{)DMs;LhYJSoH{m%-6F5F2UTcdePf3 zQ*zXpa@CuOj@d-Uca8Jm*CYP%t{Lpgfp(x1T*2*`W%c^(^sI5a6If+wX2NRmt31>1WT=Z*ruJW86SMM(J+kH_Hvo!mU*lE!E6TqLVuM_t zI=hpnpSX6QxdvAh&@xM@)Nkn|mvJ|q8_P^+HicxSNg!-Pm!`YfWZKY25;n|DH$sv@ z$-;}yyp7i~@NtZ(02>=LUd&D>MB>v^T@fsS;%V^PG3qE~kS)TI z;e~5PAyp_doU3j_`nBC*5Uxpps+vS6ynl$o-4fdmC&{cN)H^U>@r|&CqI{`LOdeNK zEGhb4Y*+C?=qebK8#)c4B|zCDtr*_MmF+7(o@E>Dj5ts*h#i*ML^p02D)z$9dOGb> zAeqv;zA=UV62Oc7GRy^^?a^k=wwghbDHb-WACg_@`eJ2SBGAp&pCp427p~C$RdpSt_ssF6eNK*Tamf3*G*fU-1omP^2Kl`%+;@(cEthe z0MBQ8K@$pF17ODlMO{tGRM^e8oY0lQ6^6I-55FAj^XZBaWg30OLwZE_*f=R6<$W_f zlW>@IX7gRPw;6J0u#|6W0ZD{kMNL$g59=Q?&3~>psZ;PMVd=#XvblxtAKLGKeCvDo z3KCd=5O{zw%GdGP;IyoLV8C*@I-XN{VgwsN#5Bwc=CLDo2Kuf@BxL-MC$kZm1jH+W z0D9QE?zwR_BZ_A z!LP#^#?8S|=%LWG!*rTOU$1K_n~dRYZY=Bj0=D9NEV3ynKfKqF0WWT{=Hz9_>IAQO z`nc}j2*yERFn0J9SVS@EGT}+lUmN3h`KJJPz;5l+HC&umUEpfoO%s7`G3=wj6$zGgC51b^IzEF*=zu84H0 zeH7C`s_( zB>HJ`TFygnLPA@~A*)Td#_SKF%`nzKMY zpqxu0B45idPIc!jzrpTslYOu5d!W*u1NinM_xzh{=;y|~y-bSA`5Tua`verO#7!Hl zZkRT4y^;Ao6&WcjWSx&fQSI~8EqAt5R^M;s z-1=pcSkF7_ArEePGyN)>xsZt{wlQW7Q5LFB1dbu82B({f@K70At z#?1IA@frOHp6`ro{%N1criD1}WAX=DYMs-3J77s*B zfLKBj#`Pi$3TuMJrFmvoQkMii^bKDGXLBc5yB4p|aD8!dfF2Y26$P}9anaM6Co0ce z=b?mgeElHnY~Nm{G_DSQ++myBfxEnwBqZbBRM#2Dil{6qs}M*>j0 zv8uzJr%HP1kG%$Yo!?WQuk8gVO}Lqr_O7B>*G*Nnoq7|uYEa__aP%Z2fZ|_pkjSd} zLz{P?Nq34r5r*gJl}4oV0lmQu?}aU5Z7I4_3>LtKh5Q`6EbYRSmA)IjvTRlgmgQgk z+?x3g*ou3dyKtN@4||t=h{)v<>^zqo@u_}T@(;Ka;v{$QaDDBopV`%h#*ZWM%nlI5 z1q~V=hQmw|+jGNpCZdA`~1-#dQJG?Gx5Fa1W8$N zO$_xXf6q_%zBa3|>NZ@?hZnt|FBQ1O3g85E>nm(RUSbz`AITxOg%=CMoI~Ao=r?=H z>OQzVGT^S>2E%Aco3?wE*XDX@U`g`W{3JO|S`!P+1s7Yrk$jqA0XwXkz-SiSy6QvV z@s<-=#zACbMEmqY-46Zkyp@XGM%3|z^cZBABk_-7-$;f5=NxHj{=sNDvb~MZns>_|ER*15PQjX$vj$m z&#fFeR(|5bBQKKeTY4=z4!ze!u>enrt zn(XKF>f5TRHpYK0bAF*2Qor*?`h)?lcI2#mZX@lI+_G2E zviKNZ7|G0+1+khBnepRYhi^1L=>+VdnWwBy5Hu3u_-`M+~%qkjxWEXlGgYzMG52f1BzJ ztpcO?;Dy&>mS^L|@v;7-8G?&j8L49T%n;3sL~RjO2j?!`5)+^&@}b5c~zl2 z{)3~=sb78zn}A-#({T_CATF~OBn$5!i+z4zwddknu4!}b7+<5(gf}d3mDOWD{UV&} z2F34iE4`8XT`Fj#VjRCzv4gf_o!+$VtxZ%dh;>_F(9YC3N;Py}Z+vTkWce#_PfJww z4(06CBYw#2;e0ulDeMfgu6Ux9Cp$#;>o}+X>44@M_PP*G?so&u;I#jUcU_<725q(R zR(}}_YM>ICNlE@f)Qf4)S7r@e)y9Ggn)wE_soU8Y_See)w_Uv|#wYej*!LG7{wS(- z@z!UI#pS~AhyP!ko^82tVIU7mQf2~wbVvSs@7mgDnCwj)y<#y-C)}aBe{Dp2>w-ND z4fJTX$F$NL@?=7goG@)x5{;Hu>(tK;0PR)drmb3~d=9HKC#W?Z*$!`L3vtaHusHrL zQF(xkt0{zWA?z;40ME}DEcHjo%O_h=8glKn1`y&1WMh^r6Y9T`JRLBqmbN@(t zz)aLupgdC~KH-y}W<(H$O0j6|)x$ztba-fG#AyQ7ec;$sQZ+}Ski0ILP7H+Ntq{v& z@R5ELt4(5i&E&#^!*$jDT{Bb^evFIpGWZ6!3q~3l8N8SB+Il2Z;iEE$Kb)%qX`nFU z68%)Wt=3NrcU8UoLH}whKXd|k93z-fuJ1G(Zl~2!q2eg7GEptg));M=YAnb!GpSAd zEFs%0E6}(^`>q;o!U-Fln{QppX~AW;P4z`p96yRQS>jC#O9i?I=fO_BnZ7h}AM9u` zluBMs0JTUnifWspT&(R@pR=(l;rO_cHw<-a1$unevYe=p^8n}`E>j^$St3vl9bR}d z@S?~}j$GN8{S_$dh!0OEVMXvn<&$URus!|na9oS@zXfUV8{aPq|EtgBAEiUz5!H6U z@;$D9paEPHgX5(me6p{H$gulXhj2fLYKX^5eqlyEBkybQ{Nnb1_C4$l67TbIf!&oQ z1EUiaknAXuZm<~qJAV;gUuBWTfz!zKA7ftpf#MAGOG{wn?ojtXj`n${@D+kB&V5w< z0r+Y@T#MqK?duu5b@=f!lpU~~oU(%Awa5Zg=qJKCQ^$^8DOOEtiO2a%sgeGUA_@V% z39Oh1#vxCm(Usb+M78i-F4Nw)b;NsoxI)A`}N#Z_bRSedOz1@)m1Pv!gDXx%f>l0 zDrzXj1bPV(fygG`mO`69>Z4X}-B=)kp~4Lj2-k02xn9w6wNR>W{%dbu_KYL)Ffy&e z-Ea|YA{Z6-vN3gST>7;2?McAO4|pBd$XhQlM_E4!=JFNw%F0HIzG=%Ebl`cpR?#Jb z7OExRXBD;Zv=F@4oqLxKoC3XvC>{eOZ_3UK!#>{h^=v>6@J!^|?t+{18o>j&`}8ER_- zfL@qotSB+d%VG;D0{taQE!JoBa1XFNmN~ydWD;C07m?0pKnxJNBOAIZl*l7)=P3pS!aEAII5`wdJdIm{H~VL!~tO=mzf}C zR%L-Ag7T|{2UMRd(IP!%Eh_%Ix40yo$|&24R+k2V&*{I#GYz;E^82Ph;{50rAcG0! zAb8-eMz1pVu`xoe4s@Hx(ET+SeM*%GxB zrH8=$HDpjB&>E4)jO2ZLy!%SzM-%EODIWF-88U~zNcx?4afNyPxct!DpaznGaXQ9t zx;0Tu0zVO4-`-jo^p2TZ{4#4iMBn9^wt^(Su`~yWC{Zv}0Lkqw?u~Ane&Gqzf8hx? zxLy^Od=*YFXE&fkg5V-bhj#`3X#7vDyI5j6*UG78+0{pBZ1SPvRJC5_%dAu*r_=bx z_g{f;M&&pjIY~X z%Qcys)9eCKWSfO~VeBiDAHUAlR(~k3F??1-+sdpPV^&YElxFq;q3>~TzM^dnqb$eo zRjX_kWmZ1sp8Vc)gv*FcjdG(=sIfyy0X69DZHF$B*iTM3qud@k53+W&V$+WK#v)Tu zEC5ot_w1=Q_mOmFO3s%b#4CtfL&yET(y)0c>OHp}6Wyq-KYngi?oS^vk*E+kcsUH1 zvEhgq;EyRNDg7ZY`sGnHk06U#qCzgwrxDf3s-&H?M5iv7-oC~aMg0j{CL3Yl^+u`Q zN{~{Ctut1RLMVxAj9m;W(jayy3j9DZ&iEX8PL?wvkVhrseO=MibOcA1?s*&k@Vorwh|B-;E6~~3S9m)AK$3F!(qHDJ zzrJ#(VD2Zrr;5hx^HXQ3tu?h!x&Eir@GI7L@U2Pi!5#(LWVF815%^J4eHucXx>i#X z^*``#04oX8i^!<>=lh-F9m+!cXY%#O6RZ>;eO@=ur?Vn_DHx)%77ze>)Nh!bFg=pq>T}7CK5Wb?xARugV^2vl2c~(tv}*%#BKogY)x#`%DJ$X? zcRa$6ifIsl661QE$$MTwkYfOhdq?La1)0l}%dFJAIRv;H=SgiG3n+wQoPTa@{QBfb zg1{sMc1w@Ul4PyA&$SZWEGWt>b^4+I&D(dkJTTs6L4AW~Y}cLqlQ&MJF6g@-=w+3v zpaVy7Yyyz0*kMVW%a~?J(~ja^gL~Nn{R>{aJ!D>Y6hkXZ!Ct=!uSzp9hm-FV$0Wog z<4AotWHEv#T%X)X)>V!`GQ%VKcMYoMD8t=n{3Y*?!)2b@lLb-$BlO}LCimyf^iT&s zdH${PIbrlJyO&E58|koLl+AX|7{Rnhh}f5fyPCgC`AGcBL*ALGkc^q#(V{al`#bW! z99@_anrSgB5)#<)KZkwL>Zn?OzM{ZK?7g`iCX)gaKj~DLguH?T3y#s{o;Qb+v&6M} z`xR=~WT9kTstZ4Z=!SR6$sE{SOZfBkx?PUNQ*}=V;nvt3ULPU%r5>Qo zD&e=d(6#BA3WQPSp%S(A`ZA*ZfMq4||A)P|42!aD+qMBIDQSl8&HY zu<>Jl`q5!#Kcr)!L(=yVX`Dc)6;wKHucmOAYnd9s1=RLX`)8~4mPb!p>V<8dP4HUs1$BQ z*F}J(7u}tWKO-};u&XriO@l2otI6cd31wO-u<%g?B*tyx9O$F_D*;hF4=sT%x; zNB%FKI__|%X9M$3K1|k66q;;C(zQHGJCp~Jsu-L86je%=0p9hWu-}R(h{q5zP@5r3 zVNBHNg}LuHb%0LOE0>-}($>X5B1+_5nMlkZGpsMT#w?u~RVtRMcuO5N9vVK|(ohM&+Fx zLdW@BasV@ew9xMTR%sIV0NV0qlq6tVKc1MoNzE3U@T{SJ&?(%mY<*0zj9eeAKhK;O zr26_h7>1FSg+DBS%shkITA1VbV+& z&Xk^T7{?*MKw=f9H6fd!xlpgQIuOyNL1xRN%v`NVEF7RO5uG>wwOl0(g*3;6KtM0U z4m0@Y1LegNIMV#xT&4I8L%gLW+m$J`<-+YMi$`25Q%{QhW*wBwS--xhhoJ*VS+i}t zL_5fv-INcdcxRjWT={gipBYP`lC%*-&R@&9GvlzVv|XycfYtaRUY?}__DxEHSSj}r zlkF63*YNX1Pq#O$OYIXl^e7vquEhglu~s%6L6izjtna?^(_V}7JWfR#_b-*TV8t9q z-s0TEQjJnPZ75m;#Zj(2$V8d=E5t4z#t+&PnQ!)IP+pi&`?4tuQDsIJSgijsMA zT{9vmHfe-&lHV*bG#EI$L)t^`p1|@37o_$|WPprQ=(*-4|CXmi*^&l7Cxvw-m>iRi z#JCmn=g81r>81{-*C}bnI`+^=M)nyubeFIOYt#O&noH)RXUQ}uz zcq%<=xfvJD!HXu`%0kgbL7xOLfo9sC1^lzkwBD8!@-G#aF_`74dcG>(aG>*eC+(9d z^L10i&Te;`a_rNmJ5d4;LIjB=>SLCT4RCHYottRr^53Dl+(_6?aftJy0da;UU~;*O zUZt&n;&*$oezdi`x~|9WA+0;58`!N?Pn?f-v37$>rUilHZ}zf_ww4}`{AY6#O!B?`Yty%P(9CVYjS5$ z1`leNp$7PEe5(cqWTb&g%ue9ULk1alpoK=320oI!yd%e0yF^4je$Us_DHVNJf<-fB z{4H_0pIsi6?3<|Wu;AEQA(SpAGG{h$z*8a<@$4+H)+T3UIgN=VewQmdK=!<3HZQbB z9*aq~3DUWv5U-GmIptVj?vVOQ;VoV~M?1Y3h>0Y$GX}fZa`gmxI&kD!hS4FgV!Fj^ z=$jsKrE_IcN78eIGAZjFaDT^A(7@QDYLOSKliSxwm9Cm*(V94Btnt-u?>^&vMvEUU z_q33+_0aXycjbq{x<>xfoK{eIEQdkWTwPuvwRIwQ_*lThGiC{4>^4HYJqXV1Uoj{? zwKKFRBHo(Dvh;ryYl_;n=yM8;9>=KhYA(*yfI&`5JT2a$62>u2H+ITL-0xi@QadIC zeTq-7UvB&2y%RbT=J7NZ_E zXikerzV5=9*7vLfM;2Rl5R2mc=v|iYkWlJj6E=S0C)K)tD97AiQ|r9*Uw8bEXCdBC z@&Hxvmsa3EiL*Z>(@6}&*hK2!@%y`;7_%27QW_*Xd}^Fd$=6DvzQBA2)6YeWAtW`( z7)0f{(DaiG-J- zoc`iBirE3_SZG3&Y!Ep%&MRWC_2ua?_4Jk;r*krLH>=VFl^C>sKGes>w)E+{X)SK* z&97P~EI6y#YUOH@+p6M4jiGrma_R0itLtmwP`4*A+B2XsHBB{(|WXRbMNi z46w}|KapO@<>i`90O9Qg1Oa(wr2%m2C_Dn@!%tM+$i9&|B2I6cD#kENN*dRE{l}F2 zc}jSY=5hRz6&sae0Kh`agqfP}g-SbK>YB%CU~8Vp)&MHHj4JlZ@qXUtK}FQ36iZLX z`QI&i3_D`b@fQ}USQ!~7;o z?xkS`8CLGBX&QCu-_7v+U<1GvMy^)ZVKLLBVmk=OS{qf`d4Na0Ueng{w%7 zVdOW6_+x`bmYu+xHyOZs2Uvok0s*Hc@ zs^4PH|00Xf@ov<$MwR56-f~z^wTSm~bw?w5F3Zs>Czhg3%^n76qL4?WX54|tRV0IZ zv0v%WoC4{a4Zwf=vZjS`OWY_2@XW8gBwv>>%Dvf}Zw_R-`XX>a7GOvAFgKupXG04m@wjuLyBHMXP(lO`} zJzD|t*eYOKl(0_u$9gf#Y>^pwr)G|gXFwU^`8f4(DyLf6mrr!8-bqMwTeIWvgd;G( zrBVgSs-9b5X^&Jz&#Fb4MD#nbK^8v%8XHHb^3gv}WszdG&OjW2u#)KZ|V5{vva+YjR7kQ86vi@bdw# zCm3hpJ%jyX*jZF-atPK)UM%xD*ge)#4#qH|uVHBIZR6GsT`Dz&a!O4NzCG@v?r4 zCmoz6l010!k3H0rjgc(Cc0r(Y z9MxInX_dhDYUd&^kdpIBtf_qAzKUOe4{l|6?g8NsQ&jKQ2@5;#KMC<0;l?#w;MD=e zt&3zZ1cq{0i$S*X4Tt0~TZ-SbOP7ZBHckZQcuPT3N(puS?+d=)IatnX1aarNK{|s* zf!i@JwOFd4SO8bOuS1e^woe=i@zR%h6|#r*bMbKnrF&SXY{(V{AI3}vCe#S}A0Jkn z&@`pb#C}FOe!cAhpSZXDP61z*TMK4sNAl_!Y^aW>sFc+rflL5<2A%qd+=5;Hlo&Xi zU$zn$`GaI|R`*350=zO)MU?qlN?@!Pau{WXC{iwR+^+~aqxVmSd=R)WrPc&^+>#8Q?*HXSV z>KBd74?Z6QM<%a31}>Ulu#G=1AVQF>_(~S&ix<=e`Ym2+V)&1p%K+$7G~@0eH|ot? zEhIVPzm-Kr^PPbHv~EveNlQMI8bEm(Mmr(n)|*khBk_JZheb0V9wWOlPJ4;tGVINw zVAg?n=zEbhLK0`Cac3sk(ljAf+c4f9F~3(ocbW>|T^f-cP6G}Oee!Qd^0XIw8pka|Zw}xeq-4ZE zL#s=k9^nBh5DS?<1jp-;#?}l<+m=t>XIB`1-n&K(`#tbU{deFqNL{1G$Ve5*hJ+D! zL+mN{Z3cf&dxvbLAzJy^Q7sg?;I~0r`H6F)1YC&G zvmnP_&s2YGLQ!qP^g%qLEG-*a>B^b$%FI6WPyM8*cE(Z9(=0xWNSmCcsH>Ei@fXb= z63-$-U!yLgEKe&=V2OWSi2$%+tc|y8a*-T>`MD+>F=P?;D%=gT-8x z$y|FtU&l@Tvu#uiR;R)ss}{g$7Rw()P}(d#1wE2)z!%o5YhIw?{2O?Qb&*?877RY7 zF*#c!m>JHBdh6}+LI11YmuC4wkQYbx8fi=)sOkB4|B^tig3<8_=C!`A{KC|HG=LEz zbIRbkOqn2irZrYpSg^OSlNCkDGPMthko{HE&N0|DzDHwGdvw2{h4Ovd(GTj#n5MIAq+pz2@C;R7#s0c6Y)k7yDEZbI#Wtd(CC?5}F<#I*-P+~cIzQs@0}1P- zN3aMLjwa80#gHV~KSSNqM{0#Gert#Oi=%w@s`}#V6a%8V)v5WjkM(4EGdKM9j1{`X z!QC1kx{PNY^6=xuAMjj01D2>uBi3@@;ibd-cS|=7s@i!RQ+hJ3orwulIrj637LhRG zsow@!(1?eKBlfFMR0lmtT}#>K7|X5`M5l~@?ZRd4vnb?yt#o2k^V$+ud%^w--|A<- z-{A#bzBhKT6aj6i(E6P$PqP@G2=|0A%4ok&@7n2_WQ~@Ejbk}QNB1-XYzzxd zAJeB8a!niF)vG;gOLL$=nSN0_Qy0s+_Wq5{;Z&1Fq=H?1dD}o zb`$ef6(&P6939=WaxD$h6`OWZ^(#-c2DLfZX2lPT*4{Xkyjmq#ypE z60y4Cv89FRVI#Evz_?`L~upv0GI! z@zGM!&QcF~a-Ah*l!_vAsLdYYo&4ApuIyq}28`gs_lk$d#3bQfYOntSYH6@;46z=o zyvY9isR3%`NWH&CT~mtICJVA8DfI!Jbw$ihDYkNUOQD{BD5a||XmEwfIgVPBzps|h z7Y|Rrl_wAqg1JbIpzFx$mu7nSP-v@iCo{-IUouE>3xCNW!!@Qrp|Y81641j%^1&VM zd|ob4scxa-Lit4y7~_;S{z!pm(9*Vs7XA9ZPWS>JT1M>a>O(Gzer)_mD2+P|L_N{c zyDSouC&zt`qecBcx^rCazID?X%T93Y4{inTYWGcER!{MlWHY!$LnXEnmQGl5DEvd^ zFcl@0oWwsn+!cpiN4O$fM}@4lo8X)HTRtnF6l_pQp|f_Gs!=10Do3t)XilJSl%>-4 zW@?~8y^@}4nmL0piEd_s!?2L$bqeK52%9!$L13V3cdb9Dxtm{$wq9dM*Go9XC?|-- zzY>xU8~9VvsB%Fy3^6w{Ys4`<2+v2m69iT5r?Db~YbmWdVoY;reR21d>S~ZQH<^0i=9RM(U7^RLi-5)RrzP(GzDFXegJZOi0$w=#B$cQRT4)iF_~;@b^; zsL|1oqZy(XP`jYLl+c>!nO%g@39k85xQ*|GJMKP?KOiTqH=`rvW+T^FFP2J;XwlU= zjB}fxpeXSOaSL?l)N5(F0*)=K!LbBoY%nG|`pKDIQ@)51VMLj4P@7moP0yZMl`+Q( z5t}x{8KWpQO}A#xFBl*DpVGpN2->4o?Z05~PP7>;q$uN;%(ps!z)z6!wCoy1G}s2@ z#mu~x#+U{Cp_!|%2pHmzJ&ERT-o+IqbW!(sx;N6z=ZqXHkSE5d?r1A#{ zz~G(w4-a(+T?|*#c%4LP316aLa~}s%l@lg0W{&}!F2wN)SmKZv+Dk8|!vIc9%Z@>H zVp*%V2YEGxQJ*#;%LCi^c2WY;&!rReo{?1jYcc;E_a*v)Ks5Mw{o0z```O}J7V#f^ zhYxVn9@JSgaINbfNVZ9vywKao*IrwISgm~E(omT3$sFP$V4+DV|L>K8^e5Ll3&tFZ zLPfV3p{(w+xNB=>gCusOfeKcotMiuq1fxXbAs&#DZx1q5(-&Rw!-kKt!iCX4F>Q_&Tx^aU&i zp>)!ED7R#&n_S zOxRUp+&@CgECCt$uXULS7+r>8I?1!paN*vTdK-yylbuq2Gt9mb@!I^oh*jQ7W(vt@ z-Vquxh51G^{(`xgO}OCDvG8Ie=mnzOPBRKgFW)C$lK_^fqnra zD4f!7GluMGg6@S5eh_zzss2t|+d5s_27$K*K7xre-Soc$-+>e${@tVAJNqnCGLpuAho!lBhDq;hP*lErkf4b{nmBqn$4T4c* zBi3&r4-7V@Jv}mFaCI$e-2j6}jV|8+10%^{$qACWn=Pw0J(AigDxE?6El?Bbw0-L14quL{%!(IkOA1Vzk+6G4*=`UG7phdD39#qycAU7fv$JUQm_ z?OWIne(R*r;oRN^@|e2441R$V{EDvz*1-(zk5=iu!nP!^8fWlg%e(}oeAh#^vAE(} zqb7k>!@#fw^T1<~!cPorY|dL0m6Q*5pbjPs7amEc>A^rx(|`3I z7qA|>U0k)QN06ACI<8m)tzNUs54MMhxl>~FA{C>BTNgTe{jgF5`!Xizd!@2FT}A9F~|BnlZwBpCl0;$;kGKqeauKAs~d@ zlT(r%eFEu;U&zgY?);on&UBN;n^<&_Mt)lJ*0wLErLnnMi7(Rc4#S7S{{rpOk~zDD zUbSy^gv?*%Q`>V~`beHKxTO;tX%Mv;4W;*Y-F-A-che$R!=c34v(Iyyb75ob-F?CC zf }?!_pkAs}QL(?y|a(jm15B%A*!Gzu5uYsc610U@*BaI}69xq^LJpln!71F!Gt zWj_C;E7U!7`AUgVZSi=>cJ?=Ho7 z!iwvGn~4=|Tw>zt($dnEGIbQJ-8~gs@=BziN>SuFG(tIP^Bd`%`g!a3#yx{N*Fj)C zQZHHlyt)Um8!8fXI9av*RuLZ<);&PiOPl|H|4_8dq?nx2F;TeqPi{Yn{J&c-r%L7c z1DX(i*k>j;_w$Y14U+KQyMFxVkU0|=mT}5Q`m{4`_-&d~)pCZxy-CB3BczZu`+YY? zLU2j^is#KqQ~!(Z74?(y|J;!N^JtnlXWK!co*@AqqP_vX8{AAZkb>MRjWSQuLLQFZ zPVkWeP4J1Wg~vJ(9(M965J565JrAmHrzf{P4}^N|#4pd8A8W>C1`^>q_ZsDJj_%#3 zr_Dl@i_k;sO3h!B*W`b{E?V!Yti7FwB@jJ|ml$TgqgfLKGnqyzV`~aC_WX+s{@Xn< z?av3vwdzqdFK)))9F6Ev^<{1wV@Pt&MRU7S_GG`gzd1j?b*wt zzR2}fV)-OkEzR#>O&LchF8-8uod+%Z2(}>&DEy$Y_qt~$VqYu$q698#=$B=ZI{en825*y$aqQ8badtO?GhEn}x~_QMx(8(b0cyy4~^ zH|7e>)K3R>_{KG7k z*Jp*^jNgQjQo&EeK!~MYM^d!32cchv9D^MI4GLc`hKD&4Ek9G4lj}%*hSS@+eB!tXNdC=YRnz^^MQ^*EWb$E3{ii`TKCiwW67XLBsvY%al382~4rkEqq0MMv zr@97Pe2h4hfp$Uz?y)I@E5GX;{2Siiz?n(qW+fFGHB-v8_yYIu4~#9~luCoO*wX%4 ziogBq_j;3ID3OV!qJE zalsMcj%0kOFv|1bexN$AS)*lXwbvY9mtZ)oOmB;4O>mnr5Y<7-vOq;ef=m~KlxeSC z`MHjU8Ac}JHA-}FbRaGDfD}IJ7jM&~@E|hk^|;P1+%6(eV_Ya7+SYF$>GTOTU@m0+ z>c<_}M8BLfp?@*`jXUMa7jwFcm!@6mZ!+Te3f`@f)7l~Yj#l3sHzX=nf1Aqq#Jn^? z28ww_P2sAY1Y;|9KVg~z+e8GU#g+BtoH>3*E^TV8f1Ml79zQnj@>`llB$2LM6k3e_ zbWT!6Tt*E0?K*WB!g)Z>rc z&z%4J&3{`V86Q~8OEep4PPqvLdVPI`T{CLG>8}1~N*d;q2*)2nO{EARGGErT%rpDu z`!iBM9d2A7(Hf}8a0?l{2cP4wY{Pv12d*79{hX$$|}f9q=7;ZWQeSd1&E}y#nGP)uy@=F)-hh z7B%*Wl7KG`aKe;22u`mt=0aDuq^g_lKVg9iICg`uhbxSfy)=#xH(geiW1%&rU{J9) zQQqe4m6XH$3TrmO6lmKS!-Q{yf0b`UK;I}DD^_UGjwTesFLdasP-Q_EWCb>^?S5fwa|)hE)>>l@C^4hba_bGo?( zYj^a=Dk%^kWdzyO`p3H}=a%<(Qw^e+mL*X~`7ew>^?z24aTzVo-p zPX8Co;+5W$adjO!%cCAtg_jb2etkNIdRK{!&*`!xW5QUg{D0>qe~u1) zuk%u~Cnu{To|GkZ)Ot3m(z~=4g1pn%r0%zg`@oD^3v8~SI53-|=Fz^FtT9aR0LZ)G zPDgWeOi+0`2bIoJVLrfY;f8hq`?oMMPkh6WV%G~0A9|e-D$Hbc47??z77iS|a~fRT zbQo@0w1>MGV;u$tLkV^b{Wgk|i%d4!p`lvF)^FcW%WiF>@|=G)&RQ2q4k1!xsT;t# z!6W=$m4586t{0v!b(s(Yh1%ZNA1cAv+N`cev`NTTpbOX0aG+;DTu}s2(o>qvN<9z% zz2@u6$+A8W5qp>8WEdF1_KJ>n_=9rx9?v}Tpgd4u0c1y29H|$zWIaHwVxZ}h=V7~frx*mV#d4xSO zqy9Jc8|U8L)^X;MLyqfPYEkp${Ij1lv$JWU+eouJthV^@x(cg{jGFqAorbS$Jtq~_J2y}4z2v>GG5MY!k1#%`5WBGidJs`27 zeBKIf5xbwWqgcONw<_ly=nibKO73`+<_mtgp>r>QoJXYmk^CG%!19y(YnKai@MFGc zGVmJ9cYbWM9DVM3weQ3Vy2Ec07s|64*$;N&G%q|*D|>h^9mYAQQc(O^nXGmi7GZ5g zD7f@GRoaU0CvtbU{eroCgad`2GPUww;cc0DWcppj-$<);lu#cL)Z3R!WCrk;o(02{ zmI$p#*mm+PQYkGKEl}0Z^Zzv`Q`<3Q%rSG5Bzz-_ulR8BU0~HJb>jRln4pYl9>dvd zJ-=3S-x_2|pf4~UKL~S^qi!mWeq%lIsAns=)j~^i&aXy{ z!4^fALA0z4a#kIx5L&1$v193e@8Mor=)F1MjUaeaHE0uDh#gZQ`HXiJDs<$8ka z+{EPM*hkySKFrhWf98+YSKAfU5*a#RDnA)ZPv)7JEk_1TKle6f)G^Y{iRkFYgCBTx zw~Ab$a8ECW3sXa$q?J^;mo|(emF^DN&@4>LvBVCZ=@V#pE4T;F(Ktxi7G+RMI8dz)P`eoT`Z*t?r1|j`V{E zZ)E=aFI~fTqJ9l|yXkRb`%|Z4?^akHpCDS(Zc!0imtuY^o`=h|%@gkF#EV(+C zKt~JiPP4^2*>9eQ(iH*d`DA_NvMeCf z_i$|#yGl-n&({|#Rus(0vFHorM?-ygE&Qi^)+<@sP#wwGP21DIsYCEp7o5H|>T=B* z@6bVl!4vFM*ji4V61{DmEe+h3aF?-k>vYD&2GvkJ_g?vk((=`h?RP z4&!7u21me0@XfJQSJqpOS2||uGo_(1!BYWTF`5dlB_cMj#V=0FSsPa)NID8NM^nsN zDpgP)?epTh4&+z=9k~uS}?{A;a|RmV&%)an5?PA|@Z%AJ`t!1MFzw(9Zm=U%f$e6nDO3842I zEB9HmhqiyT1ng_ZCmS<(kzx>45w1~CCGo;dP2t7SK*#%^iQw+X3-{b14#I-i&178rUpPVM8-n zwWz@j;C;)QLk-1Huvxm}g30AuXAA2wS6=sNt7RlOf+P0Ro<9vVWlQ%0Vt)uvU7pa{ zBCr(&#)b-O#8}WMd`&=BwQ`!C>v32OQFQNIYl!bA=U3BX$od$RgBMFD%pg5|o?Yv| z@e2m$Cg=h0HRMx=GE67@>Rb*;h}LO(Bn^y1f0^>n7x1GUe~4#xFod32jPsyebSMp1 zG)3pf>y6eK=?0<3DZ3j&byfjImAeK4nTggbtyxv(m|n5;h(eub%`20gYVhaex~dn; z^(81<1t~gPEt*%mO|ptc@3TF40%gk_dNbb}-v}k@Hv32=e-a9~zieRpdlaC;YYcbF z@x#>6K|$DFOggwy?q!WpvOne;&jqC!+bboFFy$ZL!1Xu2Vz9Q|kdzjXXi2kXIxp{fi+b z`hgFw4R3v**0e@fP1u^>z%=NK$nY=rCOLL!YbxuaS!8#@K|W(G^!scJ39!#T3=b5Z zhWJ#7&8@`Hqr67LS^HBd%HcBO%TA^86WTKTDHUtbcVctIvIx(nX|fepOuGYDM2aig z#f1+{n`GGejxL3!l>$oohKT0pda>VO4^Pk>^Y&>!$zB}v#<`lL-2(AGAr1}EH7B2& zt!i)8u9gvfJ2P;y;7YnMD@Ij~vKU4j)`IQQP84CPWY%M2zm=n1cWw-jKV*J^K`~l7 zEgmF{j;+n2LV0!}y?PZpmWKq>kEN)Rsa zziK}5Q}e8w`N&{o5Fc#`oQ!LfDXvy6MJIvKv%d+o!{&Lz`hiALZhOAavDxHth-GfW znx~Qz<%W%2v`rsLU-*z;Y?2*2IzCrM!C$Lft48wWq9Nv6`kWQn5nQGt$ak;te^)yK z)9v_$#n^91;&t@5EyI5RGXFFX|9)h<+dpSD(=azV9AdA3->A5yXO=&w`jRIIhh8-N zF`+$Z%_-%1N|?I3F#ZY-oeALp3UPT}Zl`0kdP_D7PW;gfATk^0P{CpIZQOE-``L9x zpZZ(7M?w{=kEo@qy4iomObwWuXhgU^3AY2XykAipENx0=E)=h@){ahfsr&_Vb)ns# zwfZx9gu9SK^>WBWE+yh6xk^kLzjcJtrMm|AaU0+|*m@)bN@D!+vf2Wp4g1p);wDyq?$<2_2!c@8XCH?b4G(PfUy#q&zLRD|NnzQo&T#`(|*H$aw=Q zvbkx<>fB4+WLXHaMm{Chj%u?VfVzr##e{t&txn>mr4$xGHX7gzEh-8vbyt_ltdX%C zZ0d@(tR>|PX3LFGcMgl0UQ z!X$X4KEOqH9}25&zuy9QM}BW-_Go(BN?ro>#R|$eFAQ>~ zE@-RSUyz~|+or=ad>T%eceM6>_<|s|tTR<4rJ87v?U;B)4Nj{`JU#CxYNs2kyB~u9 z*-Q36FqIcCV%8h{9rVcozFKQ#Kv>!4>>RX1L_SG7CVnVAq(dyVw_jJx@#oGw_nK<5bT zs5z#J{QhTs*3rXfB!Lz1#vXB0PR1r#2eUecnb&98_6}pN*0b z%sw|UwExL!4?QQz)jY{1a5nBkM5pRrJ-zH~xg+bBQRDv4j>SuTA`3D@!HQprBp2=TPebZk48E@J^j+PfnO@tF`Yyn-MKv$?cao1NMVtkpe>D;j{rp$NLH zt9t#|(7{iELTv0G&!%WxDs3v?^10XbtlA1GekqO7<=;2G{Abn$vfLfBE)Jzw!#|b! z{a%R{l6gDNzheQS_s;&{+5QO5|8Y~~fJ|8>Uo?s-=r*3;@8bS>7rakFSPccxU&@oT zU^cQR0Y;F7?&3!q8fg%}dYNXHhsD89Z*NwShX67bI-XV3v$H#CSZN0pcWY+`9Tcnl zD6j#Shr2t@^(C7}!o5zNV3^gZHEKaSpRuTZ$3X{!Mh-cxJ1YExNIXu}PL|I}Hgc8& z(X5bK=g)1B*TTh*A zy)dDY_TX1Xr9nU1MpCBfZMwiKUG&bdT@#pWPat5UX&4b;sy^H`U+#I~r)%;d=WsU0 zNQzI%#3zO5Rpv*(!1xi;T%Ew$nQlr9Bgr=z_c)Okk1+icAR=(%N<2(yqQtiEJFEK> zw<>av?bF!LnWhKbq>wJi)^^|NxI_{5kxg)cPK^ca`&q~>*n}lrg1wA1O;@;HbpE{2 z$J|slHaCV(<~>1zLOpJ% zll#+9B7ac|bwZ6PW|<;Kzy=O~?=gZSk$eMGa+0AZpw(V{{U~4J*uZG5E~gmyNgdG! zRUIcbo(I^kn60;M`U~cGJk?x{23pzpZ!H++3pMN4C2&9&v>dK2bu+Y$>qJ*cLh<&w zUodt{ue#Yl&^S$}N$->6z>m{35DO{|s?POTl(=$04{#80?zP(AFVxxD;!L#TfWN%f z*+Vers#tmX-qFAP!+Waf8ro299Qj-fjMV|sz;43IIi(ln6I$B`P5|EA+>Gs@V_uKh!9|NeR zwrg*#-(uGYILaKg;HfzObKvRAr$!+D#8Ur86cH|(jT19n`Gqz1!o*?WrmU z;o*TNk~45Ebr&zSpzP0|z3c0rccg1T$7C_}6G1ZR+H1~5N^``ydi0fpO)G{jRivh= zoGq1AE@w=XXW9Bx+!4H+9;}iX3gTmiF*$MWqRxggG7?CukthcesFL!=xmNgh| z7G99s|9mq*d_b6b^mg(5F?OonDei(6vEd2HwBtrN(=|nMC%j>#e8Pp6l)qqF^mwfg zY4f@~nQEbXO==AVLgi%}{WrR!3VcgsYszd{MVJRrU*7MTapvx0 z<33Yomi_Xl=L_gjC}Xym?jfQtr#E)-g>VM}R&hfu5uYAfzA5ntDKUfcV2f-(pb5vf zTb9?>FV~l32rWZ>F(O`>R74Wkgtwyp zEQzyFP&Qt;wxQHE&qo#4g1_Pt1r4cvGRqrx6>-EEwYlIkM)bS~3uHojT15R?}A-J8um}$?p zbk>5^&*6e^0M3TiapNqdbv!NFgfV50T`5me8mUc-DOMZAA3dg+Y8Cxnd7|4X5e&yO zyJAw$R(BS0qPXQzG*_{+kPGoQ9Tt^x$8RRY32Fw}VGPY0(#yQTX8eh4nO3n#>}JdP zoF46?yK(t;lu!`?F}7`4DY0YO6I6x-j+-5vsLGZGJ&O#HVj^ekqhdI$H0jrO-Qd(z z7>8#KB;F8Qpy5udgSba5sS3>;>qJ)9a{93)>}xL%o?{<9Cmb73*IQ@PR3vs~I1WT& zdXP5bw+im@ivGq`6_OMf%bDeI#h@}J|BcoE79fY!;36swK4p#3H2BY9Msz}S5-p9a zbiCsg_4|GQ8tGBK!3*-nYIQ%d(qX5EBX`}fi>{L{wfuaA_*WrDOGUO<=5aH+G+yRP zgTH^CM?G`-nSp)dj?p5O1Whvy5i`wNBl_8{zRlh|+SI^k=8zS$^oHTV=|xdWmw^!W zDY5)EqHWU}P(dgYo49K770-#hWYDKTtGXFBH#wtRjs*S^$_tC9dG*|^&V=3on$x3& z9qawcu8I+_iJvZP+>Lsz37A+8$~GmkbzHeJV))2ggeI&C$JMc^y~;ID;_CfNpXwgh zj2^A$peVf%3UXnzBa-pd%|SW}4u;2c1di0j^4C939O!m$3Yjy#P9mgO@wM;l2N{*r zpRCivt?7tj!K^C`&Wx|E7{xj~D=|e{A=WLWt59f~g_nEqeoJttE;sMlMIc~)aB77xGwd%swlXIi|X1FoR*t13=HYPfTAZqh7n?$>3ZhlD!W1`DdeN_wX zN6IY72vpc~u@dr#@gJ~skkkSb;nY;WR!NCC$*x)1#v{C@;f$;j>5TTtHDC31mU~rD z$!F234WpmK=acQNNMxj!5c-S}rSDb>ztIa^AQ!e!Rj-~kB!^KC6Hxj#x(SygDm;M=+k zepB9)-C*l&7C@)sES-OJtAlyx>Xs91P3F{Zl5!K!J#%j;&}9Gi<8WVmNC-yt=6A)_V%2F1@_h(jG&5cui4AK!WTjfCn-Y=)>JM~I)tRh|59w00?YqZqnr zh-AsuBXFNf$NGmu=Mp#g(c6~}zE3FpmoXAEi#kSV(G&q6PgBe_)@hg|%}=38dg@P` zCF#~<;Jvif^}yAFlOe{qwM)~h68)^EwF8rfMMYsTJ{AKu>iGd_5iBihdbPBdQqMD|hcHSC?T&S`CD(VQd^7wMN zI|r9IruReU+&feBT~WE<13hf|Y9iEJ;hJ2*QcL+#tr{AMY(foJ_bZ8I0M*l0q@XA{ z&m31m{s>!oHX(+BN9g^|{5oQd)D97}$QDmt(=?d0n-yyQL^7yq=xTI*O~zd?v-!Xr z*KjR?NynB`=Ml#I*e0-K1JEn95zo3%jrCv#pO+z8_~WaD8obp09JEeJcaavS~fo%o!_1tX08*!Jm zCmx5sZA`5e=Y%&0_z1r{^9tR`L}+3k>9@QjqZ3)eEGf78q$@wCo?v2d?$INPYOJc1 z+(!!VvohPIQP+=cdkbrCCOHKP<9S-NK_MZ@onQaj?t94pWh7qwf{{Odg^^Ql9)v5Z zNjF3_b5DdVu^WeP@W{nogkk1J&UYPkL4(H6K%{QRhva!HVuKF7e;>qdzni!JYwK1N zxOc_%aZKPZW=8A(UW4)f<{q5${wqwR+kH&OhZlQXL~AMNX$c3PpBU>g1H4t%XPqTJ z%+~N`+I!C%`uJRo=%zaS$4EV8fXQtlJt+QF8ckxi8&NH_;&Gxl8>cppngkvJ731)m zbae+FOpj&?6~Zn^cBCC@eow;+2jaY}+*?1E3Fa;F_MZ0eKx%)nhd(s~BMmncL<-tD zrxU+9YT+H5$pP}@jo2|ZNnWa-8-FG1s^OQ#)~9!*r5rrbD|uYlHz)nmzCs!y^T#X2 zMKkXt21$n=;xdx$ROH;YRI|MaSqa$3*z%_D!eePZqdTJav2!?5G$HHqXyNO)3R~0q zFyjR`L5P7s7H6@cKV&e@KO~6SCJzJ=msy{15zFt~`>XI;4hR(#RXR!1q2!NZEW@>F zTvmKBzq|PjMd>DBN0poi50sPX=bR-Zxm2DgcwjkEwkIDgN-)lA#sh2e=cb2EHs5YtgVGnU76y)y2G!u9DKY%n8ysYb6ptptXZmy@J%4sfxB)Ht`(cmAnbj*gVHOtKMG*Q zg`yq2+OH%QxEhjo+s2vBPkQ=?V(^Kb!?0%y!Yc~cnOPgG^w5d?4zvSuGz`+W;~V+~ z(|Wyhg&r+&7FyGl*e|JH@^UB7c;*rA8D@d;S=Z_h##9Y`aG_pJ>B5J_L@oK3jYaPz|({XjMMf%sH9Z`WSNxD<+kGP)?V+szp zj6%`#(0I}^Wk)U&zIJrv`Ol8VUv{vXA?-<_LY8|S_rMs4F1A+coXuSU_7YExmJ1^W z*`_ztvU6hE7mk)I=n8^jtl-Ui}cX6cI#a?y++38gm^GDdhE^;A;4 zAFU#e1_R^{CRpF5T0HDXv)|Bno8}mc1_`JRhs1J{1QgRG1_;l%ip9I}R-`_ju@R$* zp&=ri`81FNYPKa02;MfL$1+^hV#Is_0OqVb5y#zqowxxd9A6TuZf(zpl_c>(OqKWf zL^OOt$zv3b7lX}g`15pnaC~M(I(a&P{k#f|iwFtL&OXaKMno@}mw-ZJP} zJm^&%w<_S&Vi@mudH4(FP%`YY=s4q>g%0yN3BAO7QBmV#?(LKj>8iDC6w2u+0dVly z$U5CPZ2Z3IkIJL#<~ zjFyY}n9mpEpCS+`kQd24>iS(u2+ZQa@85n`&+4^0D8^yuaFXo@5C@X$$7AaIe0CMp zrm;vh+jpVchAm)Ck+1p`zJjs~GiM3ukuGBo(Uh`3p)KwWD_|XfIt_LYPJp<-U{-eH zN}*{;{XkONLb!hqe^ACT8wo3t04QAV6o3C|=v^YA&1;6JL{GxRy*2p*CVl&wXETX5 zTsocZDIHPU7b{iZuQG|t(FpIgw8`SES)4P7DmjnPKy}NQ%t~4RhrPFqih>Q>c2T-Z zy1Tnu=}zhHjsa-_siC`D8YCoVXptBiq#LEB1*DN@5BfanyT9+-`|tj-|F~RBm%3&N z_kCa2c^*g04))JvcA4O-R$(4BK`R~<5%ZG`e2{*$+1$^a0k7Ax@f$u1F`ab7au_S~ zctlE?4ZI5D!Pe)V05VH4^d10_JtAx~D;7>{&ndie(mu5kV!zN|fY0Zfk@g)e8&hFM zC#R>UYUp^BQxlOZt!YTCJerghUw^d2HlL(~OR(E)^xJTFxGzv$V4v@jp5}VYMi)|3 zv8Rq3@x42AZ7>@k5Zv0j7}v<6=|$dIc8Ku~bWzWgs$askw0JMr+&>~Xhr(WLRhD$b zXhF(qP`eq$GlL_=NZ2W_xmi+T!ncdmvq`fU{p4-taKrrG#9vo*FFSxVU5HZ;n=P~e zhBezT?LNSNg-i1`g0o-2rQr&PKmXeXFcN5=aaHaXi8n`J>48Lj;K1swM?b-RP6m6l z{VAEmye)SQe;ne1o6xje7io_6XZno`bj#)=6906!3EMkHE2Vy3t3;l|PB%LiW4I#yWaC6rEydIng3S*^det;Ud!dx_cvj?A@x zU=n`4t>Xd{A)uYBm>+ggMzULI2am$e`9}lgtKS8S#*-g!Zv=QuJXco8nn|i> zZ<1+BWS^&q6t{T`k8deSODkWQd3Cu!7fq8m4JB78&N&}m$F!=-MTjh-wg~t?qaV}W z-7N7Z;u6?+5T`h@)?+cn=g42UEbrL8ypw8CGiAZFP^vr%m|9!(Stj|WO}$K3p|aHR zA}zz9F5SShH78R1^9%kzk5HJ_wHfEpl^2({$l$sOpOox1l9jb* z5w@T4vj6;Ps5N7KheJC1i<$NdHMgB`eiZx)h;=##Cb3CoyH302tLdv!$BxVxzGNNg z;Ce#Hs2az~W14U8cS-e%fCSk;CpOBz86nOK1JQ!2oMB{Zwcs^7&vDnAu}eX|A6p%| zD-XzN`D5f)c&~#$PA(o6Jla5KI)*OB$!NBVqK+YlWgAOJS2UKp*8ZQ`+uOu95h7b= zJj<>A9LPtP56X9LcFT^{_!!&A^y^w2X8>h2!8eznl^@fty-94Bx#F{(VE&q^F{yEk z8E3S`DB@>Kjs5&a5zu4nzkTj?23gEIz1u!n8Z28Q{+?-tgHBpRCp6Z>8ZQ}!-u!DB z4ewiS`_U&3_K`&&hu}F)`rI zm;eerhVC5_ny)*wK8rs6)|Uo+&tb^)i4MM3wG((lCkUl-(;M@_)*AIOArzTkoTy{aI4{O zZt7VX){b3AF;nI)cU!|(B=KNWJN;tQuFde{r6oePe6N`mQ?C6G!$Yf9tJJ$*ca1?F z#$H#%45V>F7#w6T=1T4e9DVJStqkgb&TS@^NJ2Cl@!?Crk^*m!*BO_~a1$86TwDoZ zL1)*!NRyo=Hg}PQP*dKI11)z<99}!S-{=ebfe1q45z#VuLWX=#CBE&g z5dU!_-?b_~dos=Qi|K!0B=w*_3_V7n=Ylx$Ub0(gfQT{F>+>13{3q<|+d!KXE@QT9?cBOjt&gP-fwmBH#J1k)E@7DZ3 zFhEz?9c)!JyG%_Hrp~n0P^aw-SW6a6MX1)>CP&+IeI(^XcF`v$kIS{*2+3!%oVC$Q z)4y+~(pC@&K_PPiupzFmp2Osq-HWk9(}GUWE47+9uB=ZYxyg?J9eXyY4-DC{wU!J# z4c33xSMvmh)GQK5R2Gh4D%(lx&k)*$KNd{X|`B{s7rHB zK7{{;p7`PtzIxEvooqLE1ormu{SUH2g$vrjrF&)}Gpg3qWjxgg@ z)wek;xr(aP9CzoZRXL%iZdnk-|v~S0F)c~qVt@7IA6Hl``ohl``%ki|SHn9YK`>*xHSX>EZ-$N{v1!K?d;P zM88;x;%_KkA#e@au2c_8aAAZZDfxJO$NaN;KiXMdAM(s_vOD{k zT5tUPLYn_{McOz9-HCffURA+m`|{FluMoudB~N%J)E0w&3BqI*diXmbtusqLfUt zH{O2l;8R>_R|A@8JKv}HF?bw=#iug)|1_wm_&`RV7oYr;AI|>+bL>;%7{O2E0f+(2 zsW+eU_6i2pJrGJ#tdE`+ZPv=ipJ5Fm+_G6TNdSL#fSGCie3F5)5`Gn}asD^A8?n9cm7l9~e&gu6Lb-e;yg#=#)&E4G4eQNNY>4#d=Q14j zwE4bW?d`;Oqb^&L#JjyoHs#IU0&flUe&g**Xh)$9KT$S+VPFq}*jYrE79}wRBXl&|I5$<%|HZc*tgt^{LSo+pkyDN(UQq?W6c{ zZg)tGrFD**Ldwo$`MIp@krgLfe1yIPFo{C6ysyz)!{>J%^YY#Own@q>%-RQn=Wk^4 z@6fUK4YeqK<&{*sS6BdeQia>}VK8(5)$9uTIu4)l_K@<|%tVWSG|G54Y{TtD0LvcH z1|p_uvGNu3}as zY_U<(%c@nVriX}%dSBbtk5#?m`J^ND+*e33DgWJRp4+i|U6k3)Zk50jJaOvq6y#*X z`opwpoG5CsbW{wJrv}(AJoHbVigq6-%HoXp>co@gat9L{vM5y@Ff=~kCu56griPvO zkPh&^riP0qzn+u{>n;u&=BXR`CX7hM{T4q|fJ!npDxNG9v~ zmTRk+63=vRmbs>Q+&p+(t4y?O%6Om4PE)izoIE5eN!&!`8hychCAx^>xtC%>S_!c> z@jR?#GB{1MR^0wx2(wVn5|qzt4NuGa*@oD5%|rS9e>t`oUBfr6S-1@S1aDG6F3Io)%_mW#Sv8DZidc zm(M(`oV$NhaDbXb)p|iyJe&75-TFiBcU7Zj+L!FsOj2W@jAs_lz&dxBZ>@n-XC@DD_y*V5Chd!+5+{%#N1njfnDkr=KfV`hRV;D+%-ON{`!fAs*v$wy` zg0nFdnR(0f*R6*Le1Vhj4ybf5hB+OBM006H=ZO2NpCdX1MZAkm=5DbaiSV1O2Q!~f zRI7WiW4!a9cdJes3|+}Y$?Hl}qIl`cw}E!j{nIz>=nwxgeQ_=iySdkt0p^ZVe<)$MksVwLtO#gYC>Q};@ z&uI5bX^v}EP!Ew5`IaC}-KkX*=V;6MML-N#&+r93_X=lP9I*0ZQv@B>)@0%Dn^uwQ zE2gwo?~T%(I-yUEfH^`hI%<>?%I}LVX~W*0S3tQ|i+Zn`6;9puGeH3fu~1vPOV*&N zBB47q3?3NJI$kUO)+8T1i*b@VE{r&~w#ZR@swyck$_E|M5Dj~QqQYhsOqYESqhFiEHbkvT&|r zIG1H5{Aa)dt$XGib*A9>-o`;)S{3^~enZYBMwWoQEa)xEey1w(pi#97MT!<(FWemJ5u_`95gJ3Ss$POdzI*cGQeYTZ+f{F7 zZdU4~$@G*Iag6!1fnR|QGZHl1`QxX-yS-i^sdENCCgwGNceCt0cY|h3X;T-mv=Y6P49MQsUyf+iH>moP5Q@ zU*U58!|AH!S8$?zDZwOv_?QBwP@2R>($D|p|56lM9IZoS!0}S@z6C#I>n-kL7z1yo zfYtu$TBNL<0P6GBPML%ZqY)DJ%hd$!48Qq9Q#;cwb2?XUpf1Am(`WfmAKR?_`X;-Z zT;{G7>ugu2{qmik+13)@ubv0-695=u!x?@_Le=_>N;|7sHNOu)((du}#Peh_(&Xt= z!ohqz`V}@ZWv8FX?|)l){Wn9flbw+eehc5AfX516c@!gqQnj>7&nUQYtB(P$(NC@UQkWmAM>&y4ZHe>R$;%{gNHepC zMmR-Zc)}8$1wTJSiwVobB52j-AC23j%D^99%8loJEcxVhJ~M52PqGiHP^n^wJpid6P__)$XK`BlZu;7AB9 zWiW4D{)#Rg2#BAWL{yFTiu)O*k=YOKsRm`XK!_)%l^?8sSe|DGouk<$T+_$|YWq!m z=Yf*zl5y1wF3=oA9&GFr?%cmaL*UcI0_Ri?#)8MF6C9Pwm9QeY0RZxF;U(esUVgQU zw#@8Xk@^CNE@_>K(=}HL_w|_6$UO>?As?ASfZ*j#CiSkFwB7@k-d3*>#&}i>E_e#; zcKmnULJkUSYKZ#v;Z8MCys*;z5_{s032$B>T8MlKxn)4sbEh9?s)Aa*AxH4nL@f`w zGhQD*s|2wnBP9(k9pzq;%kglRb2=5s{pEeT=ZIA5nX|Arw@oo7yPvSR6Y2c0;yA0n ztnWaK!F6u*&TRu|`jLN#S2X*N-MGtnuW4+0FL>}H$tudCN`Le6vFyP3@KvFAS(J!Z zFzkYwSM6c^(!xGIlaT(YNO};;fPD3G;yl=Vfo&uLBboA?xy&`l#sLM|@qJ4V1MT?U z71)?#B8??*9+k7?uCc?XBz0?@L+5wYBn2hgm*KF+kCOq z#6qC_uWhaYexJrdGnG2iy52&gZs1 z$2;Dt&C?zVBCbACZ;BHlyjFdA0ut5`bSIW^t_SCAV>@u_MFGU}*v|F8TI<`?-SE^F ziSxKRCbg*g7e#xPEt^;KPvI;HqbH!eh^=#r#aW%U?SAE5$}*@0Cy*;{s=mcS6u{Pm z@+n_WMb2F^uz^H6{sB!nFAehTl4Vd5rY=^;*eaC~XVtfGab!XmxZLr1Ll>3>3x$kn zwHORfV2F?L0>x5q96#5V2%_0s3YuxQB~&`bYe^YFkHDWn3c-MhLt#;{j}IAr_T=n^ zRZ}mI$jqlHH6$3qeIpxdRz`iqj`G~l(#n#`>HGmosu5b5h8JY3te@1x+1xo>j;5&G zu^I$DBgm1KfLq8si%;0XP=bbjZU{p)8x(+xZ*)sz@Od2GYyPN}ttMTg`GXvEMfa%1 zDH$GzME7~4YsBH^4(p@RWj;_;e8J5yRZfkz^vZ^20}6;6sOL!#F;SQ9m}y}oTpO1Q znNA&rt!8*)9(GhrKikur*IQOJ*(+@w!@!ayeqZ8c!{;)W=G_&0?AjCs?}(Xx0~1F< z2k1W4Lsn=Lu8sj{kwlj~T#xt|)#VX9U?)Kn0FakGLX^N!QU4$KXkac4J>3 zQLLhu6S!dwZRRAF{S^@kLi@5cTY;){i0Zg3st?-7D9?(G%WGM}i~uog*Nc5VZ@n{% z>zCF6a2*~xr!Q{0K(i~#HgY5>4fXRpgV`__p*)zqRuDBgu+4Kj4%C>7K)#k`H-vTR z*pKjn*sbfe15xZ{HbwrS9o(E7r%6Xu&d&^bzb|FhVUmX?IjnbQ(9ZqPQGN*zZdahu zt1>7mwdy;1+v0PH2jn)zua?LWGofFG`7Yf~7bA=+E0HBa%U~8R z{Y)GuI>a+$G&pw#t1R65jwFC43QQ-p5exqhJO99d0V2V~y@(yx{S>{{aYZZLxEdT$ z;5%Y;MeVFCOAY!!FjC~y6~^n#j9eeFKUGeN|7HhIN%Q9w5PXW$S&v6G=)c{bqOVZY zxh)-&j-(CE%|!k90Mee!urZ4ST!4_Bo0&^g!gW`(oonV0@U`0V zu66TDYu51hO8CFvT&d(VYu#D+gPV$fZ1#}EFRI?g(iul5$Lvak17akA#^JltZ@|W=q<zkE#M@3@^-J=T;atsUOTqT5XVDZ*?#IVyxz! z#>cJ+HgR?Vc*e$}(X57$wfZ7&QXT3)Er06o`r%p330JnAsQ+gTzZiD7aA zsh4)+oE@UWZmD*v0qL(Mb|~h=ftJ!i#&P&NoJ+m|ug+I14kip$YG!Nd^%Ot*DRQ`f zP5nv)D%lE!A*yZ?v3M_*Oq1`7)^$w2l^Cg%4A+|P)4K?<(ciw9EXYCC{G6y0d!KSk z23&=YZwoBs%fQaamn@KquR9+X$bYZZM#-J!W-T~9ApAXw6_tKEev$>GO|(%mGm zdBLXk<*?b-*zRvtq~jRy4Xu&?2SXtK^_J}OXO__hBo&6mn5nN3l$F}DS0Wi>E71ju zO&lg(wN|nAU?jp->zceFT03Xd*m^)N!z3puP2V9VXZK=uj%_D)RNMT1Ri(wdWPh$S z641Jf%RsFh9PbtW>WHm~dkFmHEiaN#07+bXqgNEqn^-Z6Zuw8_&3g6KHqz-Z%M@)q zdL;T$Ml@r~%==7L6$gmS6_E}54S#Gn*Y{da0eYaMMCVkh(1rH1bIVz~ zNH2X2(8p=_l}P{NyAk^wk&;DqzIQ^KWVSceaP|D%1ll!&^Z*Y!+B3aU`{#@E@zaJ8M*=%>B*DL69-b&k!QnK>dy7OdYIE> z*C?`dwzAMqe(Tg%jbTIMj0wqs{W~_<@bcXbQ=LwST+jiiCLNsrIxg9-*MI~cy=!Tm z|LFUGfu&Kwl0Nt?SQvfhc3%!F&CZSqsgkg};iDm*Ld^<5BJ2A2rk1u0Z45|{`hJkC zsbq#V36ka5m_Sf9=EdD?^GeXSo}LDj{Ha}M8Ae0;a^UqY3~8bZbTJQ)?zO&x*z0ra ze~hL&=v-aRSFtw&=eRC*4a%nFE5Z8$#1isCiS1X}g%#?kw%gQv^DRPmi1)`JFUBac zQ;S{>*it2|JBfI?#T?hFm6S5sRwS2<@+Pd|O1o)?auFfNX(x(ogMa7Ko?{UFU}>ju zK*@#Y$6~)K>UNabKrEljR$F1gZ=1412+5xgCytj@JR?FWnv6<@&S}47JzWW~!4kOTqLaoDffWmo_Asu7B}0Im#wa=NV9*xE`hVADDI*@jaQz zVq@zFJ$|nV+f?wl1PA*+Fb=Xy&QIo3ZRF?Y;8>N_IRTasndsoqKQY$30cT!k8c zddAHQ5D5nd9WQH5CVVKt+2{L~rdN-Imw#aBitQ^wU{l(Pu6@smh{dl)ZN`AlP9eW5 z;L>Y3=zP_1vSRNER6lf^JUJ?gg&^It$WCiHyL2gN1kCI`kkUs`U76ALaVi*hwMept z6&NN<@{w@Rp(#ejB(V|QrN_s^x<9EH=@=!dJer#$jr$nnC zpY1YSNCl{EZE$6{ZKRDzv#_%v$qEn4>6cHY?q09{1C#DKQj@PY z9izB$Qzg+igvpc3`g$8oMURq6CCC@hIGs5ZWq6H;z8&wY>T8=G!q!9{p$7#yC7x;D zv$GH+l>wVo%Lzcrl;xPQG z$r8Ov;%pF_GnNf|$Zne7F`dd&M1@4}fQcU1Y}vccC3&av18eH1rx)!i@9zkSoAEnU zC@L|@!z8NadiwQ{FH>O;C6lG-KMvy{Gag1G=%V<}S~K;=txwn&Dw=SY4=Rphi=K|_ z3Jwx&=lcnq(b}mEaa9xy*`Zm|7fg_TuV3!#A%O@{o+d8$T!?3LiDjy8X0V|+=0zJS z1(bRH1LO6i{AE~pW~7jP%;z#PCc&&)92fwuhSq7#ptL-v-RI)994(N_M_wmuA57qm z@z}n4EborqYK*G0e*~>2{!*_ywL(RiwQ)Qf_KNtDT6_oCq_?(KJ9e@-AWzXww334&QdI96yLO^jHwvGIgYhz}vFNc=4AX(Ge|T6L>I54+K_E!Nig zYooII&T6N>@Y27o5Z|~*^aJ3S($B8O9(Tj9K8dzeJwPe+=j4-^dGu z2Q9vRLxU-lmU)Gy44C}$#m+8sc?Z?vQGdV2 z{Pi)lOlt?Lw4AudcY`5)houdr##M_E9lJ+~ygbfrR^Iv@-%@a6#L|LP>K`DJ&Fhp)qiaz~G?bDHXHlY3U&}$KW}BtflJQS* z!}sj%CXMtgFAatioCgdID|@XJD%bj~G1f@T!@9yn8w?fQgi4N45!fO$gl1xEt_-BbGf#z@n{0;Yj=3v?Ya8B^6n)WK=GL&EeMQ zo_Ss$!0C=^+5;LZ!8Oj|e&8^n)oqv@Ah8vulA39z5??DWXcq$&%f7Y^#PNrMsHA6R#qr>B9#LSDJ&nFK?2Esm2rT9NE z+4C|rE07Tn?6|fcC+74A6>it?t=upt9aL;MJmcICE3V5n>n$(q}HT1{G}28A9p0+A|O1u164&5se?pOy&m)|;KIflaFAU& zdZta%kW3YD>up%9B~zAaf)#JQiTbRRN^cxbDP4J%p0U+^jPqB3l$Kn0%L{7m z@fTgC=#x*X0k@4u2=8_g}jzwgcp-*`<;rGs## zrJ6p-;?un>5yV{Fc4vl48|ch`a}dlJs2ocda-ND&%_iFL;VX+&pgu8?PmgY_WxntG zj`m#l@#Ky!M`iAj_zzkOdwZizRtK%Xr&TiVwK99CHa|r?s6dwF4PzoEwxMw?qMvMh`A*uUxJ4BW_%N*%&D_2wJqf{r8pYI2n?Dl*NTxQu#kkNRE zf7dj1k-iQF6!3npOh~VNReP&snyQ@(SR(z!(Gg!0Y(0kQ-7b^{wTD z?xxA3RM+v3z^}~5h73+1*Q$tC;73A}~B%dAl_Op~p3l$G&vu;B?+ z2>{uMn#HY=EB7LNnd~UMVoEPK8}7;|bp?9ljNW}wQQ^wlk4%#t>}^o|rZ1x5gAwZN zrF=?3X}nV(;k;<4&`lgr@8f!opkx@O>t5`a5_9|`a`LrYU$Z_D4j@@=OnmQh*|4@S zeU_$6Bfoz!dP|4=sQwpNu9guH#$FZoi@x+A@sp(b2zr{P6T(DY^w-gY;rl<=D>PEv z&h@;xG{2BtPj^V&q4Y9fXV+4UFSz&#;Ni54N;KAACv<%(Zjm}JOb__qG&1gy*QkDk zo2NvM>0<7>xcYpUi%jctc|Nx6{)JJHs8w71ls91Ly{Z2&b-EPo1N8Mj>Mtkv7=?WO zzF|^I_z~+R@qb5`b)g&$lzIMyp;fRom1}R;)1jjP(Z1#aQ3Bz<`oeh*)J?kh16Yz% zC!ID_C;e7(`G}>;l@F{zqqhd=>AB9JQh~KN-kgs*Slx_+tFf8+-frugBuOboVs}mq z_L{OHiKc$&QO^Bc{Wf?ZHf2(kFP*V71ZhU9ReAYuG~&QI@ceY;6ymH0th6!p^>iaJ zp3_bfUCy1a4z2B)lF>n-)YWY(O+?Q>8ed_7KAYLwgPBedb@xuWaAZLG1r@D4gPd{O z_ZUodR9lH<*#PMEeFXZwX{7JVcdzS!!$KrZZ&--wEgfvmT1HqyL6vjk@jMEZ+>HDbz#61p5MhJ#rP^I3C)})UZFAwE)tP!w_{&AyUP#6; zVVWyfNu3lOPei6KIQ#3Lrg=@v60#wLIE5(yf>5s)Q}MA87iYjqLiPCQG!Z{z3`u~8 zpiu+&lP75-=W^(Q8+rG4A@8niQAl3`p;P$}cVtz+&ewYgg5sQ@##z9&;KtecIFk$E zor5`{BT>)IuEd1sEy;G8r$@elp<~baoEmFyJ8(<5b%ITyg9p&5>DIA+!=M}1G^N=K zOM}puZZz&z)c?xGIPhK5lZ1inNsBg6fd^oz;K`GPk3BPHA#EL3lA2OJcAsV=hz(Aw z2L(?)rJDN=r-XZEnP_FZY>v(-s3Owo6Bo9qUrrh*l0To~cB0H|$n+$8<&2s?x@uA! zRQh+-E5nzPO)e;oI%DuEoUtB*&)bVy`w-E!~B+j^;XBHSQ z<$8aY)y#EuS?3`wNIPB?5lUi)R{7jeSTvv&;{?v?cn!w@J_BhmqyWK<8&<4{Go3_9 za5w{hSN)l}-ge~SCT&ixBZdCTzSOzdzNu(2*<4_V16M9PTkhsws^yPULW9&W^T>S0&C^SSAru7>z?CJVK_(V_tkA*VK)t|FzkOF7Fwzttyn=ylD=*rHX%T0h ztX`YK=RIRe0O`liO3DY|A;pcY&wX;3&AVG*L|nlM_5aBk(rMyfN^dSj%3k@J$dgVz zo%PiE7`Ng6+lyiAEPY-W;nXk>9TE}tLgSFzW!|(XFUe#bthwMG%a#Zx!U5Jm^5aGK zi$YeEDDqy^ULn zgsq^|%4Ju>p6RTB`e($LaEx-^8|=9W$oEAF5;zuJJBI5Yva%o_!K*F#H8YMDkbi_D z^DdQHDtW{lNEgNBJ+u18R+e^0l@qKRdlDa@*pKUbaZ`czR{vV1}?_yYrZ+o`1Av z)!bC5p!$jrt;`+D_Ps2N?08~ztmMFO$^k{63JX3SX;6rOU12WS*1EI7mv33E=D`LH z`=(YzR5QEAm?av~fbzOa5@l;YVvp=x5o$qoN!igYY!T7I%x#2owM+r~DtZikJ0JEg z{WvYlDxqGslCl_|Ze*<}DVBx7>qTUXGZ$jdiEPD(Z?-rzfWcj(oW4U>-$QpO=+mm} z#BC-{t=jbo-`7r z2=k;PlLby5KZ&@<-}79uowYpOFALxU5pVVDq#ouj4`xC>-kVq!CZ-I<+F!6&Qo9v= zc>O*3Hfq0Aaf`>E>Yj#hocmrspv&;k#G7?MbP>G-5@`;4mw->wFB3z5E7DF2h0GG_ z7@OA*4U-Me=*LAf!)oqv@Fw}O)k$&s&EgaL~VR$ws0>$Tk0`)H=F2CiGxzqajr9J(*;>X1`db%)2= z?#w$-4(P=f0E&v4wnPW!3aFwGNW}d|VqI3!IQ%YsN5R{#5u9JD9@rSznRfb#SbX<^ z0}D2vhH%I42vM5xTU9M9QAwB80`YgcpXjdW`}lOQQ8}>tS>S>$mFvGaI@L7fRC4iP zy4monQcu>yVJ>B<3S^@_RfU_dQjWg2r>sP?O7qH-j+G@%H_Ur?ko=ZTK0&yk zi;}#TdTH@e0r~)wYIuIae@+o6W*X7h&&+KHM@auK+!WR%vI=6s{|pX+tjaP3v=&oW zAb2PBe7=bJG&3&z$&-k`r~fyucbj-xoE4FU0i~>$H^;aMZJSzl=4h^E>%3B`t^5(E zGM~Q=m2<*ZmQhFV{lOyz@_Rs^WP#ar$5t(Uao1_JSq$jn)|Z28XrIEWO&n8O5${uwxK!B&VA0x&7)`Mm1AF6f1@F`>U|k#N4hvlHYh z%0dszh1QudpgIW~)Ss^fSx`Bkd%2|wwGX8c?U%8ursMPM_;?($#gpLt*#p3r3Jcp0?aT6i z{k<5phtBwGYT;3@6|FZgE}k`RkeiBqS+URS=%cp)!XHTk=!B!Ve!RyfY`IaTW$>U? zYoNANM_AKW1bwpD8MgL}~$PT?HT#S4cuuc6YJBprLU3M7f+~7*`fCYa30NiVo zQe#kN@h$xhRV*L6JN@3&2;~%zDvVlP+@TO6g#7!D?OOe+bZ{MaNI=B)FM9WpOTL=7 zkY8xfA03Oqx8s%JW&7SMxyTwW&ic3LhQEs@apZ=$oG>Eg*N6Txkm`AAK;*%5XGlsr zI0pTxFtaQrCk5f3&zSW;M~p~gyB04hmWIajr#tpJ>+VfP)aG1x$f>U$-{r4$~ww`gZnzvPRVFBXN z6qhwm?+||?0rvhQ2igW%TiS3u|3E-Zb$FP+G3&tFOS5a;UMNzD+`P4%L%qoR+9-d) zqNJY>Rx8$R;Q+MVt?tI-{w`nx(D%tF@vu=Zh*InQH-b0*cEwyF0u=GI^fuP(p@mdpO7&j%2sEY z8g|{=>YlG8cz933D69_YtR4a$r;7Kuk7|i~mOl&noImKR29m<)nRu4z0Z+;gX!UZu za?(txqWw8meH^HM@ZY(j+9to*wo#!8_I?d;78((=S$XF|S`FKxM7zy4>y0AZ10100 z<1`%`(M6vRt6H~=-k_y*y0RZJ*LRn1_F|U+s#jMMj^~bZ7hLaxAs%B6o{9&Nxg|To zZJt>Q6>v|rdypwDU8w$n`7nE0>9@d{)Mw_K2~JP-oXzvZO#p>^z+z>%6_l+FzCgwU zMrXm&4G#7u89d)zEJ6~0v9JdvDdPHCwpuC2ON}ucWKio=3)W7v7$kqK-6c(5j!m4J zj}?ipH6a?1ov)7PYYf898tG7{<7qFhW?gi6YlWmwp` z%!i=$HZtGJylx+Kb>NOfhnRS+p+%_@6=FFgbrcx$_xuamlp7ZtjG0~-QDJkoWgM{| z&|n_-t>7532Wuv;LGpW2H9h9Gb87|$&1|v^`*gj?`8%Q?2C-Bm^!&?WS>iP{MkBo%#4KcoY;~}D@vO= z+76E|nbm^DG6wVU?tPY2+oiT--m|gM$AEmFm|Iz{ij%6+UA^1!Dow_o0!#{D{Dvgb z;rfbscM^LOeWgrtnQ}`k5vi+iw`;IW;5db;SXg*63TZ4llK?R)6f^(fO20*+r9v=t z1eS!L6&GkIwv;8>ithq8)XP}LgY+9W@}qVYI;?4S!J|O-m&g@KB^x77g#r#+{ldwrZeT8|ipcr0vKP^0Duw^R z^yQ=~(+c6BlI>2t?(Dj)ZX!%*f>WI)tyN59N=hM+eiNhUu_`h>q^KTCCkVl2=R**7G8&UO`hZ8ZRml2+VX)t^(p_%}Y@?fAqL zz6*)D%fow~#H3cp$DHd1kHw^~ORLkRbC*l>%sRI1q+Yk5;E>h07;kFz>DLPD0~#q@m3+iMoFTEUft=)Sq!bx~OnlGL**fx|n9Xp-&TkuAE}75`0W23?jK z*c}k3?1=#SoUSHNV;^004br#(H zKc&Lbiq3)cIa$0J!G`8W&@(-+HYQ`6vxm*mjUa$+i5m!i9z#2}lYz!QpzQ1y3F6n_ zFmN^?K8GEV;{~x4+{-I-NW+_I!I4N(pb{Az+8Md+H-YG-m#miRlOqNwsd!~Yz{7mc z4Lx5%0#qH}^$<(WQb7Ha{4bPt)Xbf=I5FPjF@i4h)eW!}awTkygaM5Ai5 zU#fZ1Jrla?49wmY(Pjzrw( zbIXJ3zic1Zc}zY>i`Wbjv5bTC)q3z89{th?kSkOKyvrh0j_ZR&-m( znYBuTC=5yP$v38`gM!(6PnsrvhEvU$`1TyOQV*-`&ft&x-4sC^@{j?Tx=ql(rMhc` zd{VO*_U9lt{IL(ScDg3`Y~?$Oe@@Ro6`kU57imqCR}AUHh2|Cq^@C3-5nxHa37orH zGo-^OKhvG?zemAG(dnm7r0RY>1-dOi)@CKNu8BaoXX(dbzJX1&0xU|f{Z{RHNdWRd zGOh63nroT&3XI)!ANAa+-=?#XkUz;B`Q&OIr)THkS-X`OrR!)6wfkMQmkB}D9p+3mQ}l=L47!o8h}q(gwW>Ya7RV${h$q;X-#NDQ zECSO!$#)f@fW_3AG)-wiix@9LNY?Wc8Zm9&4mOS2LeR_({+bSlw%|UK<4aF^>y|HA zkvyaje#lUo`z3D6OqlQn*OIBLV7adWh`tvs zEe$VLF*-MeRPs{?8>&xOS63JDZvJU1XDrS8SU&#!lrXF%GHGM`c1muwfhx2%Eg9fJ zsOVC1J%dO~EkB3^piIiHoq=dSegT?0F~`|NuY=0B)=sFK{(;f0x@G_Cf%sJ-zuItG z%z7mBxqJ9iW*hep%nF~*WzjtDQargmaKyhQ_MWG3^TW1pt&bC$JM^kBG3gqrw2qZr z048YIXL1D;g--x{qgpj$n<0|k%(cj${Wsvs-=1uR|GahM-b61|qNWIGI*nALQ;43v-X zmjRrK0GiO84=0m-vyEb=|70TPf6|KoEQ}n|>P>bGKj!zRbnX6+1KVY0x-lnD@I2GN zaPCjgg)Iiy?T$~NpA`T%B0~YsC~cKlMYt+6p)BdOHk2-kPU@R%BWM-unyv%Fd7st3 zLuc%aig^n4T2QDJ0KDqk0Z8IPm$KZ7+?pj`lBr~UJ1@pR$)<;&E6e1jQ-{Gzr?=dG zx8`;cz>tH1Mnpy9+Ob>BjJzr51x)yD@HPf1SaAisQ&aKm(JqU#R1sO%CuqASc>Q5d zld{HXv+2dTt%#CD25IT$cFXj`BVKK93(cZnFKVtfD_PcFDfa`};p3;IK}%x^o@ip_ zeUY|poM+0&+cnLVbLg+No<5Ma=0dbet4l2xClhuxmJtQ_n0)3DNVFBZJ>`{U<8s@p z@aLt6FNR~sX<~A!M&@&eX{B_CD^160x1W;Cv2%+*XVTk=g9#HIIL`f@5*vApCOZQE zf#I}j6D)*awbkKOX*UE-v3UvY1;0-(Xo4-Yo}7z!fj& zt!A)w~}=I zqi=$~-7@gwqizH?T5PS-Ib+{zkbu2IqKUcL&FdxWT&&xspH(cjO5@Z2E%kE5B#5{G;hlK#?~~#+&oGqzJj{!Ke#jpjSH#+eTHPJ6bFZSC zhgGX}>2)&@-qa5)Y<^S6_y>k!SU>cs@Ml(FrcIESG;ZxEP= zBjJ4rPx?~8XjT1INHNw_+dHXH4zU;v&qXdIy=zRGwrcG3CaqGzU0xa&i-Je+5*)@zcyv+(HTd?|MgmZHew$B!sagtL?2>FRdv;~u? zHbh#DP3E-(GLe)orSl@>8zxkWJ(>CFS6;YB(pKqW@iUc)G%*f_T1Bj} zW+*_}-a(HN^dHzCQR#?Z`o>-sD;s(3;}~;H?FCfo8ZYK|_B7%#(mJyK%)^v^7R@UD zoYtF}gxY#1=rrIRxc!Gk(DnE7^&sjkyo+p$AMuvXIPvM7OyC<*nYJIlYf~&IO^nA_ zcNNxo04CxCoeF#9%C6qW$L0LbWBBoBHwFK(_9k4($U6$Ed)+w}d=gTFYRA0D-b@Nv z=QO0O(U&R-4PWSZ%^3hgV_(lR{cJ2I?Nl#~Ye35n-`Vsi^_N62x6#yi80wG2X>ezd z2!-(EqTLg{;69Lx$}R0SGQ5!m%m9eAP{skd=Wth?O0F1Z3(QF!{m%s=_kz{GB!a85l^^mW*MAya#W{~ zsN#*l(+NuYWsbWy)3DY^oDPO|>9e7difj|STu{)$%BVrO6N>&}fKg2i42v`4g)Y_N zqw`m;AaCGZ2-O!tlCpx6l~7IP|1b95GAOQYi`vD5ySux)y9Jk^jk~)O+=IIY3GUuF z!GgQHOM<(TT$1;^NzPa2R()0X@2%obS2tCg-Rw2jnsbctU_LBUJc8Tef;u^Nup!5* zWA6npgF{8zENU#u?y2s2=57{{$luC+Es#nei)LO~I=XRTD;v#^VZc#{R7ZEkZ?9f53eZ|M>E+tLy^kIWv*q*~o`52rkHFxxx zpl5xAf%lFA0z{b+?w{_}f86B%;|0LABSqHsloR^g2=LzrUgW1Q3E#-ucP0)ikxpM^ zNXe*8;pXn_448Tj-ZU-_u9ULPMxcjr5}D4Z7LKo(V3HI2RF$d;e^WCw1lO>Bv}}eR zLAUBn#9=JDl5xv!1g1{k??_WSN+_UBpfKg2s!GC2N;s|1aX3aCz48I^^-%EelkziQ zI7N1HM#c?cw2gH!Y6k(dy=J?{%Ua+hwpdDS5%@_Ggu^&vMKWN0q1&r8yCs}q29&sH z(5DZMFnTD-#c=8M;=*hTaU2L$ey%16JxgKMEu11u=vURqm#Z%IOUAT{f~{LeKsfIf zaSsKz_ohS)GJbJX3 zf3By?G7(9r94S9%g8#uG{!>o_jMVsQw!g5FnW9u?`i7X6L84J$fwiG`*abnNi${HQ zYiCZ=iXmNs{xi@k(1 z{W~XA+!h@;L9NBZLtEv{J|Xii!Jwh;vPJ3hac=LD&`h_^%*Yico$v__cV#GzP57&l zc3R*;2xQZ+Iuz%23z@dsHm4xATrAmWkwjz^j_*{2iE-AOVNM_hW=xpfiG)TH@`kgg zgju<}rCIZsLHjPLB&whVZ$_Zulh|kXVh>n+E&&-|j6SU;Zar04qNARYVQC6-D52hm z&5AK-Iv-vR_+S7T?7z}0E(UwlXNaRtfXLGw;=@>*%w&L`t9fLjA`oUzQ_us#=lk)hg`_>jmMo{y-C?N6rA9cv%zlm8`nUb zcCykASFUnEuqAiTEQWqKjrNI1xJKS0&tr$1%AKtlPgdvEv&4dv4?PXAroAe#|j8bc$tTkKH55h02!WDtfmCxV2MMaF1e2JKIfR2$~~=7T-UIJGL-iey?iuCnZ{ z<5*KVH~3D(IFjXUs>q7@DOElkvm;cc^3fb6^QtsWZ_9WQaue|`Ky*zkltyrpEZcKW zdVtaMyRQC?^TfBx0DcV`NdJ(7j`u4Kyx6P8mr;hiQuKZU5Bb;%LQihNqpuh1YQ9@H zT@LJLP1n4gKWQ>hj6OJ#4cxw5pZPDlO#h$SbGCxSj$= zXxUA3MI&(xxuPgLvXwUE1+i2o65BlCuoW0ea?x+_yDVNXHXoLYt_M-Tk&YwC+%cWB zTI6K8aJ_C;b#Lwcj#w5C!{{u^;28>x;moT4(5LkijBsgvIUKK0j&V844GAz7Vv5oy zP{rPMjaBf3ANX@oYxrPTIajn8v8L%6!?449|2~Zca{{crj7iUUk-?9hzqpERP zR$>{{dBDdo6aMGD6>kC*i_zxF68XRnS}SQRV{tvaf2VNEd~ln+eC)LKWr zOuNhrZ-2=~(-vw>Kb33*thq^Dv`r(Wup)v|QynGBbv2}7vGQ!I`2s7n?1={hEm(lD z^H~J@R{}{p^SC78=jwpF-n$^^*hkp+I-H^$X6|Y zOY#qK{qwI_hN(L1*Ki0(BHxd@%Liv#hK$C zwPA`Ji%#UtiJlIE)Db(kINEF7X+S^-$06`e#}j*+nkKHhE^M#_u+3?|CN%KljNo`+ zl2fH-^bf}LOzH+lwQr(y_ru1EVB{^XvgtxalLMWzxKHOKCZ_#IbV8HILWk7OnAyZC zB~?GFa*Dh9MLS%e>>{l2qrtg5D2JAYQY3BBtbEeKWR$a9!n&S!|aqM~Gr9N;5usyR#$6~{>44+nFH?VHmAGG>}b(He-GTxijg zP(j0+mKhreMIn9I9TQI`h+*5dyU^1_ zWh4Wi?vsPvk&Lw4Jz57)u0OZCd=J||=AQ>!*!_%77MQrbU;M!qL3VTbMw zan%#j&+36?;d!|`*f5pe0dm(-h`%fMHLizaAbktiBC`H3_QFDcW%CVZ%r1FIc+mLXD-Cw#-|YR_-j^GrPQ8oGLf{bM?1H}W5k_j zo)%n^D{F!*Fh8@LN@gN-a9S--VkF_?k7*yhhI4yHFwwcmYue$8XsN4yn##VvRgJMy zXAZtn_dH1DVw(Vf9AzI%b0pK%Jv6ODDLX08_yS~9rQ-GGEf3~@Aeh;R! zUmx4|x2%^U)+gkM-YQ(+b*hN5Nz*>~)c1h2!l({cKgPvwggjEc>vkEY8YAm!&oPq1 z9DiBB5#w=0&Y8`>8V+5ZCJ!*!LmG!^z)RaFrkzZ7L}w?r2IYE`)9pA~)8u*T9qTcg z5OrH;|JgD5tUjn!jAlj4Y`u-k<=thfoO)u zWrz$b*gN=8KDz6pNn&cPIjE|vIM7-A?v}TLD!~|Q7PQLaQPLciea`qOXl5Y=hkG`R zJ@y9(P|JrAtl-saX|ux=+lVafQ`k`bn!g@vF+V#b`Sv6j)98G~V*W`61am$cg@UB+ zwp0G=$B8ObUZukSVo8{+=AJJ{kmyV53mDCk#l@7>(V&QA=Pti@a(Y`ngxHaqP*C8K z1qN-3NE2ql*LFmp)!QPfzIpF?+NllNAErMAqcVCNSA?W`Z&SxgU$!VXsHLgk?7m9q%Vf4k4jyeWqy{EoDp5?9V6n^4rAh4;%BovS zyc_is_{WE4G&W}^$OO-RB~GGsuQDo1lZ`j1wRP8gfqg#m^)#Q!yscUkTN~aOMyCKd zAR892@P?7inm%lE#9AC8`LQ-zh3>!Ky_^l4P5xLbUw}o}Kz6rdQfDJK=wP(ASe&+Vl00py`h| ziP8KzO_X~_?tu86K1M0YhbFB|sx8Wil? zc3qWk;4V?h4raFQg+=vAhA!*G0a&@BJ5d;S`@&@mPtjHMcp+**75`z^{qrWa?0UtU_!!NDf*>}* zMkHMDaUS`l>$oT)Q?bfj?8)sf(z&pcqb{;vV%booANmcsOPt&00j7! zcqC%RGX9x)$vCtwP9LF~7zp2U${;5(WRA_kfDnd7^^AJ8HC(wN=3m0;xVSo{!f0A! zgUFdgn`4jjm>)%sPejlxBvzAv<1A<5I`t$G^k=z*5o(y>Iwnn?QM^OWL+nNcRam1m zEAAo19ted8(OU)B1QMlNN{4-+thr1x^ynswn-T*)$sRRbZUCo|93UkXjv`3x3MN#@ zRqz*mQWXZ2k1%aJlYH$6f(U={i01#Jo}}uPGa7o02`-EpdS=a-RH%RxLrVS!Jg<1H z_bQ64nplEPk%$vTzNLW>D#uAdAu#zE_!A^>$!PjJZ&i)6VRPA@_Ta`We6y|~* zx?#7(k^Jnu>Zg44f4Zv|1_TCf2s?RBg-ULI0m@1R<~n3=H7UoPJ?_3A9DY0Ter4I- zxZHNU2A(~(dh7k4aHjC((d)q_N=8KKeKNP6SJ;M@Q8jtUU-`n^7U}N5+eUvBSB&0| z2I`?YSxNC{{U;oV)FFZ#CK46I;87@GQsG^J-}7HDdAWg0?{!0YeLQ#J&g&-0CG=Q4 z@{fSN3V+dbte;^(OLXBLt0n3qb)2?7ri>NS{|9d5)ajvDlFVWkC$;D}Xp7?wS!p z9C0%#Z?C(I@Kz4YD2niG3G!)2ylijcE^8W{W*$@s>=FF99wQB9#+{REcp%dP$kN__ zD$9hSwwCsqbaycNtR7Sjowr4XjX+e8wd!HDH_cdOQOs@o{goq_3cJwgsj!y8N4P8Lhcv9@Y3Gjan>8G<_x(Z zrOj7e^Rnp(hS4x zb(^A+T)1;_~5My33B<^{Q*y}09we+$Ip9y94Be(ZiG`MwQM^X~e!%aPU}RnD35Uj$CP78KAi`XzX7=c3)LV}Tfj^*F(Mvr*ACnTwF#J}F!}VtylR-!U0j z_;*Q7nM}ep4}&s`_SweE=#Jq7?yg>muhfiHMGF4#?}Oyrz;p$4k|Ul{e1?Yl3~6}j zQ$h$f{v~`jaRMNeDSZ7C-1K=dM40V>#%9rusi6~D7VmNf zK-$fyeYrBplf}bzls*L@D91B|Y`FVLlB@)&_s$pL>15Uq$m%5i)nhS1`Y5P@j7@2Y ze++ZTE4@bZ4t01Ofuv`o;n*@67R8P10Ndpk$Qtl>Ui9ZJY|5{lTZ()0K>97&W$Ae> z=c=>c)3~Xg&99e1Ll8)%i>h>q17g`RrTUbU3*j}VI-*(=YSn+r?91i}unokj&#RKY z$*tU^z_=JU2Ur_W|C&?rZ?T*B%h2#@O)SzJBJB&T~+b!it zL~by9UxQ=%jL_iihvS>|zZY?%1dE^A?}aFRwDqr)28y zU1}E!9-whMiJ3NzEGwyi_fp-Q|4=+=8P9qx(!O*AL2gR zA>gSss3^G&9?2Y#D8#;SeltmNJ3r{tPG}g7DRj*??N@IJ)$@VI*I)}>m>Vy}GNPln zamrpqM#PlElt7-k-)nUUlrO7q$dBfpzao>aO(kL-tgakHFUOLUFO z->wfu@V|i9X9f`C!WlI@;u?p^Cg!tWg^Drf-J5zEHPkU!*nVBd-O@VgC^zKqFb{*( zUzYUK+UiNYjnDbFNM_^H_*vq-fY-hQ1(Rj^(rKOZ%itQlyiBh^c-rWIRs9RJH}mh# zD`&y(;}*JhVsPV4!UN~+zC7kSeVdT-qUWbji-2|8eP0Fg0zIcW1oVRZ+O3vUXRjnO z1fCQ@Z=JK6?YaVE93E(EZ5Z_X3U88Y*@c&*td>=q zJu+W?G>p=!Us&P`D1aFoDr8Jh>!x6I@Js#2u@lB*G_cZ$rF2pP(2gu;Tm3pJPD24p zfaAy>EmleL@Jl{Ylx#6`#EfZ_F}vD{*7~R&?upHbV?HW5R2Q44EhMy>ZK=0WS~GiT zv8jIanhC&2sNsj2TfZ>uX~!|`MJp+17`H^g?%kNf^6*J*VLOl+=Jut$c9ykizF!8a zw3%)8(lb!q=?jr-ZWWAhG(;2cre`6-at40B=jG3T%vugY>>c+LY z&kJ&uUxLUXPS>ZFa@FUMr^fMeatNRT@zd;}Jfbieatwmhz4zpfA&z(7jakWuQW@ny z?jScojZ`t=QoTUUB{7x8skZ|I@g)f+rw!dTGPU{CPR3eX>2gOr?t-cUJ)A^xyWk9J zJ3XayDL=i9NU?k~U zy;u~-+@GtAp!n;4wo5KB2e4nsjrzh@d(-N!4qBYQjf$t_?|)(q%g>9>8RLVGSV8Rl zk}%oJx-+reOx2=yTsqAc9r&3`yxs)-e6x5&_e>*h4SEPI7Ry`#m(R_Bh-N+izvu&< z02|#3l7lVmlLBilI!Nx+4gUm9>zWQun1cy1Ww=UoAlv)Y?54^YJeG-3?-w1TYA3wbj6RtPSwYJgg< zH@ATz_F=9i3d%;YrFW8T_L3opiKdc&==?rMnQdaJo)b#*+u(6+UpFMy+>JmoUvR4c z^gi@(lEXsb<5LfJN8|~c&@Br=FpZVf4TSLZs%KIWY8zt7B8_+PZLq&ERTzkpg@T?U z<4x6imKEHJ#7mCA3dS@ks8yk$ZUIw&+6tl&v;&VsnbvE7BhgNA01q7xjz=M*7+<=k zMC>`Ggs|gjYW-T@-4a`nh&|8qDoMN<*wp2OMI4|G+KLoMw88*daY)}o!8p85ej)Fc z(cPhaW?9Gb-eg^pzq9{MO>VV^HWdIy56h-vNYdjZd3lyXj1l zE(LEbm%K4LE)5&*z!E7D1@a14_UHKl?O$Z(xP)+BbhHloy?=4FV@kEiz#V#zrh8z2 z6I@RrC#Kn!@4ybe;hfl7IK{V_Lg9}n0^NuDc=D55V3JWj;(wpw+a_*&5h`~jXV9OD|e^ggxmqG%6Y}r1d^(U z8>Irq=nl_-coMvLuhng^Gg6tpl@Wpz@v!Gd`D6HEEiI7q)zQ#tJtM4zKC+2d+%56@ zAP#hAnicJKgJkH$oM4o6{YlMzt*Qm2G^$5Q{O5uQsf6~*yZSNDe&BT6%lzo#l4va< z8v-nwSj{rP{9v5rHM&GFLl z*edT7;f>zT+WIvcqsx5~_p-h~1o`&>pxzDrh*`{l2r(f8~XUNt8eC((cn z4z<<6q0wB`^EmitftgiPjoM?2Vjd#ybmDWmFbZ3tuy?Z5Cv{2Rh%5cN0=laSd;S^SV<-}yZ4$Wr%-TuXXO!Ft~( z^%Xvia;GcmR_uvuI`Yt&^(xhP2oxiDya~BEsbm-{E0i4_Wf*|p7tadg(mQ#b#ak*A z`Q7#Ac3xb~D0H@S>%=^bdV|4&`GakAttdC%e@;LgU7Rq7<78kfUkrINK^MttZ=83__;PMz@5Gh2|mA2xhw$=i6Cetqg3?VzP z(R2xpL)Zgfiz?z8yPrJMML;D|BS6Dk_h~N(4%qJK2nsz%SG!F={Sow+GxJ&HAvzQTBPMAM`*&1U3U=Ink&`~J$VcUT{h&Xqw91@vwNjNrz9fPLpu z<4jO)^UhF$B~S{D+Bt<|gs9E&&AZ!5p7eR#*FI0(ZTnmkvf$i!u3vQfY}QiQBEPun zuKGu|XL92oAhy-D+x1=`#Tau$M4XNx#wm^yM0wkUBPkGI4LuL$IVMpDN^$)YBM5ke z~HXj71P>OQ=Nw zfz!LDdLKU;bbrR46iYcO*b!{Ww;5$=m$CFV6ikR4!(mL)MX61vq z*|Ew-47XJCOiu6@It?c$9ea+}So)ie%dUMepbK#7fj+4*Thv;wonr}7FHC*Rv|F09 z3kTH2zr@eKgg2@`?n;ua_{a73pnmPE+hLl$tJ=~ci+|I?jG^ymm8i(dUar`S{yThs zBbWVOpfAwp;g#+I+@9Z^0{WacPqaRQb1iNj=GSs&Vkt$id&A?U^oSxzcyom2=yZnt zJF)xPsBYOXNunJ3O~4@)~@%FOdHqZ8d7QMqndkfH~5+0z5MnkvJ`O^qty^C_u7ZpS!oFhVH7oo|soA2!AMqkeNa)Cg)D)_AKW0~UkcZJl=DauU?F?za3nY}_f3wKswT zunx$PHg%;9%J+f;)?azd{LaKD(uxg*dwxNFiNqw}2Ijh^u6*dVs{Z~DA=8fW7j0i(>nTOu%J+lfKE8eytyRLpPQHsBo38_?Fc8omzm zj6s_o(`g1h^hTEJxDk_jV9ON4qIfq7&=ZZ3>K5noM zC{23BgfIaxtWrNhS#c`OWyB`BySrpqh6ecS*?R;(;hmETlIrAgxBzI{gD;G7CcxGFH!ig)Dh zEw?ScjCzxui^4eCk_F9o#zO*c;=QKQ>spL$*~l84Up^n}xVhfD!wt;-xLV4ijiOW? zv7A$Pem3wn@JO)q=ao2Zwg-Th|Jmx zWK6tP6G^pQZw(+N8(+b2?lquEL{5_i$Xj=r-fYw>{-;YDybXJV`@ayG z&hMnON7W`*ovhEfe{P%NxB?$=@Toz^Z;k#h2Qk$#-m!-Q@BixrI73zm11;S597(7KQdDrIx<2`@Up$hdwpsDN3nt^i7y#9)ENec9Yue zsk@n)dwWCja#!1IRlUUV%sPx49nXQ+@tEZ8wy5Ri5exFzR^Luo35N6rL7F<&;&;w1 zJ)B(i8OE=Sco}w2^T#cN(=XCsowhx-SSp|1DuT@*qWvS|2S~J;>rDt!YNDhu!4h(FIsfyv+BdEutD4JT3TUrA&yY|3#7piv2Mm2#7uY?9Tf(5!+h7l2HSI~L zH=uoW=R5L?1}sSuzq3CmkL_01poZ~vl!W+FK0!p7pg9kTL?nGzN8p zVqDhdpp#77xvud4b@MK-#7V}kSnYr{&Dx)v({)eeB_$Lqm1w6anU&;alUTp(gdgUZ zC}HNkE^!1WX^{<|^=RIQK3g^$P;J3R##tlQdKD7M=Y*0v+?B-V>w4212R;z*?VcxvjL{tISWnCTN zNsPseb~7@=K;gjW%+RMkJAw3pH9+|?Lxb;!C;&wv^6=ho)56B0d&qJsy$Svf8$g!x z8uLJ;eM49JZxrwM;)lbn#{8UAB>zK1xp!HG>h6e!jPN=Vb(osM^NC@WFEo~-PK^gJ za-m!5#&HKc@W>}YE|e7BlEM=X7z*Z$dkS<_pP~)arxw)NS$B)VrTyWz7c>_yH&ozq z=*TG78rg5@D6vyk-_Y+dn@YuL+R;0ZL&hW2iTWV1crz5N5r}#+*w2jl(WfpNV@ptK zTV6M(uq}Bh4azB3v@&%M%3)LSwzG2Y+!;l#<3))@UWen5c5vC8*Ns4&fYwFna-aS`yt%Epi(7VnNbMmbN+s56Xy2p=8*kKdDD+PA58rcd50 zt6EAYNy4BD31@e4a1-x{|_ze54{}c^Ib0Mofk0-{eMz@79zZJZU+he`_f zOiKotJY(B3dNL+S@ie4b6Ni7WGk@SD;Rp!@BIbzRJVRWIhIvvpZn$Ff&k4V~2bQ6@ z=xzgs1*{XBj_7Qswl(Eqj0{AZ?|ljnh!n2- zOnFO&y%e$ca?^D6wR|J5h(OiSSPGxr#E~lH%#6J~aYmI&CN5?2`>*+Et16|u-MgcZ z>TF=WtuHB|y)DUVH&qyHk(MX8tX$p^!TZO?;K8@_T!Hu2wFyCcM_L0cza-iKcOAqP z@93a7*V`}u&1Njqn-!kiCrpZ9lwbJ3thCY_A~*w0sLfnFId}kj)PeM`@5L@l41_y2 zNXgJ7nS+ncC|>#MO{b+kd;i&#!DR)XU^ml*Bl(>^b(IKLu;OZkTk-*$Gh|BmA4PD5 z!#74_+jx^WJC46LBEDCB?Xh~jkSL2z69}VinX`G=mZP;-c3Q_@Y@?$RkoT4TZITN1 zBEa$)*G%J>pWAW1r5-AX0!_1RWuFc1SM1(3JzKYRy*T0Ep%&#a#vZyEI`ue0AXBM@ zvn-dAj~+?g0njR^VpEarW3oFvWD-7v;G_JgfgFaG z#2s8p3I^}(X#ui?QR)1Q=+*Cs_16LT{>{HU2Y9#TMaw-tDqzCPqE+V+C>iCP*^i3R=fnhFT zUvvURgrUru-T_u?VzlrrXp}aTeU0$Z3F|d}KC+m6EBM!_oYsDk8SUkVWDL?lvO(Qq zL#yOtAu2S(Wo6T|^La-KzDSJ$E4-*vYV109%i$2)jA#`>&_ErMrVR__RgycU5%!~N zggsQjFOE0n7nLiqkg7)!scp{-ZK;(Lia$UqPoLT}tLJjdK2ck6_k&pNn<$rl1U-<4)W4Syw7`6{luwkRI68Tn`Oy#G6nI)&S&USS`X6(1I_wcKJ3f7xuJCDx#;9NvA z8NYCL3;+Lz|G(Xh^u@6r$JpnufmN-W z6^e}!V@VyNZl^|MpQ9;IUZEpWNina`k$>%9+jrV`D9d-&JR_6*;=1A(z-%+}1>tRr z`9RAzbBpgw31*j942HZWq?tZ4#ql{^##hzSMQeDRtvA+Hv1KzWMi3 zzpnfMVL}83Hr(uymEVTbDQVFnDhC0+uK$PkS-7JYlFmyV!r65Dhm~XhB@g)>{1@O( z8Yd&mH=}trSX;WeS2$2-lLGpnz(}@5|6|Ka^Z=jT9*j>sfSLCDh4QiH50F-I=PPer zxjI=C1_rpWu`1gWm3-2za~3V+UyITFy!?O$7b&H-X7(}CFDd@7JJJC2X-G1X7;mj) zCF&9loeXETp9IZknAXFGBwZffhAOwqpr(Rlv4^ zQPJ;A%8eV_pUja)fQ4)ENn7*k8XD?t+M?sOpqAQNNb~4caja#yBe929sU#Innnz1& zAP9FiGPy?-G}D>)1L?Q6GK-O35BpGuL2MxAwoSQf!o^9X$CB#7D=b z#kjx_uaFyi_`YGIM~1JcZ8%I{?0#Y?A=Wh>N)G5q9u#O}>6KpI^+d}RS0HpK) z|HO3Ed&{ZG-%%Y?i&Ai9nMbTg1W1_<=r5kMu$JMV&CuVn>f--3IhgagY0u?7nM3M~ z;$10;!^561>KxT**<#GoIiGnk*-2gCFW8el6^%K?db{k&!v)aUfq+0~@S<#`GDJr+ z&d=vf`+#f5vI(o;G@aS05hU)S6n|;7l3O((Dnw(FXq%_~NnW}Oj|;zF&nn&;dqE1~ zd&$6$baP3Cx8kPXw_d-0zBZkT|4F&np5`Z?)LIX|}q zV;tR{Fb-)Zpglp2=nyMVX#NP;SkU`$H7;S6+-&!*>sCvo*+BhmI)MGY7^2u|Sjz3> zy&KEWyv{oeQq;CNrQX}VA0S&?|F)ykNh6M0^Q^kw{)z#kxA-7Mf(u+C+x zUvtF_e^Y@S@$`hTkj<8QEu|1{6^^**bUoLlH_DNK?igL#?p2I4>aPgcj~ljh?w@|@ zKQwsx2@YvMWa~QJ{#X0oopM5sq+)=uDJXw^yE=}Wmro$^`RBKo`DC6D;w>j-AbU}c!upX=t7}rwV*~d%`9W7je20*1aPbkmp)18xZjI$tM z%-@)G^|img>ir|nbJ}>#e@Sk?Q%uE-s-s3^Wg5&U`kW}F)9j4BL8bW z@?ui&o2CsOtDu4(6(|CCqjjQy)I%O>t~K3mB5k2CiPqtzEXV`qc%~@DqfUoec^jD= z)r(b{aQj#r?&Kb)l7)Q?K|ZiR#vP%=ZAhT%9zn|Y(t!O|ki zl2K0@D<5b;+BVr#*%b156Ui#Uo9CHL5s_IUl^6g9Yj!XK7;z)A5jl$ywv}F_W8*UR zImmkE(;bIR0)xw9qu*u<$MHPMqBn3b2uFJzUZLkiMt5MMFCNe%a7tp7Xw z_eJkqmX~5TK59TmassXXh+!(4rZTL*x%Ib z=(APihGNc)754kbqB4ua;=ver_fJVJ=IBJJEJJ^dPT;t#xxP-|jcaWFu=!v_P0kXV z6tGO~j!ja)JHB_a5|SFjDgtA<34NwnA{yBC2oY@RD+cB|Ka3!0UHit@~5htisDLhywqgV@a%049X-5bhjPEM+Uq#l# z>d%sTF%#)rWftBGxk&M@AQKEuZv`^F)^WEZdvbbbSq8?X0^2uD@U9(~u`zA~?dprb zf+gRcdw}Pe-3GX2hk_(ge2Kcwsrp9ebDxl#U3^nbn{RieSVa?72|{k^e0Z9NB%EXO z$B6s^L|F)EoeWS2i@_~_l&Vqt-kh~XAbcOeTfz%X(UnMq=AvD9TKx|A-%qO_ntKJg zraPmqqH)>$?8%oHCojUm!9gQ3K!;>zue~IF^_}A z5(~xl5f(q5gMAgNpu_q))-50EeTKjXn9u#66D=(<(E`eO3dDhC&T z$;CE^8yA#6mSm|%8+khXRT5|)51Vi-Bn&+y$28^)R_~K8H4ObOx2L9l0uU;DKM{%5 z^TVAmy^_ONyM@oFKLC(m-O(uNxlkc>Lt#^r1>KY)cvw^3wsX%b8hnG39jnZ}{~5Za z1|Ug>BTmfa>@EE74wo(G@r2$9q=d{H+!;tHnvxz^!{Rt<(2#}Gz`B8<_lwPVXgrLd z@S;P2-w8I~;XcpUNS?ICFCEf6+WNR@1pv;r)0j)D7#->u>X{iYO7W^(LJkL zQNVfO^+zZX=i5QF4@b1~yyyF@n+e{7*T?1O6Vn>yv|nMY^WE16|GS9Rakl%Pq_}it$(%2RXV0~4?7b!QR;@EfeHL(j+enjD77eqMVsYhKy(Xe;+dXerZ z57Bce$5vdexK%I0;31vKDuwMYeRHRnr`}Vc;-sj~ZDq!g-DE*y2%DZ0vOJv4XMOJtf$To!R=&L>CkRJz$AAB`k5D3gX0%{T z>TqWp-M1Gsz2<7RCM?37x0kQBMQam)Ym%ra!kxh)x(3 zJDgI`vl^~Lgpb;=?QcQ$Ol8W#)sa=v+^^*~hF0yLsO)AEiHn;7X)r_klQRYtRBueO zuF7fBMh z3PXu6ax=$g(yF5jcl+w*!O|npw(Ul<%Z8tGoY#A zqprg(gtuC(jnC^BT#~9t**jlk(tEBrca?L-mZw<7*17g^)mPul0V=ucw}S!1M0jTF za}6TjdX;Gu*H}dIC$+}y2%#)K`%yNH{0A$rjx`Bgtn7!E-uHd>4v@Rf+REJYy|Ro5 zOO?J;yv0vu=WV^*j@EDXjbnVL=mYMz(r_Ee)dMEi&TO5ges`A-GW|umaqU8|)R$?J zMblH*o1R;NywtXc_(TnUdQeN}GwS=?*QywD{4msZNOw)MUhqZDSX$x*-ZtG6fgb|P zF^5&ySBNXth9+kw;V!xxbv(syb-J)N``rN-LSQ55` zJv^K2H~`l`(Ra1xG%K#5oS0=9%W**(7VWbjeBvGBYC4460cJeqOt|<52_WBGm9EE> zanZqH&ax5;4IlTcDKHVhafkFzFEmwg+fkMYC6oU^J%wni^d z^bSvanhfbaP)v>!Yp}Ao!)2{hJ;l3!KTAvKakH|j_w<@-{gpy}!c;Aqaeib9;oaq6 zQ;EAmE6ZUX7+Q1p*F`>Jxm@1U(T4UBbqqJZ;?fBHyFGi_f2euJl{}vGAxBG zGEurwP=l?AQI?};cxuYlu#<*&b0mIR-596hHjguKj0S zZ>W0>sc2py-S6mW_SCi6JIevR5>Y(TKflp$5#1I!EgyXbxO#wU=bff75}P}?u?=Q9 z(_u`e|GHVaRkn>yg-O|4^n{oXJjOeeC@P&YKydIe;}HOtfU`=ep(hySOCSzpFBl5K zeM6YOjF8Ch_?5d$SpR|@7|X&!ALM96tWkmhy!v_aGN@wy##dMgM&=Ul$qwVvVsR)z zN#^=MeJCkEm>kn)q5U9>;n@ff_l!(j8xtUoig~p4t{SyO%WC%FuuG8{hurpx@G_AY z(($>wZ2l(WclZ2V0eBr{*t3m@HOEq3nS#@D#37p@zN!9~qsNntDwmO@7e{%p zE&%iCT5)fKC3E6yPXd_XI#LTLQcYC=ZX8%;YRHzH!Wa}Qr zkw-*@!LmDbH6Po0n8Bx%qi7eRS@Sxid9g&~3A_77ma=?eFdpW3({jc>rc37s#MYuB zU>DJZ!^yOBbvey~?x$Mn_xXR=a$s;i&K5DTH;PBRdhrT!T*QAGv33lieZqf6+!84f z474-Ie7qJ~5_4gn-+9w*7ew(0{_>@mF-4ay-sSo8S0q;9<{FHtUHq-b`I86ciFuX% zjeF!3OOg8-X0Nq#p&u*1Owu9G8@Uk^=F!k(S%_S58&!ndCB^QJQ_b5TJBXP{c|-sd zC2P|RNI!$T52mIPhW2aTvwL#Tj*CiYVD3K(0R)OM{mU{I-&sLUO?PDWzYl?`>|VY4 z?YUmoawD7*93dKi=({Gdi)cLo26TD_zyyucjTP0gwWN1#9TC@J?M=cH&3uPCF?I+4 z*hCMqRyM>9fVGNBv!9z64l3HO)DW1O%PPJ& zWl-g2P=Q7p7p@EXS1op1^h(JVvVp|5sDY%Nb|!8(DLm8W0@UsEVSIsGc3xD$Bv-|R zn%K~kR))^Glk_sQdCH>7a@#a^XmQZ}n8?hEgTzK}H?Pi_g(ua%QORxG0I>)@*|vrb zW_-G%Iur%bwU`(@uRIHXI) zZ;n#BfD`^lw{>2nhG$~)Y_Ga(geQIRV_5)0z$uc3MnJ6QBJuL=2(RBxHGx4VeAm2w zNgMSpMix<_@XrS{2cpA`Z=MGM0mzgW2wwf)MPy39P!)e_;K|V>@Bel%%r%qaAUp*- zSik>qwjSqi*%(Zj^;5?ojXia~-&!06ETkvl3hmCsS;*i1+1MEVRpiF0LiN8BD@c!c zbf;bZ5j)4?UU+lw$Q)2F@+~#~@a@SE3Je$Ll8#EEtF};mIZo$gu&O48O>lrbnne_O z%PT^~goiLM&y^g)ua86TD<<$y^I%PX-zIok z5*b)zQ1#Y~>CzU7h?XZlCLjqmag_|X%%N&Qa}GS+$3?AUZ$)kOb2K_CBI3t1bFV#l z+EuN6u6wRr!{eYsBe$_+7Y70RzuR)QUU=T(gZPkt((m=ft_QlMD1d_@NAaqEi2g() z`RTh^^=D#$I zGr*D86Gs2Zc)LalrK`viIT(xcdDeJ`to{Mg5<1eDo{!|eX_;+XcGYZFGQ%ibS4CG3 z%z?F&DydxuQfQTe^ZqAY$Yh~%NejbQzu;be5rKM+eg5=jN=T4VlU1{)KPZ;*ZIj+jf5bMt+fN%< zwZHS^yH1wg|JZS=9x`z!1vtT{!XPoKJTmYdsv z-SPgY&=Z>zm(l74Gf#dg?0~0$h&~1WHZa*<{hP&DeO;bMI*$ICnhI%X?Z;x1ZHXA+ z8RR^>aYi0`hqkz-{PKt_q-a&3Mj9f0k`9Npl1)A^L1H9bnOty!PlomVWM$mSJ89K# z;WL!W)Y_iPY1n>AF}O{JR=%g*NKpK%(+6c9oW3*s=#rymcM=S#QSkBOi_X?K7gUQ6 z;g@QQtIp${4X(7CbX-K7OL4;y(39akL(MM(v1uO(y)cu|7`7etpw>Uwo1Sy|NPJ!X zfoet04|+kS;wZBc_Bn-nU?IgfyRGHn>HxH>|J9D0g=t*rcJ$s*mq^#qAW``&A>@nHUf@Hw(FR98QGO(Z)x zML)V-yUaR2JSvNHuIk3SEtX_DY3$~Gx{Ce@F_%d%o zZ;CVir#&O5#Tz}g=9Xoe-Y7?v-%I$jwO??TrC*mdS6@-YUgNq{s_yu!DqVY=x(&6$ zd?bzzfo_^p13{21m8{XxVXJwKg|~@WUjD3RyPtH9W?U@pgk%&xMV^2AGUid;$yCC^ zhO>GpK=e&y#O!3dk+ck;trJnd7|uV-&NV;EBK;P09PN4gtSuoP#g!$JjtS^pB}KO* zoJg#g)7^Wb*|YE!?PD?|6KCB{c-xZQbf0v;?k!pnyEBd>8>0Wz--|ffh^x-r4SHi& z@#K|(<0Y>In}u3`(k3o{5S03S1QwfgG*7=l?wdogxWd{>SJbupvayh#k>2V6ya^ZH zji4>6U*>TG@!-pMMEYR{!}heVA?Pv&*98isGX}Ie(13)LbWnWGBe2p6SdS++RM%lH z+%-agbTLK&Sx;Dc5+2#zRq7^J_2RYK?ft0Hy$dN4d{jyt<7Ne=q;r;aN41JP+QGVcM|CavHaBLhr@qK=y-}>a_XOfmxjiB$vxBM;}8+%o^n4Rpepl)ds(6Os7## z!=Tq;%$U%~|8)TDAI>5~iNJj#S-nff(Kzx6o>GMkO=LZA!F`zMNdH*ArA7Np;0f zgvExxU0^x86}EgA)|Go2&X9R#hV*C=Njc^?ZCSJy6>m*U#0Z+-S{8)c`QR$_jEK=R z2!m4^nVbe5^-BC+GJX@YEnF{o-Fb@~MT`!l=wdR8<0bE5A zacXLuxjE6#`nQds=QMQB7}-LE*v;J2J}#c=n9`*;bI&*B4Y$=7&zB=RqKx*ogR+~5 zz|neU&d>bfZ)kF%Yj6*qBsRGbd4uWeOsB0=)6OL4*ey3U6rRpC1r6!hsp51WM&LjE z71?9_SH@>^JA+l3@wSaBKV9#??v>i%YnV)!4^w($Q(vNOBP52_a)))rn-7UBu=fUE z=MakEu^YAbHpP}e)O{9R(z^URw^F8m=<2)=%Qj;gN#VebeJ3QB(wJ2?G<-j@w9*q1 z=_b6D7y-O)>6!pct?^ZF;azFv2>gPJO|PN?Xa{BjQ0vEKIlKH5L&2*CGMuR%=X|<{ zYEr3jR+j8k{aBagUEpQ6yn)!q;%EAId~rmtLd>Rgz!waM-Cr zkjAc1=9q72xpEl&fVIyI12)$os#+(SFLV*{uitJ9O@i(nhkj_9u_}hs^{;#2zDbTF zcrDPb-mP?hiXsv!egv?2*GxeeHGocZ{WD~>?fFtW1A}j7)ZgaBYnR-1zR%P}%O*6Y z1xg^*=NRyug%W=Y@x8oMI|!~CNlTWwZPKw4 zUusY0JHm;goKmK~RTb69(lgRW%6MS$_x|FuLASk7jEwfsGL^$K6|Xx{)|WhVa;M)< zNKV~fG=$c<$oF7Ua%a+Yu;Dh%ZSPWemKy0=5ib`pW^@PB=#Ti1TRd+J)hHXI4}cd` zScHW~EqX!>yIh(lAZ4$Dnf7_UK!w!E{=2<(wz9aLk4y6^L}{TbH>x#B8b1K@@7~o**A9Rc2liHXW<4 z)W^23fTPa5W1c+rah*am+9|Fn0!b|>PJ8gXkr@*y>w*C2;!5Ni+;=y6o+78Rxi?8Yj?V=uLF+hl7nVJHD71m|JcfMf_;g>8`H|s;8%pw+zSnZlbr0RRS9T z;*VW8nf0(+_~aNx(jp?}lu6J8|4`*5Ygbak9lp}chT-)!gxAuw=jD>Mz`?t~Hf48r zy6Gq1iBtR`?tbY=0C4x)I;`JCKMm0SYpo|I{ zNcdHA4*8>8%64~%z`d)gVY5!MCN9N?3QSPG=NYWb-;PNgRk~kW^6A$W42x9b8Q|oW zQ#?$M#RJ9T)5hMBIqbft9aXRbw?yFdP-71fI{FK zGiDXd9QVN|zE1*%m%0vu4yO7xX~C#2Ny7f%<>5=4JYBwwhFJHbZzk(fi<~o4L<*!< zix*cfDL@sfGJNFYfttbEuJEI%Ne~ANUVLME-T?y2Tc=Yc-QIA01DZz7VB+zhxK!b` ziKn?XXt!gHVX;Hq`AZTJ69F1asBM&>ndS%R9=rWpa3;Dwsx#44DAJ^llWe}#Piq^6HT>-3@Z z8E^j_L!qSDe~TrX%fAU8XN#vIzyQ~}Nx^wUa}bkDjyW||{CxDFIgAxLuB1o?6K2IP z4MENw-NE_CL$15JkXbkWj8zxbC;U9u1V3_rYP^jKcN|T4tcJE2*>f-C(B8fj>e8z{ zP}|&!5UPn+|FhJYf_hDqzK^$8sTD#nX8G1NNF8^@le`Mwp`2gkHh+ljL^wMti7@o`M7S}{bu zDxD%@SMS0Dg51hD>vd(&y(zPD5QL4M-Sn$plo)J|p?MjTkeOgQb26VD2!+4AxAZxV zLunUtZIHvH5hB49^;#X7-P?Yx+#=xwj;k8HEe9&LdRl$uYKCgH=A9#+ZquKqxM{U1 z6_3kRCtDAkaW9EFzWM07WwN#puC55rYsY9Vxv5V9Yma1E)(s>bw-9U9>9!aZ=NlWY zDH@()x(uh7r7Gmh!&01z2ggY7S-mvTU#V1UF(tnJL_kaA zV?#l|HAm8^F&fz)Y1>&XZPY{UwY5XR06w;+XA*d$)Ggi@-gzp}*_`Qfk#J*k_-^s? z9KS$~hIiQQ@Q-A8U+>>1RWK-lm2z8XHIk+U@?Pl$_^mQlsyhU;U>qOk6J#VoI21Q1 zy~^E5xfTWg+b=l&v?_4Nd)|GiJlibTy{|cOAW~JgR(E4Shq-aLY0(}t&lIDau!&Fx{59TN$Hske?>ql9Hgp;mptqz= zHG*Im7tw}m2;nyctl2C>ymn1&T$zKbp}BKS{j&3M98Dq(*aD zS6RQ+*>v-r0=!uncqIYP5M#TJP11(!5PBZrYpcqJ8Ta^DKUK`sHpYQ)DP3m1<`;N= z{)ttzW{SX$IaY3seeux*D%*t%@?`=g74gQ3$sK2le3LthDT>lY-Tn$4)Eu#TGJ@aH ze!YQSq{g=!Rq4=SyJpTOA<4A!wtM=H|@CJ!)}$LDnC>>iF4UFg=^M`Mh`mW^St8Hq0` z$DP{c4<_ac^9e)WwDP!`1BVCYa?RP>6Weu_eg{hsM^jT@{gTzs+1XFMgGmgG8c3KP z%^oqsj3dS3c=*2^Tzmw~Q7?jME>~Y&pCk6K-BAI^9-0~9Xh%ol$VmbUw0wUq=r?*0 zeLm*k27n4M$75FzmW@d?+037pu9L;NIz)oMfFi4N9H-7kl=b{sVwbf;UPGJ> z@$Qw|1L;HN(ig)vfvAj&9fL-P+ZV$F@s44CDtz)wZv;`WP$XGrXj`$eXZx zeMz;4=G^jE5{t5kV)gQ>KzCnIVSz2j$)k3lF|1@&3Fg!MVjn_HPcUGWVd;qLsw0oy zEv7<*32`V~JhQNBjT~AJRCQ)eBk7<$-o|&Rbt)$F(s5O7>s!;7;5INZNbN#*2|(PE zfq2wtw%2xWi$SoO^vb*w#5EKOLuJn1G#%$IACh)J3!Mg7VGC&-oP~lc_-s|R8jf`1 z{eoVE?d`!_uj69^nYltZ7jkr0Ej`wAZ>ZBB`_@}5+sPE30Tb~aYeFgjS%ww2LSOP8 zn^F?aSe-t`f@z{3VR!qupA7iiig{peyM$p-Z_ghenxJ(2wPwxNMlIV!sTu-e!A1?9 z{Fi&G-#Skk!NxvybN0fAZcGG&!myS3^sTOhPfMt%d10{oQGxzmIT37f!u9R*xOw*- zV5qd9(7Zq?(LiAmKR|TpqQAnbnEsq*dACVCZ;0Rwdzc%3@E4p~w8Y3TuLbH1ek&4B zo<(a(h$KFQ%|=(MnkA33ad!{vy25APGZ)8udaAcvq=tsZL}w@*u>KM zLgLrA?^%Xzh{x7FH8{3^{(`$mP2ba?j_BW6rO}SUptSvp8=m<#HCl1Yls?WFuCnXr ztiR%T`|>?~*UPqlISl{$@JTQQ)M(%%PC$1ls$M%wG`%Lfzzt!cr?p&KBu; zi@G7G%*F|kptpt=XKazp|n~GN{bzE==$9r@3G1Wh2jovde z+uIVsaqCTf2QmS(QO?Ll6|1bX>h;9p==&F>4CR0&vWE8KiD0#hWGHX! z$mTSvj%$G?jnQbV;Pn)jfPRoOix99lCJ~V?+4n2eT8rpf&-nXpQu-#Vj?Dr??EOMR zC%v62Hk5gM*m>oIVJ+r-Z-M^ghyw%S#abAZ5Aa^Sl5Ow7rD|Lxkg=)RgW!y`H^Vn? zNXZF!Ghz=4vn)z1p8V5@`=#v>#1MV3T6fR?YnjX?hpbJxJSD_X;yx-6)8&)C*k$_) zw?R>0gB&l^U6yxO$D8eYg*4U)$gR)?c(USUP3_Eq;>}5voMcj8^pUk>0jw~!tV^8x z;iO5qj=d5Xm93%^3Z!AlC}2K$spvfHdXA(y4bGzX4e5N<nAKp^?&NHJFnfl# zXm0)$)o~&&U{An}3SAUD^AGk1gTxZah+SWdWzXb~an4a1>9<<6=4ZP4oO=rsFHF{! zg>aYV@wUTb<7uzfPln)dEO%rQ(7UE<{uBoP!1GoALUeH{IaKYoN18e%ovK{vk41NQ%VPcWOGw)*hFd$ zM3V7k$T^qu7aX;?q^xDH5!p90CnM%5iSgOJZ&KvUUS2(do;h9E`3KJ|y zsv&!P9bs+7%$sPc!yVky7jo&H1o?y2C~U>Xun}aHbeP&30C<54z1#L&DZB4dzwX}5 zvS6)ZSOACDuZXi`-AW;61#Yr66wU>YTf!oCMB>V=_wy;~Lbb~R{+Toa80tU0AeM10 zU%XhfX1-Rz5hxP<)dVaGCX_sGmwkV`u{r@Bq9u9_0qe;AHtxG2dHcmDJ2hj{C!uK} zR%XCYt;#d@R^SC-5XH#uN#4?CeT?hr!*R9PiFQW%QpDG7>A2K{Q*yf{P))6vpomIY zN*tB08-dVxfV2y-TLl3ukm8NqLP>-}x>=Zs`fII1z5MeN(IWs0FG1_J*!e*^jzR1& zgOFOwFvkNfpKFbFBp|AyK+@;$_G2fnd5QUS*FA+Asp6lAwy50ior-3*wl_3-$r;I6 zbhHX`>F#$goN9(Y1_LS;sg_SabbWj>pv9(1`j0e3NO<({+ZIoSI0=K^d!p#vI7T0K z3g@rr5wZi8(L3Pydpu!d>Ux8ye@yG!T^FH^a#Mnki|j$a4@YJdKgO)P2U1$x(U-qw zYp}HED>rPG_U4!scB2BrH8r+g<+#mDe@IG3Blse2o82qd7lam~;Zy+6BFJn^$tUtY z#zknjnT~8y07vAUK{S`kC)P(ydd1j=UAC2NkyakoPP_~>z1l`XO)VjK*(i{~DXXVV z^2%WW!8-kTT*I-%qM6&SZqeWJMBM$9vd;FlbBjQvb59YI=S54w1bP^l`tGofA6EH> zutedU3&008Z7l3+vxiEh78MBkNke z7$S+C&Og*i_X6#1N<~-dB)Rv9tG_NNh6f9Xl*yv&*vGJ=#72t;GgV~H>#@eMJ;Rzd z12utKb&OvxjR8sCX-oRH#*KY<46!FoZ!a>EK!`;#er<-K8R@d7D9Rx~$;zUEZ_UqJ zT)On~>y*qg4ERD9F~<&9!f8566``?h66f9e>`iqmr=PP}MfE}_lnx+;V-?vlG25+8 zYb3cB?>WBK(|OVvZiE>!4YJlGEn@4qQPbKq|AqN=bi2*S8Qnz8dKwRF ze<7C|N7oOO8xP^5#f?7@lQUhge!}ZqG1-hX7^JHsPK#o!8S~zniswZW$XoX@80T+J z1^=ZY)INMM2efKI=j5L~Ba&}O>rnu^q2b*D2CvZFN$i?g**XUH&=V*-UABu9hh`ni zaqAeuuLvCJ3Q22bn8QB+->QurPuxac&J53MtrZF>GwGgAZ~{Pmdet+0eUO)K-fb*y+FgX>hM=f`PpyBq;}I*>n><6)R+=-C^;E;HKzJ8N=DY!I=8f`+@bG}q4|I4dSk7;D;s zSTeQPU4uJkXz25s@$0OF=aMmQ=w#*W$h4CjDM>jX4k80VT=&9t1@3G1@6xTW0g#u; zb{&mU97Q#dav}LI+pI3S5e7q<9nECTn`zAj0Dh^`kMZDS(DKz zRb_>a&S3|kqiH_CTUAUEFTRaUM!K}#?6~xQAY$((#ACi zo`KQhP0U*1w5TI1tC5!woHSgIMPR>Yi9V!jIiDQFdoBLe@R3HW)|EXlDR1e|w0Z}d zBW=0P`EYK@ZdS_9-z`4Nv@g$+N^tW_Kic(Mn7`OxR2!#M2at7Gyga-=__~}F&xoVG zWWC#5-&E37?-pUPB8M6@aB`4VoeGi!<-}c`9gtNUT5u(7mjEIm+nH4J;Q1&; ztK$0M`JhlaDZ1iE_g`=!7=pGVTdHgu;|`r2(82PGe$5q|h{}d~kd@Ysyg~8d-=US+ z?>|r1bg&wzj;FoqZ1!2a8naX<8meqJ05)tkON0g#Pk-i!* zAM~rumDCLyL}42l(CAa$qf6v4W+Z zJ6HBGkX2$NmsZxrG7ve_vf8O*M-S_86*IS#8 z=@xz5J;&K1+!H?QV7+TBMBq4_*j!~wktY8LUOYiBIN`_Gr+sUSG4amUdMW+zU zS&4qp!wBTS6YL|@8fvkRMa533U-1dc9w_l}9Fo>k&y&7bqCM8G$n2o&>iKVG;`<`c zP$-jsLX6{_=_q<#;6^Pvmv%EU^^iN0evT)4$4?x;ugE<3t4^Ckw?beXJXagT!3}|C z^23&PD>A$UkI&x^<%uBPgpZMRyXxrConXPtQ%H3eO=n8m28u}+9ycfBqmRV0cfCH5 zwV}_?%ssP$kQg!*wz%G9p?qgtIt{y!-tc7>(0)M$m2NZvVT1??H=}<$C7kt?P87ID z44Zw($VOC9<7t-XE(sdlG0w{SwhmS7)8bShR19Fliv8nfD; zLIsNiJZBjDGqz9qVX3|ZrgqrB;P%NKaMb%ha^IaiVf^S{rnmJ*L6cRO77=>?O0eH^ z7&>hzViex+=pyGesVq1baI=7E$0$1R2{SYg43y(H(`4(W+rrhwVM~d4lLPps+QMA z_CYaLyRR5aKQp@9Mv=@txtvOFyxT4Et>q!L&dqIVC0W4R_LOd7{WOEmUP3LqL%E4K z%#Cc7gY8y>K2^)k-KcV~n7O~wCQr=Z(<8%^WWN3m(M7Z3J%GPyE2eeL z87vx+LxFXeo(Q3ICYLHc+koM#+jl5p9}e7!4CFO~N-+9U^AyLx_>P|wRn-Oi+cfGz z_nD_yt>0AHWN7L2bMSBZj%dSh5fuH262lfxHk{3QQs}?nv~gTVGFDCYv!b%$&GPEb z-&2fu)-%4C?@y>u;l8%yj`*le@a1^CX^BSBRqBL`D((D{XJK0Sw}v+G{PcE@pG8}J z_WV!q&Jq78BJW*9Om-aXe?F6M85}|PTw!7u?yqnEh2{BwF;V~T7_a}&&;0Kh)_;F) z2Yzw7^#HOMQI@HP2T5bMIb}@=&yH<1O&J}A;LK+M8dVQ6K|Ke~wM6v_`K`LAER)uI zsBBoC741x78w89EIaL>1QWKnS@=V%~kb*U;gdz$)g_)gYi+^9NxZ(aZg{0T_8yB+8 zg(Ly9c_m@IrK~%eeMj=k#ryhjv7CqNe?}9hq$01$=gt==0(slRm-X$$-W3O(2LBCV z{QMri{=eWp>`ro4*#L$`^$yuFo@`hYMuxQ<VzLNr!)bQ zcemx!SK+gc4MxfoL^E5aR&G*m(^5*3%&aBt%l$e%A1E5|YqyUM_x13@y6z+G${o-| zpU7|2CsIlj&3KHb&W;xH7RYp-bEJ1ULkulh7ZJqmO5%qTQ-ileZ4GG((2_uhF|k4A0m5`OYmp;TFHBPj>3*A%|zI31r(LH+8K&dcHI) zc2wE#M^7p&I{gaLT=BE|Y*pmwNJ#z+e&N8TV}-rC=GVgo+*P?bz&u@()F1igmUg9eP`%{Gpn3-^^51k zA(0jcPvrMs0@{VnMljstp}tIn5UJN!0WFLFIA9p4MV0(YQx^Nx=hWS|E6{`^_$V+C z3~F1je%gq3`%hgjvF;mGYa5E5Hw~-aV?Sq1{hkTf*Vtxp(o;xDt+XwP@(d|l46AaP zR+@T_z~N}nZNT>F9ye2A-Qc;+an*i0Z`e(F-(9pytNRjru)ft67IeqdD=hli#yZP; z)TOI~A)eTMF~{SKSG9A(aJ$3!P%5TLJ_#Cs@z0~Ya99LZQdcOT&(0D!y^3GHUG5;?jo5!^7JG~pAy^RZ@viBhA>L+QLU zimHyP0%8R(q0#+LRx0;H0yY^)36pLWhjicl>U58W1nmbTHz5AW!fly~-aUt}EABi~ z?;3knTxv&~g?N$eRfL1PQyZ}9_uhwy=Avq(y%&T;N-@P$5ut4n?8C73upPoUi~Zkb z?!Vx|Tmq&??+aYx@F!`?ET}DW*UF=`i((Al{jLUmznx;!tuEr6D|nG3+B}5X`orw5 z!nuSa$`;9W4;T`t_nM0V!xUBnWKO4%?~J>(x-W+cM9=2|r!a)C0IGa8s-k7r-|uKM zhjSAp7^&=LeToFf+#!rfV}ME0As=JbS|PrOH5no^7c9=RymS(0nVe5-+~}drUt&H6 zxHUCQ&rhEjU9hJUg&oE>` zlh>72yfRdfY*@Z$?(p$V-a&^|CEG?t+L)lKR8B!s zfaJ#I@n&5}ju@Dj#ZrLY1d7G$7>#89vu#s45XJLuxk><9b)%NF4F?z> z45i0f_N+r_+GzhN#lPUu*$r1{^d1o_c0iVznkzA}qgqVhxERlx3rVB?vS5_trGT?mVV*9yI+-VYsQs$n z4D;%a=oyIwLEF@WuVGnJ_$Uf;MUdeB5|z_x<{=&L#G037+vY`uNNSf!TOq>-Ujhnb zT_e_|SnvN8aAWdkd`r@o=$BF@dzjo3-hZjOOMi|c{Gv!yy@68FQoIo8ev69uah!5N zD4A2eeE3(JWvduMbyptTfaZF0)mLgzeBbmwf&(;}hX4L?6t;|YJ}UY_rWwEB2z{F= z_;meyhD7f*P2rVtB4;+6SMi&_nKCw&!keYO`vuq6g~)8%Uo7$VAWg8jxGVzVJxM%# zejh51{7H$SVo6OT^+KIG=HznmvthB)X9Oiz;m?d_(JYRb65pIUgx8#2q zVp+HIq0(SVn%koiZ;O39-pIgkiARc zPV;QX>Yg9SDPX%MGBg`9a~fttHHE(l2G6c(MnlRWPN?;m)L%Auc((qR2O-H7Pk zo7J(F+hbOpJl*-bubIPUX!P96lJ)ULQrxTf&v3f;N!e43qa<6m#NwUcXeeg!QyrLw zIZC2sI_D+p0-RAEu76cW+7nfY2|l7 z3*BDKV)EbDdk@)?>E86V$i?&-)f&d$gpj1XZ!{Ac0{%oI7JR;YWz_F91-TXcahcv_p@r~Vu~76U*W(Q(n-<(ofO{f_%Jz1$$4?c-1UcNWl-lc z16a#rIVdR$cRu2&0mCXo#5-}+xwBOz(ikvP^srIWH@9*u655{O0FP2P3(Zm+GAmyq z+W#FT*%gW21J;@eFDO$qi~a?Nqp~?JU=iXZS7UU{zaw(O6preC(E^Jm#=KDZ6T98~ zw0~MD<@xo?9;V!R2NfF*&m{NLx*@bvV<-b+Yugp`7Ra62IxXc=V<-_jtQ2Ag&u@WS zdP=`38_J2mrTWSR93+kg$ajypq zrvf^WaaPE@z=@~z(Q%yZ$;)n_oj zqB2%<^8yoCAI3)|acN2_7*({Zt`w8w)5skgbhQ;e#Mo2Q1T~^znF8p z)YxYKSvkZ%|Jj(T1r^OIo$JM5N<`MJqk5c@L>fsNLp2EotF!Qd41resEbVhW7oz@s z8J(DqJh%h`B3eZ+B{f1BkQGDNn(O5-%p!WSNM~~peH0n?UlaT7iLX$br8{fS>5{=q z(hyCo|3Lc8iAyj36ofoqivX4+I3`F(q(X1O6qOqTaT)b|YLqdlTK{wmqkk?(rBCX# zxUB&7?7*C}0%D=Ov0^yp8;R?)vNXuVh#f^F!|X?k;ilWIQ_j2P+!yl}z;Mcl$n0dp zqFAdd#!AcWJoF!KXH1}C3FD=7Bkk7*qB4{5lsc~xBiPwoX=_C@e$wk7CzZ5N-4G>? z{nbv3bwK@v*y~T@$lk{p0FRu=2KZ>Dv?0n6(v835hHox7e5HNB*Zqp(CV!sxmonXQ z7RHQAhiGJ26b@JN% zK+#X1d+B7t^T(-$xz+!PN-AsMm~7SpxB-|C-kN`f8Hrph2l4_tds^>g{Qk;oU8@4vJm`~IJligp0_X)ylHXRT5Kmra$iLSnjYdtAqC6Qx6D4PXw9&=4&8 z$#>oObE}OQ(W#%7XIpN*=%Jz{?u3E@kcxJ|`xdyco$F)IiJu*z6(+HbsgP4fP;zh! zmP<911Wd7Yer{10U*MGyNs;0d7p|&t7^?$(H9dRv=Gl#DIt>DMXQO2WL{-9N3kuqX!nF7eMA z5ue(Z!jL5!o=REgm#z4_Hnbk@L#g+=Qcc#07dq-_K|~y@KbcVydL=sxC)CQ;T>L5ZdJb zx=>`Cal+HSsv^3>jZ_7vHRiblol@NBtU89en0bt*1*cS+?rtTRYmUr!$yh}=R_pB( zdJ^B2>j9QG8OHYUR5~z7m0ZYKRLMcMnZm2`6$Cj@fyz|=#>{W?OP$?a|$#leyVmr2T!2`$fST{+7{S9r)Sm#jy13_IB>(EiD(%^G@Xt~w{-IdOx`^)-2I4I?m= zy)w>q>|QW%a>zuIVvB$f`#w4fkLsy(e!8OB6~;=jEhs$`acFw$7D8_B_8wE68SC5X zlk^9!tKJ8ZtSqE7&O7%}&pi_AVK@eM$8U1N+t@oDuyt%h%EHt5T}wi!VS%4_Xv>D7 zex(56A+kpuHU7ef4IIm0k7P=L5d1P~&uOz9D;5MMYEY)X0I7%1?WE7xX#s1%KiBlgJ1e%Phw zc7#jsRG~~u9xirVfkW*3j}<)6uKOsb>Vfqis-8eK7Kr34!TafcQH_R-9dtz)I{Jl6 z$Tm^Wik`gkfk?}Ny>976HZTp`Lk9eakiF|wzRnlfst)1mJJL8 z9gxn1dWWwuMJ>LX}=UvcUt8O+H>hg>m`olO*|3BWbPu@Pok@n=CqZZkJQree# zjat4Al;A%}%3U()2JdtXi`=d4tuJVH`<@cgl z`I+=?uC3G!@k@X?=G`0z%jmsUD()_m&}IWWA&tdUx_es6j*D+~wvhW6eG9-ZIPdKh z7OyShAwR4Ulyo_CcZYOIcXxMpDIy?9Gjzj%baxEhFvQT^9ZH9Sl=~aq@3Xhh`ySsvesORB zbKm#1*1FC`x-Yt+1x{YjYUVgnORXi2jso`HHoO*9Aj z#Lg6&N%V!Bixv5_F#Alzb%^sfzZ3ZDJ>36-5z-82U!g7Fe%JJ!qsh#-T4p~^wvo|F zz1rHYCq`N>0GMb}yLj)XcvkL;^^0&e$S`;!(UfjHf(4uwD0q!MJX zeP$lXE5Z_rU4&XDov>q2FiZ9~Es;%Vr>saGdD=JQl^qMk3I`E8OJyRiG0BgSTC&b} znXJfu=O~>S#@Qi;r;0xPZY?B0t% zO9wt}szL1yE;C=?we-~qaL&CsgrEDkY`wV$MX!sqLdu!;;Bx5zMU#Vgp|g@Qy8z7c z<4WyHf>*Wjv6V7Ct1arBp^0fqdY9O}y8r@y9Zo3V!QmD^b@_D4z5_9Bd3M(F2AZMF?ysIbTrZW0Tq;Cx`aFyCHwX0-Wp z2mq-4@(dYU!0rCSOLxmA-`H+vY^yn@Sr=h#SM^!0b|ouu$=T1Iz5byS(@}1y?}y_~ zy;q@%!3_uA#&0Fqn{q>x0c?4|i&AQJ?loyXV7E`g8jt+CwOh6m+*BK^1Aey*6#v59 z-NK}=^qbh&-{W#biFP#Q4tb?S2aI-$H!0V1yoPF9Xy*NQ8TQ|YflP0I-%ZzOBpgOk zFo6P3={4c0Oq1J#T}+Z``*<@m(ZTrHhk_l7AN%{A)hjnXKRo0p3W*upAB4Eg>R_B) z8D&35aQ&hFT11BLJC_smb2FPz5Oi)^=$n;K@1}AfYa(*OaL|g#;HNri=uX}0vG>i> z@pt{8H*PvKqQ4mAJOOJj>{gKlACCnHp7(W^Q5jtpxM>m1v*IN?^62o*i z(98tWrc73><+TqxBlnF?WQk=d$v{(e%z9_*!D?B8*FtCzJNpz&ej*2VM3RXJ{N9{?5OEAHcexfbqDNl?hIn&*Uol6Ou&A=t+n3AK}Y6W z>>fmE8|L*!fi#Lk&-s%Y`&QnjRQp;70rnr&!avB<}z`80NX#GY?obh;3T1DyaGgEEUFb&ml1_##{unR88 z(6EL^nT_$kIWn|HF1<=+YDh8De<2Cwu@Sgo&>{H^rDq61W*%tIQEr4kw3W0U^D-!i zOfH%TCieH}TgtkV&P&@_LIJ;XX}k@aQR?7U`tj=`%58C};>EQWw9&uX{Si>`QN`Gw zOM~(Er80|$YSz~%%L(wKyvcGg zX`jqZk~T2|{HLYkCw^alx|_yuwK=`+xs>2B#V}XN`q26EPk#j9NM08s`ZmN>Th~E{ zFKD#w#FEHW%-Cu9oy`jW%y%1wq{mY9v~VxOF90$1$WEx2dY7$=!xJFvE2os zKSQ%L;Kl=3=mj>b2~^&*)i)egAtCkGh0EqqGH<4-3s)4jM4WW-?9`Z>lDY*GIWO+n zq;mK-zx8Hv@DR7XdO#>cO-Z9t|Jl&3R7=ROskEK4?-$r`5=%wn#9Bea_t=zeOA5I2 zJZsxpZi(NEL^UN$=^U_Ech-a5U#tYv^XFjg1rKiUk#4$YN=YEweVu7aRZ4iYk zk1S=GWWfPsQBR9iBuz2DKVf8?AO#X@7&^imcrKYk2)=Vo>K!~19=pd^TO=PK)FXYA z4-lhfe(B0+=&grk88Wi8cX{u9kZ$e@qwqQGw<*vL4(htW+|$I>3~vQ!Nx!C*ZQ|-U z2F$lZa*~U)t-Dj=fqTXc3yf!#_BYA1dxDF{JOqAp-(yYWS38Ki6>@JE<-vWv4dud5nJGWoL6@C z!p7O&It&#oM_US+<*Td^k_oM zg@%jV4d17CG#@hp8uaPg4qJ?@JkM3VvY8G2I~D*a)9G0$0TRT4G<(|&W=R0wTrvE> z?sQI$gjrmA9Mg`b)-`}_Q~m*O?9J0rZb_lXP?MJI`GVZ-V>;Tz=C;*TBr5~f`$Wo!jLlfLUu~MvliOoG%|#C2E1RNS=&DwHm4%9GQ&Y0RYvx}MJ^4?d1p7J z!CS>Uyi({R|9Zm3nC(g@Dfy1=5Us4E%s9X9dsK|!Ur_hNX$Fjz(d?#5Rp!v&W8wM1KV2#VOavEK(7hB}s#JWg?zYh~#m<;wh<)N6Izy zd7I*rGvh&3dRYPBz1epC&SfQiV)p}gjK>|w7i_2*TgBS^x;5TCT?0`g_PwV^iFIou zbO}ACyL>``XJ7>2#pzxd@MlEsk?D8Qt5y~8a}y+*NuNbp=J)mbHv?5+sm7CaYtmw5 z)APTc_9O%SSi7{23fTd2K$)xLOatU(fikM3)8GuhIvHy-4??W^F7 zK9jer#P3{W*ipG~h~9uNmV<@DgHu6>IDGW!x7robIVM{-daji;p3ls5@pkpxQ<=P) zi!z+AGEbz{L}ut)hqje>D3b^=OD$vhTOD{h*2`uwSuvt<5zrW((qk-97jUZ$CTU8T zbbQS$Anb(0=e%cR?r1zE#s+H92Vcu37I?A!b@l-EZd-!2!=zv3yj~f-th{8itv7mDB#@+QTe>_K}J^|G3r5u9d2wf=6L3%vosJ3cLUf z7G_8d{k7`s-Ie2^>S({68MF%EC4~BV_*pP%&K5%jrE1Sz2OQNN-aH5NrGoiguMriE zV7zF=mS11Vf|Nj!T!;cIc*xW;vS@HIK9(*a#Q5u@*)harOD^3o-s2#(5m)`Bs|_^^ zxa3EsIY>+|5RDS^q7y{vQ~4870(XTJRzSk}>HqWmeky*#&piFSftYy=nYG12vc%9_ z(p$$p+5bU}4fL0vXzn*!kNei>)=HL~FZf#r_s{js6{n0N9K$64M8rG_)| zR&d)LXIZqo5+g+FJ)NM%2Z$OJVDJ8#28lo|_-Z7}zOhPjA6GL{67tQk-03rDT&6Sq zuF?oG5lg2K!JD3sPRoTOQszM>-9M2~u~IPH@Qyq7-2``8%h*uTI4nmh*_DLjB9A`? zF17QZQR#CJ^~pz@l4#^+JZgS89ld@j4SZ97);jUsH@Qn?@A`Tf6YOW_f3I2H)iPDb zDc(C6M@Ybgh)UdVh1Ex9q`kSnm^+eGI)1b2a^kp7KyDO$^cg4+;h;(S~&p-lX;y=T=1ZuT>s zfTf)f9nFx)dhD1I(j)alFSgnFaERb;*H4*ZT?B{_gStR1#coLw8qdP($A)WT@Rg3j zmj&u2gI((zHU;6gQ8?nd`XBI{zn>cF)PIthG;QbIA@NSr%&GOY_X^&zIQ{sU7djEj z+BM%ReF$KbN%C4Fd`Q)pi@I2HbVMNskIqh{gAN7+TWwLS_wrcyQYu$5W9+l zGgwSue$h~PH-B15mV48-TrBhpCq{jBwa--tZS2O!NrQ`^AuCQp^RSs!W5O>Jg4QgY zYQqz%uZvT-+r^~$u*h)B6cH-7QRHd56t;OseT?P3&eZ$Grzt9)bOFT8%mw6ee<1Du zfm{1J)VDt~xzfyZJi?Yk zsa+NNtiw0>mKh43w5HYF{JLP9iz04Tz+9nbFFQ%%k4Z$$Pog;$by9l**qac~7<&Fu zPLM5m5G4^$DO-f$J45lpDCr`#LG~)*PJ~wx@A3@aGPt6N4FW!$D7T>Vn9y{gVwB#E|TlWb@8vG7#Up7 zTdeg6>ZC?9;KUbvt9VKb9iI;BiFE}3bVlL<63js!Gw@X&2ed|(nJ@#-f2Hkti%9L#a2Et;x?HBRn zB;9a7iKISUea0DIm;O!5Hu+yma>f7jbLE8Ljmp_e@iqh2PM6EZP9YS`!-mnz7W%Jz zwsanb?MdFe5hH9>OwcuDaZdfNd(_BFu^%FYAlA7WO3igfRk&tNe1uoc>qCwsb{4l{ z*yxP9pj25v+XlJT>j$4S(rlrNE_M8BH>?_{XjSi&AG{41u#2V2Gc0?Zp%xe5eya*z zS@%W*myuopZ`j6kscLVXV_!9du+3+?O9CmqjU4}`z+V3N)&84_l!hPhZyWWWN!kBO zG6S>1Gy7Yk(%{Y^**oM*I)wbddAFZF{hre;r6~~er|h_a|Ilh1{!UQ;ZPsGCR}e^2 z*V%^p{souwHX;zV;Jm}F-G8^5wZZ;9pVpl?p4)xR;1s{n!YmC>o7>$n4Xl$M40>Z4 z8F)=LJ>4Ie&Sly-JcQ0na$(&ZTE|S{jRp#(5(-<)Wo64nU{$rzV37=oCuEOMbmeW_ zwj1?~eaGVzm!>y)o%d6!!z*5G=XDygFFNmbxZG|TStwesr%P@L^W2T!9B7||AGHF; zZRgV5@T45Tt|jYt2;t(I`wK2mA&2C^($AN2v!4d>bU+vA^`QZ1EBS^c;eqNE$WFRf zCm8yort=UNQ!a-Xt8Pc8x(28DY)q0M+}H~l#|`zO>kA`(sVCgazu>eO6QL?xo5Cd| z7vYH=9)}=XS-!MS{>g^`4XTmzJ10Db$DO@*ibGAu`xyPtAj4c4$U|CvnOxGeZOlmU zo;maJuJ^Sy%qAP2SHCJRn?srjoZp9wE1{_UjN9@7^O z@eflNy(-wHX8Bma=1uO>2|ou%XwIZqV|fQFvCoP2GDom30LbV@^5@3N8s*jQ0)v^~ z?FH#W=qazT^}UmA+xrI6)sauqO|V#1v^sX#(ibG z*bXScyYLBKZ~_(WQLgTLS+lV4}{vcBN&pR{GP zx3YW=y!P#z<`rCuSLcUl4XFDk*3SGa{rsu_PM(#Szo(iqF+Q~p#MjhomGx!M{P8s? zkUdFE>FZ&pd6D38q;sqPP+06iP;!Au=9+yO3nSR1$Ep64wc?4S`A+1g62A{D{}Ua!}$q&u*n=On3fV}C5^EU>D%5f z5S@f@0zHOi3Fqq@PG$VIB4A=UYzh%&{n0J9N)d-yd%@-ZyLr;a78E^1mBKHE#)A@kq2S1Q(e+v$xR&oLoZrA@1LY zSZ&Ewi!)bS?NJWpG6mRq@!r+tQB}`P}@&F zuqPF0b_FuH>X7VEhZN-_Xew9FpG1|_Uao%_S9e68XJ&Z;CEYz(XC3e;?dP0s>D#At zRum}FPiOSyk<0;ldoXjqG}f4+ttLc@2ALc4rgG~xqwx2=uhbe<5;@X&$qae^=+`y0 z2+MDc0@blS)E@cYL^NM>@)(6tficR^IS@)q#;qcc9z}8()sw_2dNH>_B$-Xm?EQlr zh*@>YQU_w)9zmc&HC%OAn+)=@1bIKdz-tHinFsjp#*1R-0d0Rc)&@fv5gZpt9y9PZHP>rOxTWITInr2q&NsmSW%# zFXRC9I~%VWHhIj1So>Phj)02SbckHUHMVuDv6b|K zRNpR=fN1RGm`-wwz{)^Vk|LFIAfD9MdB%joJe?*8B;2+z*UpHuoOm~kQDOTTQzVxF z9xz$gOol|7Tkkx|g}8Tvxh2G6Sa*&rcMuzlK#$4Iv0@ZK%WN3o^sP zvucn)EGZotJ)feYARKVY+!+k+w6K+L;B|Bq5rt7K8-CbdaDM;XUo8*cnlDbISvMpD zJ5yn1;&Hmql9MCpl0DQ91J?7^4{3lktyJcX#xXVTtHrK_W69;--bQ%BmW@6#8+Enq zf16LOZy@YXuxtp26u_q%_D_nf@Tr8Wen*0?0I;QgenM})3S{|a3rkf$|19GPw9N7L zSQoFQbf0qB@6)DfFrZCaH6SKpY#!E()^X!O9MRc~fxAN^Ts==gP&a>;5s8wwikv1z z8@yzye(ZB=_9OLq#BpqWv^?VW!TXUhP{Rm)BGwE}Z>3;$MSc+>YR?s-nbHlTUAs9V zS25QpR~XK*oeZf&Li$dkq;WK;AwzEv`PSD_tXDp%hxdmhSNGPCQc)iPHIw9ikqgu% zgYDXdLy99qes}-XBF~V?m=(g>)txNdb!o^7FZRgSe!Q!KeDMhKS~!_7*Ag*k3HhY_ zqst%6+#fK6IGb^ob2JUMx!jPm%AC^6L`&)rkH?q9QiBWI3q9lxfu`p{ZXx(TfR z8OniidAc~YxltpcUae?A&YK?d7p`%D2unhjfmn^g-zpHB6?PEe?a^PDJ8}$p{U|Uk zqxWwY_?Acq~Ga&D{dq z00|Ybv_#W8U656A#Y)Y85+n#YT9}sDp1HH>4Y8K&-0kk}ncuoj_Pb z5AU^6piZen*|GbiG`b)B)e~ls#NC|z&c^)mnD#eS1?Zc8J;;pt{I5exM_UQ76w|~8 zIwv2jFv{2DqK=k{rZJc7|C5Ec+4l|2hfplPH9DjnC_D}+Qdd*YuSLS~;f;2s?;Gf% zMe^9Xh11?5Ye^((JGXYpf9SzTfsX!9ozlE%Bw8gHu~CX6%wk_WGm=P!1w4xLTVgSk zZJGA-B{%jX#t#o?u5N`E4!VjwyUh-ea+V#7ndX{D`1Qtbj8FzX? z=-pT)p1tHeTRflK;44H|$ExwQG3N=YhV&1^TNtz?ud{g2qq2N6AyfV$@>Pf88cg99KT7Jpn04KHNip6p z)~Y+>bH#x|^2Sd}_1A|$kdOTB(&}>VE+=a1tMc}nr|MZ^#MiQ=U0MIyg-^Bd{jY(I zYU7=eA~lur%*?~S)@II{*qDMRR{6_wsSAV*_oM;7cC*B6m}0jcA!2#pCoIYB;pZgw zUzWkj8oP?t;yG|YI9w`>6+=gTNOM@u9%~#9cFZ>1!q*utAcxlsewdAwM9r0blXqlC z+mUgc1gQxwl}4>*oR!!1P5n;zTLwa=F-bkDVh_;=chy%Mb+cCjZ)6-lO9Az83amd3 zNSv!H)oWM%nhH`&4X?Ob~VJM*n znHF8i>1?^- zmpIQ4iLMMtJFh>TGb`5Z7geNQH`C&M`v9n^%lRe|+fSM!ghTKc=3Av_ANA1N$wRHe z+bAnzutm#}jKai}B1}QAJ82=W*CXAy1QA_z*>*-E+xv94pHo2tx8}*D=W-J}1lgc1QJ~hpESiYaXKnNAfO;3JkjT_ido}-?xGG@5fG%@NhpdmvHj{Q(gB> zx{f}9elcBWmFqmOC9>Hec{syASgp1{arbmTHb=^O<8X0w%~`LUeZG?$P{=vrp5eox zY>yzqwv%erR2Qq6r~F)buis4K6pmMHm^LZ|Ly`QvD5a@S z(t4}OXhTPvhy^WVUBG)m#cy-*m@rtP>+mTz_Sx&h31;-!8dc`6NSuXJt`#sm8ckT% zD)B?>5Q9ZsiBI|C)I@uFvuDUu)r4&-^UU2`k&gosgH-y9@XCU;d433gU>>>~mXBJ8pgN zU~i$QcYHWsNhcw1-tnqGrF9lgu-x*?ew$kwG4HNoX4JrS@ae>u-16SYc)UHsyVJE5 zjxU_Kql2J_-dU%YNVm5M}$>y{O z%TGP~y>m-mvFcIYX50LI*?2b7oss0h$dK?a-FS)D-`5{(7j6m>g=QT#t9xGUd5*Wu zcteJbdM5-X9eq4sy*n9KB>Lf=Rn$1(d}~QT*?CX=2aWM>0me)61b;zC08#LxrFV16 z%n=X&Fz%XpU(@ei!iJlbJ)5~c1m{>9u6@45aJ+4F0l{FCCOx?(0~%WtRrL?AB|Sww zeC;U(Hi-=vh`(Z&`ZrU94_%bk1SIsV3K8%R%{-qO_*f9=+wA=VlyE*(Xqlp>jW8f^ z{&&>)TkZR;kH0Y-2@ghvgZHD){fB6+yj@E2#v8s)v@G#ICAas7j%^QcYDm`CMc*61 zczQlZ~<)*jMX{dt<`d#bH-f(Fwg@iaGYcHhnA(>0;aiR3u#)rm6*xmm_R^bmnU^Q%=z`HTKS<5PLDcaGXJVDz(OtwcsR>b8 zTeGyDB7KcIdc(Zjw$X!~6E$C|@&qLO2fQ*i@uXp)surPtB^bQvz|$-8Y5x^Lr}6Cs zK>^dA-WxWf8~#jk_QpgeMd!$;&1himGnWY5m4ZnH3ztE9)}vyT+a zbU#@z6974G{-3wF7rNuEpOd9?;+<@q!jBfRhqyWQ8b zgkB2A0Yk_>WGty+glS}fu3)^cv<pH;h`bY6;Z${`mnW$g9Rh|=65>%d(K z$WX&8vSG{X6POn7IeYtc|2xbTfEDL;t!zqWTQtHsAM&fdwp5rD_Plq*tYR$#OtM%4 zJW(X0O)W;Kcz}5!d4lHC>wcvBeZ+vs0koO0nsLQ)Q5k@jCC0Xjr~DVaQFMT{GuP3J zS7Kie1wCZhTSGc3!K-Neie-}Wql*m*33AQ#oWR`hs?!eq8M{dB0=AQ2*62q%OM*M;JNfqUq}75B5^FY1gyo=8&t<-5e4qRa^3IO&ae#R3W00hr;t@ z-(H6RWJ`D$3;K4rr&9N0?T;ewi?Yl)TA(Pzfk84stbblcp3sPUzrWMFU?*K6V?35X z{(We6O7(Ez56?~H@*(VoJk~H4vp6~ymNoA%(nz`B_F>^azFU${aW-h}>kz1KW&=EH zhtW~MCDT<)=}f}MyQGS*o9aJgogWvROvR<74Rk4Rnw{#mvTGfo(Br?R8FL$f-(;zB z(w5y|9;Mlo<#_*AS3oJn5k{N{6_B6U8MdBG+~O{pqa`%&YHuonTaQHNnZUYbVa(B= zUn}aBqX+}IR(>6}Pv$MPG3;}mIWOiIP*IUZ;m!u32csF;R7aB;0FDpmqX#up5k4o6DmuyQ3&p1U3$kJrwu``SzT#kD)= zkVXZ2GT7xC`JdDb7}+mL~f*&gUb4`UrO6 zbI%6m-JIR~I2}V+icGo{W!G=n=(j!(-GF0=wcw${rsTP~JHw4@+tsu)ComptTHVcp z_tEW)uKqP#X;a81wf4eU`j@uVJAc<$r}}hg;kT?k-dV0?Wh9EoOojWeh?H&m*wW~w zI?|2bFGN!pV*Ng1y}biZZ92gdJqrJmC+k9bk<9ogMcwN`435xw_j084?}0D@V}Gz9 z_uq2zuHV?Ja&WI9JzjWGVuW}_EyeuS^U#?7bgb*hqy#$gAt8wtSL;GGT4YJq?Ne3h z9h^aW+*P0Z?IEb<_uoGa$%iH}qu>APzaoc=zp04fAH$hFvi%S4&m3g!N;Nd3$&4^a znL2f0r82Fg2n15NUdI8)E<7#BwhhD%H51xj`NZ$fx8JX{wRDG-!|AuXtvWhuYef9Ao;mp~2P$S-%2$zKsJ;I zZlCN6E0!jtyQ-}|v^UA7m9IdBJ4)k4l|P0L*sN>~K9N4red{rBn$O*?NT^`MdkSat zO`y9=+wSXFv}D$?l?>0qu@J2C{-6Sw6bMaiu)|MfdlfNEC9iklVgixLCq$b0=#O~H zw!BQaXDtryE5PFG;Uo;K4NDLzF!V*iKxc!y$QK73{~E_)TnZ~JPH3q(5vnjRF7@C| zMn6oC=bfBC8KDqSod`%^)7Ij2O{^2hLPh+4t;afK-f!mXntGydPfqDo&zHv%-+XI_ zXImdoiUbXnBdrnrbBvU`OsqIB*;U4!43Fk4Yuo$FQuUlFKRPyM)J^O4*n0~E391R; zQ88DR)cvFddD-eOh^0373G_Kwq;K%7b_St$&PjaRX**+Pl)(l*aaJ;azM9~!JcN~l zWMi-r9)J#sdaHL)`tAh6$J}qHcDi?_ayg(-Ra17N>j|D20ZZ06qJ9J`-q=-EjB#$txw<6?w-D{d=-OqSms0- z7Iht$IqUUP^DL?IJWLcW*(A>a&})PjuWa?d{Pg|$zfbWB$X{^ELrNnOlF|`Whqv&{ zcCM^SDya`d)u+yo$*^@q?3<97?OYm}_6*-EE}tzm8t}b!t%`R&V7u56S=0w*usiz? zD>OiY{9U~+Kf<0Tf!xaX$zN9@f9aaIJ<-#-upAlkVwSW>`CLORC!u28jSWG z{!FcGnqPM70p>aScE+SLf^|+3^~e3Jws$rS8(vsgN}sHgN@7)vCNL;p zoM?*-Tq~$p(z@LteLuUFZ7%uoc7k&}i!Ej~(M}1rZcfD6*@$*PAt%zRM2VeL2j(2c z6t4XiJKmE9+Otp~7DGD7Cp*pC5A){C3Z#(yGFEL!ngCDoOpT+8w%E!lBnqV;-JhkQ zMF^xEFvb~cF zO}_@gTA1R&wbx84-ioOs9~oXXj6a#~sY&Md<$Xv}1dd#%iwtXr8F zn%LT(&G5AaX(R#>r^%!Lk>VfQzaG-u{0@B-MA|JHeX3C?U^t;dvk|nymBVfTgnwME zKro=8+-A0kbN6#%d}e)T@D0(lIKPAvi#4ha15R0SMC3J>R~d>kEVH0rodx)??ZjcU zh=cR7Sqm7Z&u|ml68x<<+aVxKVru~IwB3mmD z61Hu-SYh!}joslK6C^D1o|ygb8NwmxK*V(Km!?e7~yx$)z`duc+wrNjT+gH0_MM@6hM%A4nfp9)-^gM}Hl-ulwUtOOAi{0{>F? z40beLFI1_`WN7+_jV}{cp2;DkdOUyj&-1qi8;pGr>p;V=TL8{ErS>buXJqJc#vTaO z9}13c01g=v<%&~H!m0jWf}P2gSw^~H3chS^qTP*14@rOn3Q7t6kl9k?+MKURwILJi#Zc199i~toS@k7CXx0_+pn7lV zq^Z`TVX;5?63cJ#eaH#%Sa%@N%g6xZPnzFPrOy4~)$3|oZJz~j8SrXJtYAG>C$}E)a;<+lA!vl>=e_TUNEIk$3_RDzx)cAf_{$e0TKkeh+&?IH zGwAH%G`}XOJvc;bYN&3w+*(UFpHnG8HV`Q+B3>@@)3wEf%ewSL9Y)to*;UTos zk=78?M?>D5S;v!(pxB$bh3qG=3Zv6N8CK9gO~$i6KC>?U(pG^sGMc=>HL54_JsZ=> zkAAEv5tJ7obG8h04*Wy`1qIv*wlYEtzffQr-rKd1OlT~u7*AZv_Ukp{kd-!*?b{&)dmQfBt!Rded_Tt8i0{^ zk`w$oI638QT1S9E3+fXS?^cwGrc9P?FQt0qSdY+h) zZ&3T!i9dsp*R-T z=vfzzTkBLO9l86t_fZ0CmVAnPp}B)TP^d*qxV&fi<|1P(<-B=nx~>TwJF~AHHHIzK zTlHOH>u=TohKXUL6cRy=Z^Ee0;i3`x#HOTUEe3gqdwDvj@}vnko3d!QT}k{Ux~W2G z(i2*Tr%RYz4|G7DHLs1D28}=Z2!q{5f`>cd?%`6rRZxJ}Lt83Cw^R40yIDv3$zO1} zF+~MF+`Sg!7bfvBHNEUiT^CLyuxM9Wq{b&h)VX?J_>=RYQ!*xj2L7;}%C>nS?HO~t z;QpxHY(Eg&dYGUmIQyT){B=b)rdz8rtfB9tpVy*N3=EeW>Z8$0^;?e7gm4mGyp1~6(pRsvI-TkGiS7@k_>$n8!lQs{o%Axc!Q;(E~N zZARzA7Xw5h`y!%~xq30Cw7%UbI;a(xX+M;TLi5m12#{AxW6;lhcN4qW0{Qo++4!-v z!wSPGGe}OEf%xwn0(aeE6{n;;uus-saBROmr`5k+wO?v`g6wKYU(%)Fv7S5ImP#Me zbEg$h!(v^LFo&8p_y+|cou&Cu#GSQM71{d~gaCT76VUn-ShT{1R}FCJzZsL37)C24 zJ)HXTE255hqCx`OJ<4-N6r~RwG?`bNQ-&t1!1ne2MM@R_aAr^EDcgt^f zsbA>RouWUxr?o%(3vTYF>Tk{FcMpa4ZLdXiKK1Bj`}dquN@h9#Q}HjjG=kWeBoodCEQW_~=c4msF8#PE+j=*>Xu_0i zKt(pL$K;OW5k@KvsfN$1F%`)jIjiT5Kh(tk(@^zyTf}dZ`d{Tp_x@d4l&?B_APNEM zUZ;*GXOdY9p^M^(5Z;((J#Dq%ziPSm@vgSR^pr(K<$PaPv@)9sp`MIxH8F*5c(GG- z-^J%YuZk|+{}>)T$B!?z$W|D}%;Hvy4NuLiu;UJ3aDpfKV%)#rM)EBOneR_1ec1|e zmkwsGfJw^!ALA;fX3<6?7mukiE%_&h zVdThJjj18H`}Ggn;4x}P>0Q$D_thU}u`X|rEi8%<-@v=5tPZQu-q}`5sem(It!8DQ z_9cv0kgd&~SavK=8A$Cl4WdRzLr!E!4oVL>@vp*pM?`uXLYpt+ z3o(secU+ToT(3N2S6h>tjG2=f5JzgpAMiFS4wC{o#l!j}QV2{j-};F&%>L8(ynUVm zSoJp3v@meLKIUV7!JoGIF;UO4w%an@&JgcmFfo<{!|EtI>e(f+cl5%@GBa0fISI}I z6a53h}S?i0~)?_cOJS@R#8Ty;tOkCMA5LewUoA~(~B58O{~pnTVwtU zu33Q^HrRZIIY&TRfeDE+J*(^3uUMApNVcrfSJ1Iowr5L~mi!~vdNVf$=*X%T>c)P_ zC@G1F4A=#SQe;OIYa~tlI}wbQdB#i0{9*e!CtMS1DGmZ6zSz^nmp~riht{tXtzI6F z|J8kkkQL5XaJv-KtCGf!NSy#HW5p9vQNd*ni={QrH4E z?qe`4V8A_@*FiWCS|WE4bSR>8uqu1xh?k-eiBt& zk$c{xuyEqBt8!*lR!pLUc0SQS@=*LzJ)bp%W(1#6uYSSwb6Fx>OP}%TQ!^rn%EYt$ zF-{p092qXsfN}5)6yooxT?a}c26)%*QCu#>PAJ2RTA`3N$h~Dvxn82?pd{U|^sqZ{ zI~IT>)?;cIyDxII4PbDG0lk5Z?7N%4#%xS;=cHP3Xrq?g$@zFsMpjllOVR{aWL=z5 zIkjrL=tnF`O)ui;%Dltpshh>_oP?^aVCIu!>#CSH&aVd{S0RK|yWo6NoAR?Q$b~7o z+S(*2$3RZS8l2^INQ;u39N|{*mfkYBWad(UkmU};?LqL-W}iwxjb*{_%~7v@bW|bB z+8ILIlD{`eiDC7{T;aetJOWW)rZv3TuT&a1Jcs?|y3~qJwan9$DL?An;;;1_aq8em zi|yyl<*b4#uqwr_L2w>#T1Y+u@%Vo4rG5<~!t)t2FXWmic{`IzgI&`Io7xe+OC+_ zmMNBL_RBa4&bh51iozDAOy81K#TdbG+-yTD$p9ZbdSq9$dEH2qWdWYUOi|zTcgF|< z*dCu~65i4~$K@(|Od3Vx5N)?+^9eS7sQ0s%O(jOd)s2y`e&=3^H_Z%8Onmm$g@mQA zMWTRaSJmPldR8Y^e;>}5f%;wcVBdr=UMpYM2rZX0Q;Tp->g8y6PGQ;QP&cm;h)m9a zDNb$d_KBiy+$-_(;>}bdvH~h^kkPAl$Aou+oc|S5jO>uvteVscI%JZifo0a?JP+oNObgknHB!VrM4LK z7aZXJuy~U;A}XY;(?yY5#OZ2bPD?xsn82jxBswqwS;RPId1Zp`@qlTGRJr$ll@TXJ z|A)6V5=408jqkI}l#Z386uD;5ca0#}0}_U61s0#Lki$UC*Ld!D6R~+}WJTA%@Jl`YLKJCwi8K zfIdB?G?l>5vaH_T^NYGh-EaO3agucHuQ&tS)g$S9;nBA{3}yuw+D211bH!mi2r%KavTRY)4Df;RUf5RlzSN|5be?{O{cWOQJSyJvTm*!>l!T|ua&3G)hV%(xX;$t@);v2C!I25>*wBj87`au-9sE?C8)M(9 z(MZj7$xn$u>Lnj@oFgF|_qC#+A%;7pwiz3mrN=eu3W&3M#69)~WP-Kn@h`X^Ry1FA z?yorig7YA1I!~6k1YvHX8eY$0P%~lRvd~RB)M5RUy~#b6lfK)0o)(oZ0%zx5>U zo4tSeTh38~g+Gto0q>lL8+ad>?cMxzJ?o`7S#i-f-uxhJ`3ahDYv8#>mp~Ej|G5a? z^T7#kKW{bt01CFL4X3{0=fEUU1&M4WRqdwXM3p0A|^SU78E}p4I1nYx3l* zsyWrz}X!M?nj^jjJ4f zI0Z{p)RjsfU=ME2Q&N&&rpC1k#(3}A%DW4-HLLydJU-8eSwwylvgYxfMH&7hKI=id@6*z%}ba%dQ`O?UN_K5e$GfWp-++ zmXYR_keZw!6Z~4CE&52q+#Ixe1d8(>(H(83#|!mdz<_4j^M}e%k~^9dK2jMGI(o6I$C$56NK5m42E?PpmFkIa4p&85dwcoPkY$j= z(N?Q6A*jXt`&aW9Q}h`COB>nLAE7d5{yPl7E|Fq+N8ske6ro=y7D6i3kF<1ab_<=3 zX9mC>15T?$oRoZsRREQ}OV_Ll5)TZe<2+Q>`1)t6T$O0F6)y*RH4N5>0N;WR;C1^KpFS_g~b%xY13kF8wfBmI@_CqTAk;9NlU%z6cm1EO$8aaYO_rD{1v z5!_*|BWqP*Mzt6ZCRzQ!Y=`Dbo}?SuAH6pCY6>y=tGbXwjGVf>X1~B&;R8~^wG2Ox_iSy5bJ(vmF_i>{ z5t`A+E`A3e>4NaJaCUn%DHD7Cpb+?xYh)jt#}|6_&U)5B5~F<;GwLy%uK ztCYM=WpQX=b=h)5N!IJfXFL`PPQFDUcZ1$6qUEoo8;Kcg&*xCVJn{w7T%Nc?BK6L8 zhqEd=piM&vReCg8t_wY#=1f-~yHz|T15zN*PbA1sb$Y8dBDRt$et$@QAnns(zezDOdutB-w@41|P{7w3)=%y@+L64zcF5_Xs3YFzHX9RG9MG2Pw8rr1liW z)?YxApK;@ip}J2r1b>Ojspv+(>SUUiyqzAKO+GTq2d379#@IsJ@Tk5Dh>~Np{1h%; z^9=7AqH?7BpiM3ome9bO|49%rya%wEQPjgzkQVz*1R|09;Ro?*O(`dO-q08AOOv*k z2%3#W?_UUTqVvDd-4*ew#Kgp()d>74?bEm8niQw2#VK?Mb3c(bJ(0&S6XP@A5|zBH z?o;>1zFAEqp;hybxv~ii9sM>u@mWCB@?X9#KP%L1LodzV>o4+XdFiSe8`Bg=(^)J< z!&duj+3%}XoBs`2|0ZKu&w`wLQ6=C~GBP~f#CRuPJB=x**T1Qlm6$KVX!ItR7rCmfAFk^c7vuk&U3K zzpIOUt}d=9z+bZOuK)SeZ(|IR#JUcZ%5Oi*7N%of7KoEpLJ|;>Nc&TvW99Y-K?gSO z$zlYv+^4avmjVe6%}6ERuw~GeocNyT8tw#|2Y;BEaS8K7Bfc`stia2yRg;Sm#8g6J zB5|c2wd-i-&sWi)wNWMq$qioy{#4(0DXfnACjJ&R*e@{MjLlVjNSo9^ApRJ zDdle25z9)IUId?Fft(L7HK-WtX$gT?dI{kiUr&23PROjM6H&bre_u38>$rQti zK^l+67eV~@%}TV2a7@UbASPMWNRD8qntUIzk!NG02plZvQ05`Wa#}&l4j+j9E6+o{ zk&SVi)`UOLeoSUzWq=AepnW-d;p5F*a zz(3-y>i!;|_v*r$XY4-R4%d>EIb!C#iHp9ZR6)tV}=iPI7E z)DSRZhhqTLlTzGi^ZRK`U;||_yvflajd~a3B-C#?I}CVfTC3Kav@85bHFf%j{fr{X zB?_tA`KXg)$3peC0mgjQwC7G)AdlyphlR=o_pw;QG3ULKK`_0aTvZ% z=VHc_bCEU=V9I@|9&?{;okTzRK9G*!J)H(4bsBy)T0~?-3J=R+>-V0mgC{d~FKpn( zu3z5h>ZL$<9m6R2SCL_Ki*cy-}cMGb8Fw2dl=O*s}1`vXP$381f#DSt>4& zYlPh|1Uuey z`Vjp}I}Zn#uFE0Yu+M2e<&%OILZAT}V#me!{A;f)401*}tm}Y6T1TzcuP3K4_L<=< zZk%o$;vQ%FsHlzy59%LDj$j&g5f2hyIrNB6&TUf~5#hs?%(bU6KD~!mOCL0eu-cQv z87?N`!vHBBpdT_-Xtc}jx_&phkV(F4GO zVF2=T(7MoeY=rjW2zx1B7DBQc{}CMMhYECKdmKi@J*~OU=0~icnifCnM%#Y$S;+ zMDZgU70tBDM!qWB?FD@6+t|%}$ce;sINC+re06ZGG_&JR9|q|-}waCn7K|E5Wwl&;M${O-V-?V!p>o~bA2TK>uBK z{|@d5iRlHa!IB;A&ZKZH(9|A%<1e)Y#nAok7M3dQ)RvcBl!A!&#u6)m1u@F)JL(9V zg&ALQTA6aY%MFTzu!YL!j^^ivf)Yli({nETxY%EcQSjnMQnr2?;z_neFjO{|2-s7X zi>kEU_+pbXwI&4CBpFa=cE9}pZl>5>Ht$6e4pi1YiiCn~IGVRV`^L|lc${q^zNA!n zs3RnQ=SjD=I_R?TwtqMrv34>V8ajvBJqJxZTJ^A^8*V0xsGUKI>FA+Jp*urv&qMN) zOMm~&Kc!3Ozd|Q}7;6}~yW%;~D9+QT#2`LNuoWQp1E=V^&b?-!g0kst#I^q8#2QD0 zks_b6jFk~(q4}3iBp(sRbV;`hlNwawwV!+OLy_GDr2i0}cPG{eZwJ;EQudG9=M&Wm z|Epl_f0v3Z^l6U9i}+k+`uuNsxHs5OAjlzfy%y3y!?UySsiJ(<;i>rv&-9@Cs<5d| zXj)`X33pOWD(B{-$PF?{1m$ag+OM7)3@8kvH;3r1s7=;=r5RN0&1Ao&Q(8sa>rW2M zy!)CZ^cK$VSVGzRe3Ufwt18PRaTg(EvH9qQ2_DyCO>NG$sJ{>r$Ci0Qwvl{E{AFvH zapP$X5Ab_}d}!>iDg4~0y(YPEWC!o$^N6K$%l~i*cm#8g%BENwp}M#g?gX}rcZjCo zmc3Gb#Dlfrsw zdB=?IPSKjSrKKUngF5+Rx2Nbw1@06hhiTl2v%3n4d(0iRwhvGJx+6VbweZrKgtuzd ztg*Ev@m#AV#g3!6JTbH`-@dc$ES1sJ6!$=l)in$v3}rJ2*oAnILY+W%l^|9&A0g@_ zi6)!&`)_)8Am@D?e@=ptkx%m?F}#fL)E{uZzMv-y89@FftL}cM7QbID$kZpi<`G;2 z$!{i1#0^k2#)_Xr=VLyM?NPGH`45kTDG<9@QkLDbZ@q~*ZVE4w#Wku~MvF{D`Xt)3 zfaq4dDHa7tdsjGCg-r5c^ppy0J~I;w$)$Fzb~Q9;RJ8PYgUo^njcca2zKAu)VM24w z6QJZ5Ex5RzFr+JV6xK*Y^k;%os?Kv&*_C-;qmtH%vTQum0Vvxgi@rD`RmGczWwvBZz7IWh6tsjYa6#rylx{M z)DLwtQkC2l1t4x99OS<)4Dq_}tbj$cMNQ0-5Oy>(OM%I0kw`jdYQ~qY+UxxGBxzsv z3ar!-ep)e&>`rJcmzyA51Ll9sa2^1FBi^Ih2E;2Nf$#5;INi)lG0`M||9I?Pp!!V(MAorA znBV-Pu>f2-{)gLma?~LyrA{;H1luCs$I$mFGgim~y=D4yHQ3|n6Ta~GwM}V&_ea4n zGVbpyZD!a0!U~5B+wX1|Mj$p6EqBIvQ>`5p8X6y zMbddh#63)->U`ZiYo4Naw5=gde3qUa{m#{MA)bQ`cq6SFudfb4dfaggc}PKVeok3j zX(VN-v$Leoju{IpdydM6_g5w2E!n@BeBUB}Z!c@hxLZCjeqZXO|h zUUh7nUW$tFVH?5mksm%yKE3fqxbp0c7b8l->6Rm}-QoBIdSm#4%&V2_6)`8_nYE!n zfeg>uYE^&O6nJ}-?5$~#c7pCk;hfFq(3ocJGA^BpzYB%N(02tMfsJn(xdL*+}RMo~GUsz0LotytcD5R?RGXchq z#~MTnB;IWE=?j-{iUqGFj5fp8fm;x1VW^BO?K543TPN6NNol-+I<)AbzOBE>f+Bo#A{;Gy5 zva<46ZC`ucf6giPAy6cypLvUq)p0nankGoTK>mteJGnlUB3HErv1QQMv+F-fc#|xz zezrZ0>g&)?+U;A!!K6dO31=)A8_LgWa@p+iRl9-rXKr<5Csv2)w4p54Q%GVeb zUGTdchY!Xkt|r7Lb#0sXJ0{+|7H-weqP6@(atx-reAtmDGtA+P``TK)46O2^!a7LE z9Zmr7{xm(pK9Fj-k)hWH4T7Kf%t$oI!q$=H<*=nuKrp#gfjX2$ixF0XV=0~lB34t3 z3<-Bbw!4`5uR^cm!p50Zc;B}QqMr}U`!ieV%9%!4biMvTIZNC@YZ<~w{NV>}3D9Dy zRlm4>>!?pp7Wwf>&T2GIF`VLG>!5#)8`dzg zJt+DaRjv*5#B36@Vfx(NN9dItOTjSgQqPuv0V!x`z7%=C7{JIt%v#a|w zoFxO)3<@>k5TgPK618Sy#JE2Q}{@-?DGF_?)-lr z-v8fzb%iiS4Y~BE?&T1C_3J*a7M^E%HHc5j# zJl@1v?>g$8cnNX+vwH`N9P&7qbV`%w7!?MX&)OJU_Uf(jSjBm)B6`kGoEtt2&Kdt~ z_9bY@cB4Fkd(gMS+OIEBuA@%vNqxPA#=V;UeAUoO5THOZA%S zNso_V5TYd4;IXOwOi#65o#(Z-|Ay}$oQv>vhj>1GwK-Hh06lTi$-}-@eLcDeNdART zY}hb8!t1>N!;LCE2Wj~Vf%AEf@|owO0A3)dVbT}bgG(!JKku#Y+~Ww?NS|qt9KvrI zpAC*}p=WvNDn*p74PXl{!+0v3V$#Ykb%Gf$rwiA*hX6=_(cNa1l zUsuE@Y*Sq7GF_|=djA~8W#*ZtRm^b1XiBaI{J1Sn@@RbLBs?p&pVPjuU0IRR;y7?h zs0XoJ+R!%$+vf1(|NtAf6YV;s$#M~_u5pA3%#AX|29N`%Jb)?gCrMIjbVp0#V{+C5h1^7n{Q{8^c}kw?8*xM-tLdOi>f_QoB21^ z)^;)#B;NO4GeD7S67ZUv_-p?m>~+-rnjFuRu^#m*ry(*ORwuE^d%$MU?orpd!M4%3 ze-fJrnRyMo+0OUA_>`;G*5Y{5Rt> z-1WVZ&UC#fR>jzzhU$A%j<*0*W+b518ILT_afUcimv-n8->yk%U}`M$i!INca(@Sc zW-}MD2z{^QZQ<>5hVt&Z1i%2o@$tR?67O38e_VQ0Y05gPHts#fQj zi~CvYk%?XFO(%krX1|3j+#TT08SdL@KjDAICqd=@+xI< z#@`c`Hz?zZtA<{5C2C;l`N9)9%!3$8C6;ABaVm$X?cXFVd>!SFnm+$1qB8Nsb9%Nb zLb5z4k>7BRsx1 zL{>c}=uNnI5pI;LN=S87^_}6xOeKtWR8FdtKsk=ZrPABB*lNn=wQILrrcZ6@?sVfg zb&ZCxCHha#IJkObV&@L{!i{d|e*kRclpFh8^t1h z3z}P-6K+4+o^-x;sI?=uui`@nq)CI2d*oehm!ey_ke#rs9hAQmcSt9PXV(xKJ7%)F z*LMxakw?4;8bJDDP%*a71>){`D}mBHq$U(j7)!rR;)+W6ltNy-Ckqv$l|twWyXaA1 z{X4f@`6rX7s}Z~RQeRd1LMn-eg)7CzW%;Cz1q~D<7_5Gy^d$<<`GkF8*Tc*$YkE#^Q zO`0-#qA$N5Vf5Pfn!F(67P7)Rv1^G1zt)_wY$G}lQyh|)oPj{d9xh|X$NJ@%2MR&N zk30ta<8jw^QPd%W8AUTUfut&<*WoIeDs@S4h`rUyv+jW<7alVd`)1Zq~GXb@|%*_#3|DpE4<*Wte6M&sru8h@qB z*$b_FNwygGdsPfI!!Yd|$+p=K`gEr)$pse@u!mY%R*>zygfw9kCV21%w6vv*Wffp!fcI$3r~vFbpNB0#`> zX7DSiBOD!sl*I~_+M+eX&8)XSPa9A?Lu>hCONz34eb!}(bIden2LG9t6bb0K#T@(h zQdyje3F+}b2S|-=uztI%6ka>mHJYR$Ix?L8rxDBhwfcej#c$_YY$(6clC-t%ija(N zxDBjt*^}~~fA@+Mi#u>87vpp~D2qdQpa_44Chxan#Mhc{+l+Kf9xxw^6QvdWmxTfU zAGR-V(U*W4POG--w_bmny8Y&S%zho|zu4;hzYqT(eH(l*h$|kraj`bik_^x+d$@zO z`O}cc{B*^pApDIdiOZIY37JNnjdf)A8mR7oVTh>7kI*m;e-$0X{dMEnTbaCLpHC~6 zk?H3UTe2vU)Aq=;NQA2&*CBgv*M0P%Q0WkT}0e#Ax>}H^iwDmBy{0_ps?ZD;${+}R!>0EG zA#)z3l4(hG9vD`!Cr_|BJXw;*n}O2Hy)zmnJsEHZ0i!)(ZB8kj?Y9?pDl=~!dK8g& z6(km)&cijZ?w|A^c;*DDdilu%Zc8s26O%M;oy56~=Y?32k)8IK)BnS6T5 z4FZtL1ZQaQ#|A*)!jdz*)d4W?+!}==1z%Obs3p}mVx3`uK@7X=ZWg3x-_+q!ZdKLI z?F;*kBOZ~TP$R4}>DMCzTNDIj|2&>y8`p1U(S@_mwX(5o;vml<(Yb3k%*7 zPv%bQhuweTgK$TzY{uA~4~zp(6mlLvUW{Jg!Yjz4{ zg7rv?m2GJc@m-Onb{h@To6R;$<|v$bdi>SiMUS2(KSq;Eo?-2{4KQ`fM{`So zM`=@^5<_D^+r)!6a0c+eSZ*RfYrsJ8^})oIXb`B+aC@1b0D=xOfl#dIu5vxmPGswJUF9t{t4?TrGP1(XF z*a=<#WS{0`P&N^{B#aUd7zpMYm>VQk&?ncz=rX2b(6?GPZmZe;ZmWGLj0HS5G8>vN zN&kf~`U@enXpLs8c80+UK~(2nT-Q22xktiObn>n6g7i1c-i&93yh*BhZY{%&Pu6+M z7Wpo?=1Dm`l?aKKv%AUl)8u1@3;&ini~51hV!!n~D?fxGQiCp!l&n^y(GYz-^45G= z1SsW!q0Bs!9#n3zcs<=hSuzW$YP}Tb{ELUxbXwsmu3q!ovh=OvB3Q?1U4JPc^KYB# z|Nd~*{*p>@a~k_WBoEoeCN`i$`d& zbh|*m-3P$m|GU;dB3gu^m|}}Co`tOVwx0fSR%Oim64$#MJj{rv6>GQ& zglObnN;G+N6xq6Ot%XA1&NHNz+S)9@$lGcpU%EcEsxzSsf2;P8y-1f`4(jS{%y7uC zv*$*O#3}P5W$-wC*dAf2Wt}%K7OF?pSNC%`=taPD9XI^n8OYyx3!v6dQj|H?nvIs^ zIE+}{xWXiY38K*@8IxvSSL=m`TC#dG`yBu|PnUL$8;q^?#^-tDAC240t*epjI)w7S z8taB_zP#Pb)zV$vf%8N!-XpS#k$0Rf*Mo2!!JXfDypmD>8$O| zU$tq#=6FZlybl-NIJgoh@j1q8Z`*}F@PS&)PHcA6NI&VA-LxkD5?cgT#gWY`;JlPr zI)K}f+nqeSIhxbl$zC=j6&Ss9ZU@cz3Qz>FkO<41MTkO= zu!{gf3Q8*4`%W;gWO(}6mVHoE2!H&1J<%D_RM^E?Dp^wX;zrj2JSLV}fp2$Z zrv}~=OOuj4vQ7fC16A)ANqKLTCs)Q^XFMkGF>Pv96?~ApciAxI5m0CBc=J4IM|J{) z|Hze2tphG$02V>OzYuDGvX6RI@Q;~k%IgvfjvhMYnAOSU-w<2NVtVuxQg{~Fz8NG9 zPc8*r97hpw{d_uYs;sBlxtF2#KzP#1-4U;Bh}a@m2+oMNbS_V-pi;wLcdjD8Dd8)L z!?SsIz&~=$B-`!I-1psfZiv362$LniqWPjAE1b}%Wa4)Tigf}bOVM^s)mrxC^qsR|z z!TyF=-llvS)$W7L+FM&B-~`KXGhXD_oL=h+HPIaPI*un|wS%B?Lw#OwiAQdx*G#VG z4BYW>sC$;pK;{?1Hr(`mLa&vjbV9C(-eGjWxnzZG`8-nM+xoS0WtkxMv#E;bR6Q(J z&-T7Ha^1WpF*<<1ctpEKJ^B&js& zw1k#hWY=``d~||$;V0tuF3DkFh}Q+^>TgHk*T1DbYW`PmNT?i@#dvQ+y%7S~STHs# zP+7zfr=&YjxcFDKVyd7whJP(!8P{2gsgJK{iWLTAFDCnLq4u~%o>IS%wvh1|bQpF7 zlO@sM|7!)Y{NIAS>|#R0h>M~68zzZzn~tuHn!Xty*@#$Y$`|q-88OvQvKCeEh;AY1 zP$f#m-=zx*3JoC5>Lq>fiQ6A_vL15ekTt%4Mw=Bg+ltc@wLKfomBTmZ6B<&!0~;Uji5h-Dp2XH? zJmVN8zI8}B1p$;a_~8!s_w8`2rnU>O-G22W$pzhcM)w>i4X(kt{UDEqdScay`0QXm z?Z)-2x{8qtk+>i=0M@_|G@YIPv|pqYMc=*B((u+cTKVNvFyXOTI9XbdXd21>=}1!R|a`%8emkQdu?!TYQZ~IE`{U^@hYkt z=UsFC^SrK?F}ybkd^Mv@g%Y534LF__Ky|h=2H(dVp*yeM1!hty02MWX@^H2j^H^@O zMyv1r=4X?rZGuEOAbf_pvZH$C1qy|6=LF25pBJmXF`|DRQK347nZ)u7!9JPU zmSKBFE?$U{dv)m${%ti*PU6h&MAF1El)3f&Icw`ZJAKkYGSn3sFzNqp$-yvr`%^zO zn0>YEtOm2A`NBwB+{QP;Al#^f7%HSdsnVdCNU2%!@bEE0LM0TvboAJp&JeHEVTMG0R!GO zS>(3}AfR^sfcEsQIiQ7aFRSmpdMnn!{Tl`N%X}qR2MvkYSCzq~c7YS8W*8HB*La~( zcg+Eeb&VNnxNVmYXweiE`zAVm8+!; zr2~TPMEtkr9W;a*^N9}E4zV|E9ER7igqnntg(^24N6m!{ej)IC7O72^`5!e%8|)pT z^SbcBNUiNJct8M@3FFNoCPR3s4`dSex_#p{EB^P7cjF%JzN5_PjC?48{0R2Tw#!|e z!*52R!uPD`az+IQ7-Fpxo<}vl<9ppUDV`BU8<-rg`eWGdI~DXsNFcyuMvz%nFZLDw zlp!q-b`>(6vO|bR7J&RB8({c=^?SGCZySZJZ0D&Z##BaqYnWD*&DL3H1#20uq3;|~ zZ_qd1$uAPx>igtLFz)OZv1;3-3cyQ(bw#+S6)#i+kjM%Nh4%sdTal2g`*RV|v$olD zC#gq05vOx&2Vjn!0^D&$1E?H8cD6G~HS$+zIgE~g3nlYQfdz0zIljFll*v@|0lme^ zL+nSrJ@`(l34W%ZG{Hgp*ND&8qA^j*DloS%= zegj-~n>vD=wZ|3Dq;^??Q0G;qD6abz3F^!sO6FH~dd8>tE?3U!nT3 zc}oLGK^i>DXq&Nt&d^cUd(=f6SGvMD!QQ`{-so@<(U66){YPi=9@_>93$Lpe zg{{L{d5@Ct@MXgO?R9^%o{+UiM}D5sgwjoJU(T3Z=D24p!_x>Lwa{(O0uayILCwqnaC1V*oQBGM zk?o7W;?cy+#k(mCPLkNcU*_->I`CXJVb}zP0w~O6mMF>*1BW-8Qk201DZ7lg>)`e3 z#oRj%uw3w%qN@V_u%Tr=aTPKvi$loV-ou*(VSqBEE(XrYko^OZys6B+cd?#5i-UzH zUa`S#7fBA=eFZ(dq>$OTkkCYer>z>-eljxVxW8Smbt37$S>^Z6fF)kU!>^VxNY-OU zBh{u(2~gyb@8=f$*eAVCymTXdan=g2hJhNv-q~a~LBbCV_HIzY63LCL#GC2e(Gjfw z7KiTlYk$Wf(_eAO@C(88-*Kq*3n4=kF2c|biM<~X`TIJ1c;Tic84r1XJ4BXEaG8ol z3hz{_^&2h#B2o9@eDL_J+*94Bqli%omOgwDE6rVIUK6OFdkc$+QQeLcp0p~1kU{PD zEZhmg^^$;;HqA!BzjKO9o#KALMu_6i82!uSb(Aqbv-;_u{0enYFFgH`oeU~`GB zkhS(T>-fp%KI;!IY@>>TJmSW)cpeeGS+dpaHQoPl@13j1K|$?VEVU?JuCB)rqO3cT z>XJn~^aE-gTLU!CuQA6$xu$J17s?}5sd=IV}zIFkA2DGOmE5nvZc6JfP3Eq(Aj94reH(dS|Rh(!W* zweV|=%ZKzJ@`nQMgPgiOvbIeUUk+YrFMGSB4ffFF6b^3-TSzI#vDAe*Xb8W`D^kn< zsht}A@x9a>#4Fa{1w?14&=6xI@|V#P93u0FFLgoMoJ3&$PVfo8p|3pqG}5iYYux+u z=O`SiJdp;04$Ar-AiF&;Lw(%pPkNOtQ!wsN{Mgal!fc%l-0zVFKJYPD7MBnMQn*VN zCv=L|FW&w!gZZtRN=36ZZ#DVlRLW*-Uv|r4VvuXs9|bXP#cj4bRzoLS8Ss#BDcXh3 zj%Hgk{lhB|TY|dwXGzRT(lrPW4m9(e8}YcW3Al5B$Jih5Camo?X>|ohZUA z4r7?7lKy90EhU6^Q07r9Tl&EeC}Ixxs#1GYG<2%BtDZPpDEzG5J!%wWDxL$8CGU#R z7Oz`nV0J4H6%Wr)A%~clYDk70>@*fHk|FDJXW>Q20Z1%2ef&Ib2ou&gJl!mKLE6Q2 z;LYp*K-vzcJ=kACai#!R`s|vs7-lLa(+^uOZ3E2=ND&?;zGb?UFfd_GNzS1j(Irjz%}uQDV#In1? zYPmY7rhyq1eeHC;aqCV_RM%%dHfche_-CFSknh$CX+{d1oUt^_dD9`0mNjej^%2Y9 zLIotR(9fW_+|5U+n$4;K@_LrAB6-ftyvkB8819c$3ZsN%*fV>(Oxp^1M{y8M$u#IG z;at@ki$VejVA!w7Zb$mJrPyY*(d_^HGM?o%QCAF5fq7JZhHF?=FPb!BVpKMpbC#*K zX8ELTG()02?yuC>T-%Hn3mJ{ zsaNV)sfG?D4yF_DO=)KF!51e*YcB*ZVV=Rlp+}(_ueu2*&cYaG&Ha}f0pOi`*JM8m`%vz7+uw8_F=g=JWDLIFy$yUkFjIR} z76G0eIkG<1#XMU!paw*l>sjL-H$r5_LDhP!uT(vz0cl?v)?31LLTTAk4M~D>xPD-F zh>C^*NFXH*k0U~pE7D6-Ob@}43gqeLvqIwxA`@B>{_OOdvvcMSgBZPlxQdC+=Au1K zu`ozzKlS`f|GTk3=RtOs;fnw8F|Iddkum}3MZ8KGLWEi_>Ufdx^c45WiQs4OvS=hY zq`qiuoJ^y%34>rK7dyabiZ+sBVW9{V2RvKm9I6cDFLQI*akM;r-cSq?VvFUe6f0Y> z@bIMfM0ox}=XxL8~FR72u?zi%3yPxDi zi;jA`ftA3c_fct30n7h>bHJY-+Q;QdrsMaJ;i}1Xa!fII)gIQdWo-6NJUhHg-ljc8 z*!BHW6^b_%q(y1N{;}+~D&utw67^%ZhPV=ZLUrz3&TA#7k8=Bl-c3xBri@|OgRF10 zw0qtgC=d}3d4M+2i#t3a+~;sNy(~DK=u}ZzYNSyg!$N8j;PJ)WZFpw!6@ne+P$nw_ zbqkL}QAZgZ#TrAMh#xrr=v_8CZh~ya z=C^qL$8zP{Vz4WzOOmri7M4kjM(OjDSn4LTSTht1%zpC55M9u}-RS@}y$-)`=Mx;? zJ}s3LgT>x|Y6S0=N(Gx6{z9npl?$Sx65%|nm^9aq&+E$12Am)5!iB5Ag+S&nc6&2# zs5Z4qfS(@gZiaVPhT-)SXEwa5+Rfc*fu~^3YKq73#irIA_jx|Jx>H#|!lTTd=3~<# z-Pz!jCLFAeeaz2*E7mVum~VgkyI<+b+nX|fa1x2VpI`8OJPA?@*6Oea=fUvQ>q1w1?063U~K#e+ZMN6G|n0kQ4(R zgZp3};O%Tx<#*Qji2zbjXy_=*&LQ9iaC)epnwK(nfHvz>>>RW!sF1>0RbityKWj)Y z-x#s>Qmb}I_FBW7^L}4MAAXvujhD7qK(NDY5H^h-8#0+%sE`(e#FDw9TFI+ zK{*u;5dA7X7+?5fMz?Tq?r(Ik`^r6Rq2bJkE+@4D3c*UUTx}Q@xac1%^(c4*^Ja@> zRqti+DoVzuo{o7ga)R;!45Ue)>ynvrjoDyIq{Dh8(--PqIZR-8iY4bij zvzOd)iU5xqU$z-Rd^4a~4!;oYwD=kBL#Ij~ycYU5Ps?g<>nz|t4;4PI5 z_1+_*y7l3coOzSA2iX69TF5&f*n}6W3i-~jqi2K=s;AmVtTjQ=gx!ODEaapk}$4e$o?1ebBs@)Sd&iWqaw@M_< zb|Hi8e9ezerZlGsFR4?rSUx>-j_heSf$CVUi=D#-IEZp2fA+6>!b;&<907{2R8722 z_gwsCIv3#No?i$nq}1W^mYNcKr1nM#Bm1k`=|F7(=GFu*;iAn_tI`)qF-E&CGcP1P zjAdh~5$cZ+m#kiO{rtxFgDOQ@&vz5SOK658@p^msF(4v0#q1qFhg_KBn!tTlL&4>A zh+)Mr9>q!qhKfT(3O7dQjK46rn)}*+rvWDVl=8hX1?NkS9e`Ikhgw*fi5#I_A=jdr z8s1X{i|5T+`-dOl;OORc)sYfC5WSPIxxK!^z*#qp#eR?#AvHf+OWh zwJ*DpGL1_=>JXU&1|NKVAmvS{C!{XcyzGyD>psseP2Hg;-_3sIrlB;rvW657J~5_} z&Hii1vTLXDVD$RKD0gCsq|jsT{n#z-=J%WEOb}tc5&UaryaR+5O8-J& z;;z~7gs)wUU-7{UhzVd}%!?a2humSwn#cRel{5hS)EoO7_Pm_r^j=i)$T6~6s-MxD zg>W|ujy2!lDvm%@Hq3hBJQnA5=8)sRYUsD&%#_x5WN7Q}jCj{p4zi-g1PYCc+wBMx zbnVSe`JQvauYu2j@I8U~r{&-QJGmevU#;BBVMpFu$iAe}#-73ccaOsJffpA@!U&Lp z&QGlHQuym~Nf#Xm9#GJ>vbUZfCz&8y6VCc#1|CZ zuNT2xHhd0t)9NzXMc*@d#8{WNiv!!~hIuUxbxLCWkvs16b$)Mcu33a`@g|2$=pCGx zz#ZBE02Ud%SS1DA-222VM@=`drK%xjUdkFE1AeHJ%aKPrc@4!U;#A_&WS0}ei2LUc zvaD06hVGc+I#c_tOLPY@Xl4!?cHccklYQxN{TXLGp+cC$W*Bs3PSVmI?RIj0-%yS- z#+D9f8D)-Q=%IZ|b5!FrrWNd>;fr^8o1zd z&T6>I-RAfOyujXoQvz8`8~3x#x2qsa9r7%5es;Kpy4BE%{Z{t%SrIePPg6#HavHUT3;5sn;&`a`a=yo8t@kSb;4DF54s6STpKy zyjKUOTD<&1x3}vsj??dYqag-L2cU;q9DPc`mdm1}{hEOIem@G(hUX1_M^qS^6SI z*)GXz0o+eb3@HpQCaxm6Ou`~f)TEiJl53lGYk(E-&L)ZjN40?l85%{r(_o-T-i?RB zf0Q(j{?tBDif_xBMs4C9Hh$XcC__Zdx6~D2p?eNNL4mhN6&npi`WmOa@Rl@v< zs?uKFdNS|OD=|UgVrXKE{B51>uadfNyeB&CIJ;BHb<@U^rlj{dEWZi*0gqKFRB(>$ zT6j9r_j#R?z_CH)W`^0s+{L=oqIj-j(Oi0yEAP`Tmyjpz+`>y?a zOO2yqZ=Ux1Q%&t5mX%9nFvd-kZMe!=shxdc6ix!&XK2lorS010S-q_GbH3mm|EHEl z`X~(R$nNjSbz)}~p4m$$QZ@>~))XwGkgT;pm&yq`CsHBFXT6~&c}P#t6x`Eglj#GZ zUwb7(h3=p83X=@8%vl7rhJZT!4*Kz;ctG#^<7 z8%o~hfIP!}Tm47n3YF+VT&#Qwnjocu53GeDp#EEBSly+Q)b<1UuB5U!)y-QcNqyct zAZJk!z3Djc+)jjUuNyv^i_e!Vd(6JSGv>WDoa`EhvzZzK$Zo;AK-t6s$*q}>_w^Sm z7m0aY>@j?m7O59MW|uvZ)-~H#j5=E;rKc*--A9#WzYgFdeOH?*U>uHbfwWP7jDe8u zqDB#yUbyalRa`k$XK7fBOUQ~0I|!;^Lm*vtY0b=K&-C^yE<352cym}6ow4);O{>oH zRceOcwtxtFOq;V614Z1ttb_LVXb%U6qjvw@VoRN8aHEfi zuEU0V1;LpUo6tKLrM{sq$=s3o5BM(d-(JP-RJ(W3aF z>B2{2`1Q=kvJVcMH*YUw_tUJ26Cd+}y+1Cim^kT+l;+Q79pDfynlH^amx#yOxHxHx zpEnm7Ialqt*6d4h%oyGaZ52ctWq1+lUt1ZAltfR5AUKTfhG6wfy8Vf=LL~zOOzve} zQBA0Tb_*NuHzf=Fh7*)%(b6^a>x{wrjzt6{{rKBlc=s~-gH%F?E{uCWyswXOZhB0e z+^afWhOD)xr1aizwQO4UZ6?h;NJNqiE!p2;@u1C)d-MArU$Iph0m=^*^f+ZKWL7ZG z80E~t5MBZc9}s5bYCZ9rwsB7d8zJF4K}S3b!UG#UyO2zDNG5xfXGdyXuR+0E^xIYh zJ*j-eXTiuTk6IYi;oibu`*kJb6KF6c-3bN;?t!>ruKOv`)!4CT*ylo@NGc6QBemA3 zYm+Wu%I%tt3=U3jZNkqMG`LKTDz0Zul1c^hcCoLcGh;p=wr5=Z!X2e&Z3)*iacZ_m z8!W5QU+nl|<;n#>ga!oJRAC*dVn4=`HSQ0Oat=bHd%yplJwzOZG_DupBHQ4tAA>zw zC1h$R+uE+v8b@sOQYO$T%XRl%%Z_w|_#P8B@Qy))u}5(Rh@KmnQJP z@O*#&o1J)OUJ}amJ*qF&IFSAY109l2C~AqGbEorPQ+`3EHpL(7N>=uV-)oL%3mKg+PGhF^ zAuI!YdJndetDu>BHUR$4qz3gD!t_*&cp~e<9#@^Cov|*;-0SeV1F+)u7a$`F9d0uJkN_J zPOBNxjr5p}rQ+95treet_vSO7iA?jd7D%47SflZ!TNhAb zMeH6j|86nAR^m)htxki=l4AZ~i(X2Ufes$f`dpU*R;wRk+daxERFG{_%cEGLk~jWf zC`?S3k`4{Zpivw}L48jQ+Fx7`>D9Slv&?dwd;js-ed}A1Jnr{;!#Bo_PrcydtkqgW zdFB7PMxrK&o}8>0aVQS>&3wvx$gt16v19&0OnmRYXExt=Q$ zWBh!_+%n0_&zV9fl`>By90dO1U~bNVqx>o5ha)r)u3zl=A=+oivK;vRfSXRkX~2KA z@^B;v3_~^&rgVflP&!{)Fw9nGQ2qqng{JLKJ)7>Vb}T`&B4|o|^}NKc#J;o_gUYnS z@xg|6#JnDwE|E=n^eS3K23oqCO?&Ou8Cg*YLFgOk&7zOFZ3~43&hoFihEU*CE%Y^~^|{R3{#WYXnA3MC zaV{Nf`|R+!c+z3!`+qh$=n*g<^~ICt_&9gY8G@ZJ(lcv&O!P>**|3b4x6k;&pL2ID zdD25Q6y}7t*(xrnEKqY)3EirdN2P^F37&JAh_Y_%&e(^~3D4}?&v(;9MJ2p#p2F68 z9lX>w_2SfgW@7`@9$~Er_U=R*cqg@&D$<(FrbZWb_d*5Uf5CYF2w3~2b*{|?nj<#m zQ*3hzR~e}Hl;)!BBw+W+byZVyxtos6X*1#*3{W&VIVM3ZmBdithZm7U#h+_{73#{= z5{4D#C*n0oBdh$K+3#J`c4Oq>tWG^TXxR}_O*Cop^ztw2@Wh!j z3?nT&vo=oeZv$Ae!-a_R8aAKx~TazwZr#!xiO?nicYcIdeE(v`Rex{8F|e=kj{t%*`9F`K5OBW zy7=dF_z(=jVxu-u2|UCgUpE)O53;%dXGA zmoHowzyvF(X!{8g-T>ftMXmB-%z@=!@c(3`?{%z`1613>YmsZDS^`vEkY;ZSc*YED z!^sUHl9gjm4w4Co4t7U!a@7Qjf#|FmCX{!pj-vMB>-rWSpEdj1rr^%%d<%A9@KUKE z%&d3*_!8U!TdU<}4{W?Y=}l2#@B9XU-#5e389?qjc3brr#bZ>-X?*jDnnL7BTafpF5)C=2_;%{jw0}Z!LU*EbtQ!niN@h0luHFDFLcn zUCK|msSYY-pJd>{vnQ7zv~AkCf{b3|la#cds#(izAUo@zu*vcJ-z2P-evkWlDBh|O zH58!c`2GcI3xo++%MZEepug2MP@&mt?;n%z&1GgTADQ?AsQEvW&ASJ02lLVyYqb}2 zd%0K5DehZa;x`Y13Ct%H2}Cbwj^=t^eL$B2LfIV(DoQ9t&-juYN_Rf&y@zH!M&ZAm5( znSSAP#y(#hd|+*J6rG91=cKeO*eVXN6QgE?5ZU(y*_=U zCeRKm5a6!QH#W(|Z*`DIBeG09R3q`m8OV?36#rHNo^gw%HSp<5_j^B>%|PO-%|2K# zaP(6jt&1*yis4yI-+WcdR7T*lxaDt#`@U2Ym)eY4LG_7RHHgqO@kb`hvW7&bIIUbF zziFXWJOh({B{lzVGc`p9ix7Xgdh=0$Ot3WZyE6_~AL?5Hk-txbX0tnzhKu~a%%<}m zr%Sa3p&GMz$DLiGfSBi!Uo+S0?0;X9B%EV}zHwBnQTJmRB9{F)ZLP8M3}vgthyHl9 zy-vBOn~>4DYL?_eIs8=1ujHBQcf=p-q0)gA4_4^U$iwu%r&V*_n)o0C(R+l#pG2GO zU#p+oglQn87d@)QBH8HW^&-k!zT%RF$EEvHX*krx(`0~H8HF1_&hmRmZGXWBs=ot} zs>HxF2c!Eqq;kaI+>mP8k0gG^WT5wMowrX`iYh!*J04EHaISKKrHCW;gpvvxj*OeO z;b;~Ra3&Jv*W|gGU-qk1r37jC&JLdB?t(314U09WD~?&QY2I`k6RH|V<4Kz5#Oh9m zubirC4blonRmfbHxLSqiE(!bwNIpkqv}%+d4IXnMH<%TU=D+LzwUX->{8;?v#FyRv zW)^09GvuP^&7T*yq>E+;ygU%u8 z)=la=(t?ZjZ}mm!nQh;-r&nhbpWr_ktZ`uz-9zdi@A=sZPOn()J?wqalvPL;BbPt0 zZZC+nKYUk?aBuwH;?#7{Ik_VH7tFlXZ99o7QLw=w>({W28*bW}dYbT#16$ii3nns3_|>{O{h5m9G3=Cq9&JC?paEuy
+p0`Sy zggL53i5d&Ph+9)^{0*bi2muq$XTJVPwzOAf$U7vPn~KFcMeYViv(${&_q^k3)0}Zz zz5zsqoAJ7DBHdUnF1SvRWlGricvR)rK|)mW>?DTt91sI05V7+Ez8}9lp)A*$dOhlZ zMhVxitSabfEz5%`L0@0U_q)(76o{_<{;nqbVQ$Bel|AU3P1I#B3 z^(?Or4|Zox3|6Z*f(~r~0^uK1JQ#`3^eP-xDtiXY{%J0Kw)dC&P+MB4j3#i?qZ*ZH zLst3rF0HHnm-&QA2Mx7M8o}SI+%Z<<|5kZT@`2KT2y%A;{+5(!6GYOYBa*eg#;I{a zj&lmxIFS~#kj`?yM27M-xt|l+qsEzT>&Eq(>j8kvL^D?K$RB}K`N|$H?TVy@{x&5! z!V=_)`K~Q8DZm}HDLqBIyqpda$%4)>P%}^Fe}HN-((AuqdW4V}lZ__IL?Uwu`xD%l zaU%;QGqMc!NimxqKg%mcu?Q8uy(%~3iH+?hZK3=>1 z@t+=U7e(QC1=<;(3Yaf2Oc##u5kQ~uEcv_-D=p@8%iJX%leXW@C#e5E208vHj{m+> z(LOI$OAkeorBz;oE{MBmp&uexN2&SwXuBC-;6Ke38@yr!_`9g}&cz{5OlQMJgis}h zeKk)cpr!L#(L+mjoCUH6_*Jo7-29f=ymjgBPVT)6uHr$iN^;BQNaM(*i|~bhkzs}I zX*3Wsx}QQ)M37>GO9X^MTrRp+`!iEAweXSmoris`ag;cMw=xw3!1^jTD9UaQtfAon zo=W#``}(0w+TkO-Xk{ZR!CFa1Wq1e-J3SH5YI!>Nl2xz3SL!2#!48n&clP+i7_3nr z%*sg2c^0Y4B+%m<+rDjI?yv0ZxaN(vKunF>A-s+rw85PZ+O<@o@lqS{c6-d=mY0xqBWo7)>u39ml-~ORbQ~?zKbVNHRP3bdhHcZ+Q$)9>92IvM*sx=)^uSy++ zs-y+>*RGIA-E9zgm@29%WLe%&B-lpY>=zsww0qq-wfh(+CX5?8`U95pEDxK0IssPS zzmk6bUW1WbO+iUC!&v`xLZ;OoSb|^P`=iW9>F_ez2+Xy?mpZ%PCnNIog}Qha5|2+3k_$2$H423s?p6LRRAqa7 z;in)Yd(K_xoi~FDGI&0hg=NhZ-Z%>dlCGMCKgK6;K756u-cTjs$MpX=Xo#;Pn?LvH z^xW+=ejSz4+4g!C`f{WXx79}U-*u2fV2y;8GAoHDps)1Fz6c=Ahe zNPZ>Y94%u!6PCc@!)#C`b0gR6lBF=to`a848swlbsNRS)83JZH#Wh<~P?S*#X{thC z%a-)@tkHNgF(Z8`!$|_fn|5P}!T$?JDKtGkzjvutMIo;F4#<)VAj^<9#ux(}a%l;- zi5kNeH1dX2-d}*1~dy?Db>*L5?P~TmKQa1b*kvi5ht=$mhJxrWQ(h zrTV1yd4?i?(N0jFyJBZAiPK2@jDn39D&{n~E4d!$O+b9sQm;04ulZnJ^Y0xjFrOUb z7B_@;&7Avx#&e?Gj)iR!MXswUZpjS=BbZAYmNu2B2fp2N7ukw|FMFtW-r&f%!g~QS z{oep~+Cx3Z3``ak4Gs@$h-_?V*k3Tj?Q`FLXez*&rvDU=oFI{H51}hD$7Ca6iDT`0 z&x_rcM%EHhgmEM_5k4AR|KJVHUO3(V3&zD;@D2W1tk38iE@(rV^$Tb&obQ0IZE8I z@>L)s=lC@q23greMdgL##SgIr8kD2&6|N*nOkS-YFxA@QK7THDJjQJqRTsBiZZq;W zJD8ejmz^OlQA}3dgPU=W>YQc`O{DTd0ELL0TgtlNqlEktXG_SO0E@2CJGp3R@@_x{M$2{wH|i~Nx+&-ngA zZRF8$y7|^#2wwc+_PH#*^y9bqlbLGfS@TRt*7Mmq{rBGwb50O>GtTFA-yDtz`|7kq zWH+cGFT48U{3Y$`>c}9L#N%$hTW(TMwJ>Aa%F(CjByym?byenKdZ};GmX;(~i7!B2 z&nO7E$xS^YN3oa+SLw>oKrtYI{FL4#Dr0b=`K7?$IKZSh4cT@oY?FqTkE)oNm6=A7 z>mj%k4&4k!z+h7_lwU|I)UGo^rv--#mM5V*V&e|oiOjaG`+;>ASOm$%aw{{f?N-&X zG>iXisM!o2t6JVe2bb#01b~`TdvW0`EhVfFa?9se9eB%amhA)W|1a+Q_ItvFv!8lu z8so2Jk8a$%nt6Bm4uf|Z<83pSG0U9vPZwNj{a5$VCyI*H?^sORJ9hxWpPIP(T^D$~ zbu5Qa9+LNPGJlwoNtihi(hJMT&X8b z%a*9t)Ql=g1m!GqcF8w~$4;ge*RpP$JnC-m)DpZaCdn%oSp>Q#m>!tj?J5v7UGzYo z#_^Q)sX=XkpS-=FmuOK3->sUH1Ic3$+i$_=>2fBu-5&^l|4de50&lEeD_C#3rq3}b#ym>7l~XZjm^O-II3RZFjX8j@slk z84R6Qv|s5v6KGH87LCv-q9uf%*)}iVi#a`0U`tjDfD>c_=~GAw;X}G}<;)yHLq{Ey zDbSA3wLz~bjnqi~6+HXc^cM_Tv5#P*Qy_8rZqGOych(xmyTxJGF%{9Su@D>QC++Ub z9AystmFvs^er;dEFZ7(8rc(5HxwJ<kqazC1A&_=Br>{ErFq`U{Fd6 z&dbWpmqo=orgFOXyP`NB8k(AtShuJ-;pS*^A*l*prppb?XyWB+S^#CVKY{L2jO-GJ z*iN7%I^Ny3B?Hjtb7$rgUJ8Z%=>QwIwsEfLyKahwwNHT6mns7s6G;PFYjsvj6E;n6 zKNh74;Dfza+HJvA9GV4f&D)^(d}Cfqs|y8X5`Fsip-DwfA3VRrwIt(Dn=#+YTw(Ls zt7ZF1eA;GxI+l!RGmfq)bAEko3U11E?(`bTW;ATd8K=LC)Ow=h=>*%w0totnM@)o6 zh6ZrlJVW57poG|9{hlyd)5`6=ES~ShG=!RVE}&oO8Br4+Ak#C;gdXB4!$d=(h_t({ z05*NJJHkDJ_7B`{UAwOvuGJf1IMi>&b%;=$-T8g;dy?*r>XE3`cWMYu@&|_`2s7Wo zEc1)a`_DnY4=^mIQn)X~M#gA8YozwY779O;a6L;dz>Mf1kkK8C zVBNv_my9_k6HswfE9UUirG9OS5BKA6RRy}RY|0fH*!ofaoT-@huv^g zF%(1QXmjJN+ht6GFmkt+`}S~G69*}x!iG3v4{oV@m;AEgVT{5;=~m39kjuJY zm<>F$RLUMl3p0wknpgN&!D)|pb8r)Wi*Rv&$6_96MsKEbXRB4E(uVV2cIT9H!Tn3q zWO;i*non2z=k(QSZLZuI0c#6}NAo^VvKMh*J&48_N-{->TKY{GjQkuu(*}IR=UyCN zSFWox9MSvQnh_UlNLl=o3?C6crnRvmH$UiI5~5i7Rutdp>Kq<*aE+jAsZu|OvI|!0 z?OP^Uam<@2ko85j)mrzo|ASnT|8JqnCih0K+2nbxdTrlzxCJ@{>FZ&6g^TXXWSeX* zwpw!&>4i+u+8z^_S`{RdxZHYH&w5y7S`5)=D%OR9NW?Kd%%RB0h-ehq2betx!fnct zG`=)=7+EomE`fBh6Hiu_rFPgiZN6`Or;U1?U5}utupBE*YUt>JBHaTeBv_rv^WJL~ zuwqJ{f)m}^d>wpp`EzK=sWoWEn?-hoBRu8>$V=k5IaM7%x73Dc#iAztyfzB^oXj7;28uKshX|em_8M6fyGn&R*$n)H3@o z7|VFa-d%L!=#i`Le3#fj(`7;NKPj}oU~aO5B9+MIb{sL9+ct1$F`njq?DV`{Y<^uh zr0?-5e7{HBVeP{cHJPG)X8*|EJ~I1luH-(~T?OKPnEuO3Zbpmt#os5@}897B)mhp8FA}8=I!1j-McL;B* znv>@nL1^&eUG;R6hmsx(sYad`|Sct6e=w5JCm(b3z5&Pni<`YgtZ~*C5ceOilqX2Put9H}s9)^hOeZ(blXiLB0m7S%{D!+bZ?lbVP|E)10 zxY!M3AT+FydCt=F96Z0`G<$3Av}7uJ4fb`T{W0eOkQr-$)C!{uG0(nPHn&Ea(g@i! z)?saNcKE#Se%FQGAIy1Uql~q>zV!UEoEAKixSeO3(g@lBGdb`I(kqwBE!F_g+bkp~ z7y(eQO!JF;){GM`wVNgICCn(w(3R~=>+QJ6+PwR3c6J^9G-2MMj_YJI$n@SuVVSl< zHt8F*4^;-a`)VPr*y@et^!s$6@=0o8A2q|8nW2r`M&!G18={GN@y+JL+iAlINDp{H zBjB)i-K8ujA=p|#^vRYIrzu#rL3d7#hK(rQPXW8SsWRhCUz7+mqk|m_#+8jXXe>bn zC?1?aU80xQSU3i7^^%Q>$ngdM90CSGjxjlUP*b*Bl_^Uz2uP@H?4!>%CDD<9Q8Jpo z4(OglG%WQ0X4TArm{`n!a2pUmq$t0@R}efqIVay@f}4;5w)#rGY;U!^AZyPa4bHeE z_#(cF9?xnpUF;Q)-1U)V|4g`Y6WUPgOzcIbiI*U=|I(Qa1+~PML6+td|EAq0l)~QN z%j6X+5DFGhI}iBGVPSj6C4W#F5RPhOH4`z_zrfThYSJMsMFPL7dTbh9;I&v;Wa4Um zP(hfh?!)ulA@1y5T>B)4drp82Rpf3iE}8-b|C2SMa!q1}Qx_ebT4oZqCxte^wK&P> zF&f$+y|$N1j}m}}^A`-Rnoc!PEO;dhc?50M2^Lk)2%*1q_a+e;(k13sGD;a0mIt+~otLq-3Rv_>JB$Jq=D^UHRV zv*^=0Rgc6Io8p?8h2LaS1Dq`!;@L^pL=vO{w_>mco?Klx>cL@uatN-OxyxjDzZmnr z_l~oxu&2I-h_$=bMUm=>wfW!8-{9rldMJL)ZR5rWCDkaQDs1tosxzW>u~XAFgnLc6 z`mr|gdThkNmub7h_GAl#UD(py80cdho{ZS8JuD+yAVdxro!j}|N-Sf`2bAEwMOkN^ zV2nkNm0DujEmg&CAKU!FBUAbi@x_pu->&>2#pm1A&=&}B{nN?Z0nDV@s*cSG&%vM) zc^LU-evg}bu?##{HSEOe-WWg`ucJj84*zcJB3_gkYVsi}-AK(HigcbY7<(MoDsj<& z?3Z%QQ`#Z$H}`ZHl)`Sr!AaxQSi8z zoTdSRq~pojrd@q#LQPL8Qw#iS%=zZg+2Q_S_Giihw2=T)q z;QyySDfGUln3&v;=lY?CT2kyNly8e|LqK}`h70!@nH%fu?DMN)+Y0WS`96COG*3zTvN*#R>B{GH{JOrQXLnAfTM6oqpg;pS^UL{{B8CN&WrIE9CBkSw9YqbZy!5XFJRyBb^kxdh+%dAiC1ymw&E~!jW z!nRPp?C6;)0l%ZT!K{+-8n3uaIENL&cUp>v@PVVjg#!L!(X=R7tTki@y(k2OL*^|x zH5_U)Z(ljTmg-N60z%g~bh>8yB+Q4bNHlis@GQIljnO0F{!Ue3VMjj!H7{mgLas(v zz0aH_{z7PVn3gl8k$F=b#-Qh8#}83CH0nM%PHsy5VR$EIc%^ccM)@jNAMA-hZ-uto zR?eZ-3c%yw^U6xCYedz(QF^7FbW;;VZR(=#qUel!ILCQVYP~qj=Nch3G0ow)IMJ2! z7bm51ezQhjrm)Yu51JMw%xD}U-N95mHs*YqXS6lBD!MVF`)5>__^X#Xi0)B4RKh+~ zOkx+}c1?YDs_yigXS=EXku(WrRN-5uUp>Z8lRUrYvNTD+d*iHI&AI#P0o&y@$>-MlBf_L?J z*gl_I!H$FvW_D%j1kr>Ii_vB*m|$!eb74r1tP@kcA}z0$SH4-%JM`2EU0OAJhMh!6}T+oGc;Q%`1miqKHp)% zq~7Z47$t`7d-``@+k#hiqpsqqpHpMJ)^sKj^f-EU%Bd8;8z$MxD?5LDw)ah-5_hb5 z7ym0@ktSNg}qA{+S14-)uW0%(03tp_Vk8`{;jltBL_Mx)RpjO-UQwG#fR1& z#mdnz!Z9vutamKuAF?JeC*_1wtv$G-cBvhNZB--C93}LIPPBN0T5971u{4o&x>N0_ z?b%D#5yaP4L)ynLNaOQd_j1{3)PCq!t8Et3A79c)?A^PXnuV)oaM&n(wLf&rU>vOR zsx~@X5fULgWrR^~>hW2{bh?5afb34bMQ_#AIiD`n@xP;OZrS+aSm*2ba9Lh;qxoeJ z4OtJCu3+i3Q`~+>6M?VeIld!Uw_wT{YvALi+Z7_|>f4Ts)*u z(FS*2SvfnGShC^;BIDMg(FdxCpG_m82tzv6at*(XtHQhsqDyVhPTi0PWJF@&P97ei zlQ;kxBfIM{7oxYOk}~m8+7OJ3q%UpX*QiI5~PbhmJBPQ2UX<*Vy z8*^N)1F5Z%;e9!G^UsX%W!rO*FC=Sgt1GitcDNOXZje}Sr7xWwUXVKFZFX+*9V<}H znB{IYIc@q8P}3ArS(}|)nE`LW@x&wZZI_(o@^yAU@vW6?&-B{l5Qo2BiM9!H@b4jQ zE?PO@%4kV;ma8qoxI(A;FByTT4(U#n#b&Y z9{F=;z~FJ1eJcVMrnFYBF+;$1pb2A|D~h7S2`!*Tj0dh8I3cpB1HLpc+-_~f_|^1n zBaMO#nsY%OpV#w07T6{QE7A3S;LGt6H@x7(2_^VWPGzDmIi-ZfKy`b{N*}-!B{3;xkVdfv?^Z-eI*4koUpv~N z31-RM#2jGKHC=72_43ji#fGVt9hdrHwwX1)DuPwlNqCYzitN+~$2I-U73)dO8;w+j zFj4k$7=OZ3=6wS#A-r(1N@1HuSU84h#QRnb0tXh=yaqTyHs(XPuN2ErlBNl zu4T(>B*vjUNVKFyrUnHYF^tgx9k7yt5%zh77f- zV|5c8PpsJ7rAZTRT+m{&=unuyljYU^a4(!cRe~clYw8apNp@UryLA@AQNv7rfYvivt)o)4u9uYv_t5Wm0n ziRz{G3+0g9g>WoBGqcr+CwkoFJjD4FuVG$(!2Uq#8qvXT=NH61t@upy8RYw+x(e z$^5FhCWd#wVTwWEe&GdG(Al6;H4}*wHFl=*VnrX0bCG{DJ?~7$eQ|)>EO)gnu=D(x zUq7jDOCQ z0nTrK3q)FBU_}a7k$oPuJMIDf(=Ml&1BLXWf6|5!ZXLB|lh-Z-k0C=80nd6L_Zg(RU8!8sARBlM8HFX+jxIjvR{q z`G4JpBV>^a>xif9?zss@AeoKF&U z3l@AOoqT>|FLzFXJMhA=jPx8c4I2@;i4B8|jF|fVZ$1!NJVs*?6~a+&b-v-u4MM}P zGss%{=mf|x9Z41&8gnOFeCa@HU_Q%8$BG)=!^YRk<{INm92L^fBpficpT-L-`n~dGl07z7ATgIY&3bTUJW* zc}U6n?-2MGOoGaQtU82E%t|y&K5w@NZGhvPXU=0Zakq-I#4B5w(xw^SEV>$E#fOW4 z^!`{|`ON!GGJ;nw|`|Urv3>#P%p_I)n6Dn0^)6m|@&H#!oPF>D{$zH*CCctJv;v+_U1t!@$;s<=iWYJE;W{s-*H(9|zT12ec zE_)9Yl}?hFNHUcFJ%ZhW=$NcPx?ilxe-$imqxI?#Fj6qXz@XH60y#y1_8O+&=)-UKL^8_X3MpgB(Z;Z;%Hkn$1Zd=RJjq6|nk zdJ(`cZGUX%iVggJ2xHOeN|`%=8JDIUdhE+DvDJHLFsA||*(fJSi2_@O{LM{|?`C%T zX>`L5+NXNEmN5Q%;Dbp;{ZV~;ph|v!GECR%dw4w!3O3Gp+?zw=F+3v?zO}&#QH;st z>UFZQluaz#R0fK8ai1M?FV(6D#WFU5W|f}15FR(PK5xTkEn(RQnBRivr`e-POuj(fg{ zE;+k1VRXyWuKtwmMvQkvk-1f_X^v^L%n;UZKJBwpTcdW8};{-vwe;hlCJ1xQMx2+ z$=vf=_^heDR%<##F4^q?UjG8hUiC;d_K{8XiB|=VRkt)^aMUpRQZ_VB#3nZ_{&}g_3<6)I}F7x~j(l za@g43bjgqfdfcXixDCMt(Ju*Y$h07Ob^N8;h*x zN9eA5o$VYts4qkOMMH2xhdm*BYKbZ?Ms(6SZTieIXhVy$#iDqf?oGMzx12?4k|bw} z%}QiMHuXZ5{_8isqQ_&vAB#gDGFFxk*~5%?B>j@DN`u9Lv}A?6_a_SteSm^%v{?;L zPb+lqtj(aphH-s(Ad`MnmSBpD%oK;$-jGvpm|m00XJ$_9F!Zc-iZ8wr%5}Ep&XR5% zw3m)}w8KEE*kDTUN{0WeV~t>;IZzlMot_p(_GX)j zulfF_mn|g2L|)~8P^Z06qur|NHGkwb3bV3ar-anB zrJm6#xk^g0-_w}euG)dMow}`39Ua#~Yg40KE6lW*vEQ&7?m8C{X<@6}Tbqki@s)TC zVYV;i{`lS|=yKGMCGh}dmYR1^UKc(2pJ|{{$K~B5WP8rKDEO+-P z4Wo(+(W3EeKKiNrO(!(FBO8mH0trt&*2a(~of78bnl4@kCp~!AIM)IKlhxT3eC@#e z_5_uR4P+J9$i<#X$%K{||DO&^L|avPIK6dn)r@Al%PM~6FFF??QJ>;%z+d#>f$=|{ zO>C#-Fw7{gk;1py#sDK+ndbxR)bd6arS$vXrc*6r$YbelBD@>MV9)FABWOF0C&rUe z!R{F9Br>b`mIt0bjo)ZqRr|K}9C6g8tZ-X14cEecs5ArGrhB7+^EOjWThtYv&Sw!m zRq)=G>Bz?U1wgAHmvrV9#DuH zeO$%pM+S2?nSVB7+sKT>PxAU#f+3nPq)VWjBb((1?r=667W>*d+u(^m2h1D<&PfUg zf@KLf671G){EY$;(V_l_Xogs}5^)?%Jkrs!=A3LLA9t@I>+eGJcKWJW3$N_2{k#qnx0v$>@Kd~B9 zv6i}!qJ8xx{@To&sgKL&-cOXYl6oFMAYpQ+p^Jq6IK;ZthoP~inzOCYqV-a zm$9q*QjK|*vOAGp>nnGLgJ-+NZl`xzw zCa&xGvQWEdMA^AM8KzWTYVIP-B&+Ycv(ErD@Fh+YIyv!%WDG(m<3vQ_w2hxcvtoxF z5?6-Ouy?xn91b8$6nmn{9CG&eART0WNjR}VFu$^KV0El=8O5m5-Ht}3a2P4+R`%-4^TbamSYUUQ;jAQWiary7>%|K)0T7$y;WkXVc(=SqIvk91L>h8}6f9tOF* zTebRuF%dR){$PZS{zl4@ww^{g*J+eWD&T;$!tBTkx9f6bLgQ znl5E183&R$?Hx*O^Fm+!ma9c|D3KFGti}Qw$9Z--^p7ZkP^|fy9McY!orQnV)X*$x zc!Le(i*utN80w)#^(bN=*ryO)9sLU?%}wmQ8xCAGi)ySDgy~b+$tb#w&(NHguzPpu ze&(JhH^M$BJM)x>QIn*u$3iESq7mL(k4_+d=`M6N=kSEUk{xzvy(SUluj30=%A5n)AK{_I4z8Jtm(M5)>qprGK zjX~Jsv@dvAfr_mLZ4)sYN})q6ZFLl5>jj$V@D@?c!*pu6zX&OsuaOLBD2xQV#+~+C zXYuE+nbMPqgyXtLT=X~VG-*`(2UUmFAyiW2l40_8)#k+hYmK{-PUR9^yRbcfD_W7E7#< zOj^ErC&i^h$81M|rVR#FJ2k;}J*%xGENtO~&vExh`q0?qCGIK}QeL+YG}SA#ja+)a z4KI9+B|YB z<5q?X>tLAdbUf@&cEaxWmCr1%-JX?(_oyxx(%RI8AGvP3>+;LoaGKKZvSiKw)u*=h zPxz>WBgUyvRVmgBdM#3-sifz zrx(LnQibMCy%044htWNC*6m4WpR%)rr1r2ps3`$=E`98q9gMk7)%gOx(xOe@ZvX?- zh23qGUA~~6V`h9Y8nid&onq#3d};g~H238PbH_^?t<@^ChV(+)TI z4~>ncQds8~8!MxnA010JZR=$~TYlJ^PpfCk?Tp9gUn{N(E;Wm-I(vNs@67&ylXex( zZO#!hxk-YoTm`FmUHgN!Oawg?XPjQJ>COQCta^zS_jizIgmW|C@-J!!lM9#p)Q#*g zXKgf#t)j;MckMPa8#bNrS^g!F4x!tCqX0UfpQVkLplmu-D<@v3{NVVzw`~m=5;=oY zxZE-rKi#-(H=;Yq*0JZWZClLB{^?O%K3sU)0+_>0D*P_q+5+EK(M}K$iI70n7#M8e zY#R+8@GM%gqo8Bb@GKGQ#Q1)h4!8K*t3AP&lgH{FL#wr2eoPEjBaNxs)h64)Aq~MU zF|G_f2*cvo8nMN-XC1H2FKpDlfjqH8{z7ESGX$69ARIWgY@U~wL$*L91_r~sJew?4 zA`0gr2QWS}|$6Aywk^qVFMB(v`Myii16b7rEZY2yWPguKp}yTsHV#P45!C z0+4NraTpt(3XNVznv0NV93AImdB|GAFq(MZ?RC3BvrO)6oC^+7ok90XX<@^}JlZ=b zTF=3jjG|^THa97q%BO$#>E`ZSpY|sp3e@O|1joD4z4z;BaF!|;iK?)5R+pNaIbEDy zc&_6KI2GN;Qjv4VTx3YtvtXlKp;+Sy95oN-7Y(Vm>9T&>0AU56*#*PVhQv8ofPcD- zObp#S%c!`%^!K%5V0J}qyktPT3ARZ%zh`9sE6W|~L`%6-TV9VCTW>DArCpkk(``d%_y&RR$%8YTH@a*^2wO5#{acx(dlSAI4w#=cSC z=)R%WCLX;!jb_@Ib*GY@_Y1W|?uN`kXpF6LIkk75*4~P?;v--uBHSJ`cZVqqqm7cV zZU;!u4mYosKS7OVHr62;&R)$B)4W}1bSA6G8a69Ioo~Q_3OB5Wzp(jJJTrdXhG9Kx z*&0(LPWrg&$Sf>2*MRJiS2$XXr;YCL5oMum0xlGP`z?jbQo^PO3!?(51ipSqFmcta zIZBQ70wMdKHJL^cd#iII3V za^kZ`Ugtv-9N4t5egsPlU3JRF>p3Mk=fnaw@7o3^kFY86o_XcP+Td^J%~|iF7I|#) zu2!pds-|3?EE|Nkz!MPAQW65u9$*BV;ZTrPhw+?giEPun)T|S!#S)A%k*)X0)cwQt z{f@l@`rS`se z({@|4M78~OHqO1c^Rf8CRoLgIWbsXrs4WxYmCPmWPyU)4jKpVZVyThwb0K00khXRX zOrPHZbv<5QkY4mVGLH0C$(9NF12_1;-b#yMgF}2wxAA|`WM}QeVkkQsEZ~u;F=`Wz zsOIaKb5hrjhBd>-#Kg^t5TahDe?0HArU4Lv7L%ur#@%?*CP>W$7ioZLSz^ zjWj3f^&TDRjD7ay{+te^PY7^Lhk>}xL%&LE|7?1dq*~ojKXvGP$M=?`E!;@_K;uQn zERL;xBS-^U0|eY9Fq;h{UrFTU=^fu6m6f$*n9pmcE)Xq?w%0zdiLmX;8QmMBw|;wr zPnlvEp;yIz>XpYJj*Q7jUGt%%w?Rd29-MDLfwGwuVe@TNKBoo~n+QAE>o1>Y|F2P4 zzdWGhMn~04kc&F>t7s*TbdMxm3tUDPJbJg3CP+Do|IA-gCR8{szA{^eMtC78F+X57 z;>FR_6@K>Ka6SD!^m>k4aq5M|AYX75^}m?I<5K;3c3($hM&Z5&T5Q|mz$T~oC(Nee zTmIP1wJmyfEPPUgTbmrjjV;qaSioWR!-Ck+8!E3C89Ci}YP)q`R&3(KvFsRUw7c)? zw7?gVh2!vM1J+o1RnTBcWI;NphTWnyGL*c;1c>yC zwP8-4;v)xPOJh7Z{eHB$%LGOyIW_&GL^dzFT_We|-xc?{m-7uwt|U+VWjbSjh1@nN z1YCz8hIBpDfLk0*?fZ+!g}iZID|&j!O)r2bpwrOFM*BMbi7gzYkq7C0jTcFIlesOj z36V92()$sVe2W-UcHEu!@0-854yzA`gf9*8OwVf|0h~K%rLc6swdx_Q(2BNG7WO!e zUSc4Yb*qQOKd6XX{$pz?WhrRtwY1?lJ|ffl(B%)@`}@&I2o&NHD1c}eL*E2#3%|t| z#=^MUrtigcRI<76csuXo`G{!if>hnr3pMs6e*l8NZ48!lxJJMbnqiJj?Yp0I<*TxQdTjQhba#mG_aXoiC z#BOqPf402HS&%xhc<;;1{(>tWRObS8Q`o*;M<4#Cyrq;jU4PM*C1)6_+F5=%ZiT)z zT;)2bX#{nAat+#WT5xHGp4XvNsHUJ+Z`GlJG_halsdo~6wV-ro03_SMf8`SyJj59L zBwXEQnSQQ*fdL$CbFNBx{01zI*dkBvRhBi3MZ?Ze%INBx$Mo_GfQRVQ(#jOW7dmJp z&9Y({nN!WhnuOZYBM=>oZ zB0EaUtH%>A_U91HPY;Vq7QGt-X6*QMcdWh?I`GcXlq31Yl?tgmmiW)B_Dqip*aL0H zn7cE}&>)0JX8W_`EQ`jN7L->shcO^Y9z+fp*hx#^!PC}oQ~S4hZ;~Y(;8CF`FymXq=qBY4( zuy0SU!dM2U`hPndK+K9*flv=oUM_v``O3`wM$kvH6(LOrM;A}t5AF8X?yk2A>?!8j zjqTyZ$qN=xA%r+C{rUwgV+VJCl-i8*|FSN1OQVO-U+0_F_OZt*G4a;L$MQ6; zrBq9QCwRfk*H!j+r=)s8o6pI;Ob88~1|{$si%1_QYKW2Vup!|G!A&Wpjq#VZJ-xD_ z1v7k&aXeLb4CBXzbgz3(ccoWvb`2 z`o!PvAt}O`{RY367*pDXWz%6jfrm{@tS9Q;OCubHre3(~rJNMTuDMt%RYOQC4AMTi z$@CJ?VevGY9SsFIPei99qrut*KKZZiBRt+VOvLrT3ay?&duVex^&YLtK9m2k7PgiYEj0*ouD_Tq%NHPd zK@=WA92!ZP8)Dp_4K52F=wW8E?`EmTH}pkq-eyl#bOZ>2t93{X_$${Pmm!#=wE7P@VS68UMP-x1np`p})SSI|8@(?K2CYK) z>~JA7SfPoSZN$6EMc@2`I-vAW-plo#WI&+3PT}}vHtT5vO0~B~zI*gS{#I=5#W;@k zUP*_sMKh{8hLDp@`KG!#J56dMrwZcE;-KXuuam~EaQl%#*h`Hf^s!bj)oYvn+5%OW z20s%Y2MUYf1U_t{Nak;tBfla@4-TsR^rvDDpTn1=MyF-9UR*V69$CSOe?9U#rpA8l z)wdZHHAlo&Ex}3@&VEBucX%L{9`jj$gqsL6gBvht$mlYlmFgGp%E+!0Va9}G@6U^7 z*MT0SHC%NGnL?hX7cRChH4EX6w7lsbx_X@Yor-#U$ZT^*Nph4ayj=9vbPXRExKMEJ z5XVmt_G4{Jh-Ir&P#kR>r(hgS>hCY#k`TS%E@^&uYiK5!5Qg896PgZ^R6%E?92^^hMCBIPc`~l5A9*d zfM?)1yQ*B2G-Qb{`pVIo?^gAXr0rSt7kZEg5sk2x=2N&bT&cvhoXPbB>aV%_4Hh-> zIQ}FgR=fA-t&AjOBUS1zE??(fJl(Y?Q1Q4_w&lQ2!8k|HX*Vo0pXYdvvy@? zRGV;(kvOoq2VzI&0}Gikgf8esTQqfp-eCNQ}dt21p~go z+HrKK|6!~k{qEsm>ED^lZ?VotxdHnm6G;rc)81BRfh)v@Rkz zaDzPgL$p5i?+H9GHNAIWT^cyQHx0 z+x^(o*ZIqb?Y-SYPslL&bEk`9RZVr*`F&XRtt`{aLD~T~o#FZFPN?EH8@aulBC@hM zDFu!1f=#O~l-*9wS$o)e?id;;p>P(aszC<(YX)ZPnv-y&+S@Z{p=u~IZgyeVs2%z# zUfY)EW-p2&2+^4R((h~j@Z4@xf0>6==~`4%Dig>P_EzAQvQX!b1U*v2y^+iiwC-!XJp8_(i2?W2h4utEmE=DfT}$a1o(ood?0#sWEM zT-1|0l@5t=Z+dk1p3Dh)=Umc=ViN0@e7y`nfj$OS6XYLE#Z*4Y4W#TEjmKkGdiEZz zc3sH&aKrOnTj4WwWs24U4=O+Tuz*?dOY)2PE#tL}a6|IjK>uS34Hcci$}gWSom^#B z*Q)|6k>TH^G~hW3%)~M+BDMW9L}(G0uFfJqrEK(5mpzk@sOI`ulhur;Y)m)QWv#5P=gVy0B`_Eo= z5OYAh5N$y1Y(;_gp_u5E%%=4-=xp!)q?`MJSBaM|299N2Vytsedaa}F^ryGvPt)D( z1L&KeXE8MUF$^lFMLy&=_#`#5pK_2R1JyQ`B(9tTDxO#%LywA8TDqbU1BJGfUoSn3 zOyZQehzY(1T#0#2qBBF3r+H9Tr29f=Dj9$(;QJAUu7JxjWR(BsOya*2jC?%BjfF3*=9ngJ&1I(dy@bAUoCrmfpys*>KtfC0;FiQ-P;7cylJH z?ih?nJ*KGGj2BDOmC%g&>~P`4q1A8u2Q7YIulHH~LqqPxca?OTt*_&|Uw#ceY~NCu zFJl&OjjGRfHT9AggZ14}d8(WM6MQhK>DEu3s*$>w3tw0 zxRk3_r5g8h_xSkW)_v=|j<(lx4FrueMW)$d^PFyn!|h|T^VMBJ-?C=K`+7a+0E94t zOi=Aad<%nQ1erlR?zAAfo#Om8s;=*z*4xBE`9ZaJ382>x~`v)3YRGiYYu5!v`=~+DJob= z8}O%KMm##MqJID^FOkN)(o-#<>d;2}Y_MZ%!Ife9C~s*4k;V_F$ZBHkXtUz|XBu(F zBs=#PkW35ooR6NcetF4llBt3dB1u?<1cHq7xcvcmeeQ(T_5<+IqZwWYGC`bA8>X0H zF1HsW8L%_}qBzWg$lvKH+V*Vigv@df{H9zdW+ zdvGGtxN@!25f@X^ehWBQ>tCu8~Am<2ann6@BHZ>G8;0S3{@wBy=m1B|zqYEK8vs}SRGBO6f z4YqRf*Nhg1v{?LO!yi8OHaH{8yRn#{1|Vnn)7iR2&8EMFPuKaPf+r3xwoJ=o-vvKa zvKXVI_R8GD*Tte2H~4@nu7-^Trb1-1uJ&=T>#ihOc;&KdbB){N)fCrErB7bCj`y6I zq$|HoqE-I6Q)YXz)lLWlk8ATFA>jxbOsdY7sCaIA^1KkE)xcsAzmAf7Sx>fu+xYLY z2Fs={1wSFj5aSGmimC?bLB-PQN?1?#`YQ)*V=y82ov^AsvvO2@KW0k*tZS#EIY`p` zHKr4qrCEb5$4d!yX57Wg=*sEHfHII2AB8ggee6PfP?iE1=Hk!c^$)t0^JEtChXZ3o z@vsf{IE1i3={VccX1Fm~a0E_GpAREF`YgQxI5KhEx3ob`mg~{a9p-z44G(LCPl34FUnsbAb0Xb6}fd`R8~39Za`tcKt=7HPdRw)T8YwHBvxD1G9YgG47{gr1X{%6gd0{SaqwcW%;mBZ!YZY1Q z_KU%~hPG`m>SXunOVwnr-OYl34^KoZ){17R?yL|EQSJ+baTj&1fA6ghiOZgGg&=w8a%|WQ%$lVHuLp1qdd@W1{b}mR`{n8gg_*7|B z$E2wJVm*BOOv}!PTHLiZ2K-AP94U?~g7+lLU`v-^4DEzYHCltdt8lb_ybV8hcX!0j ztMBWu>JCpTNh@sGm(gTOTMQ+1kR6IuSXx@Wqr?OzDCr=VCnXc(aB%~}N0o`Pdv@2`|Ec$n%waasS$9S!CdeS58E(P}aA7lL0x zr|sesd-}gVi$cpc$j^g&dmO(O(0^t6FFZf24P1bdPi$V3#I7SM2$QfJ(H3#Q3KllC z**6Y?8Q{JD2o4`Vs&)Z;^1aKtTGS~2suN6bW}p(Ui*3mspyS}>vP>RapV%;7P-_1L zMLemYLJLoQh;bwrD;vn?fZG}xkBUQzzkFliM|9cFDo@2tXh{m zlR_=+f+SSdgx~Kwm&@R5!1)ViN@o@XIH}ZG`!#-b6=}Bg+;=7(#K%Nn>%q9(5w@u2 z+i{I$zJA`c%TLEx$VLciw3;{(f}v2S(v?%D7QqGP1O45OrVXOawX=5B9~dC9;<4xG zmH3x!#9$kIP=V=X%s2jy((X>vLN}&w;4&sZT5q=(=PEAK8jvCguNkVG50=$0p!MLp z>GWNJ-7+>Qj1M~IzpTLM$`V?ex(?f=>H?jUC0hsG2nx?;y&ar5KBS!?Kba;`6Xkq2 zIkfe|yts`X_Zj9__!1i2G1GSqqXJBfkoH!hRLfv`c{!;VoL~-{w zfMlbzy&>N~Tgj2g7RLeocdw!ob(m`~Xl~DzFR@r{^Jl%bbV<`5$jTh(hV)ah2*Ur_ z@M_CGc7rF+y=`OG36xRX@J(9?$Y$NDHSkTe+;1rfKffJfeAUg!{&JH`$gJzuG7 z1IHLm?k4Gx?1>6@NzWE2z;dFeEB!+&Sh;Kxz;jcoT~=;LtSsO4*IM|2pbtMA*As|H zUdsZwNEgrq#gPbiLD>`QyIW=}C{fIv8?au&b&r=qA>FGR|EOB2s5-=JeV^BxC9Mf7 zc8o_~ZMtG<;Rzk76%!p++UJi^K#!iTK!aG6U`PpTmCN2V=-s$@EuGg*fBeDaO9}&9 zxS?fNqn#i;J~?bGq(tmKX~ z7o$}7(H1YR&K$7+*I0cdsV-znLM8X8i+l`FH`Y#1^*Yn{8_&=~AADbgZVu8fatkFC zy0>bvN ztA{}DzW>m`=LYq2(DRbFPMm`6u74%Rm8}dkUc{gJ7t)9ghtVRG$P1|ugfsG3Tq-Pk z)*1;@7-&G^daMQF^x6ei5*syoKN_O=S}5ytdUIYGe)mN@>LtQ(eNtB~^LuMv*0(%{ za3C&QMte#UmR)-mBng%kV`fBysN@4rZ=2%+i9E7ST_IUWZ1IfsmAlFYA4lXYD*^ct_}m&Cflsi zkE2ulC6+Zys1L0tsxU(wMjLHHQHq<2UE`-;^dj{p)KQ~}Yf7_KoeU(-7fl*9Joora z)id?UK*@*!#cmM^i_YO|o2;o#)Jw(p=DZVc9Q!_9_@~syPg7@;_E_rY2E>3d<@E8t zd7dLY3z@|uzhPbq^$U%18Zp+(Y}9yHLkv(^b94U@zYNl>||FA0;B+tC+ z1o9nFf%ikzyo#Cm8BC@K+9iB=KLE^!gsc6-is!zkBopP2PZj>%`SE6sZJmf2Iu;TL z4M$3dv3-;RbAKPJ3{77|@@?X%G1QPyBDC2WntYKsZcvdZ@(bHNo8BE#sK5%5nqCLXS8qe@swnz0Zr~FKY z>0F7`F8sLCGkcLJGG{GIgS!p?>D>vUHYH->42MKW(%n(EtyeJU0e6YLJfh@tQ`K@m zO~-cvb6ox0=yzm{3?T&k9_Al0Q;_3-hZ619f5Rw*@q{Grwf@=wUe0R^UkNmRjcmxa zrr^dz$T1;{o&6FbPs}K*o|A{0PYCo`Q(Y3N)7rSViXJHr`~)Lh$)uNzI#~W}iozLA zdQeodqGsR0he&x->L0%f28$CNKFE@b^Kk~J+ZuTdW57ARm7vj5WA&1pRjXI+kEh-+21uvCPx&^#xYvcC>rcGe z{rj-m>)*KbjR@v{^F3Lcm=HW!t0;SjjH0tzcr{W#*F38>5Ki1{?jYwtcc&QkjX`jC zF|6O%&GAXgsF zdkSYH0TJBSg`P0ypaL!PhCo!x2MMoM(QdsP zjD*jTpO2oK>P9UTNKjWK3!G&Cp%Qlzf0%+>^hXhx=)u80e*doNsq;x+?;@xOEJ^sb z{gBAICQz;{g~c1?H@I_z^;{uZ2k3e;3hVrI0HrZ_AO_T% zFb=r{GuG43ii(1xwr6i;t9^-E!f$9OdziCU@h~G`qf(@@YgYI{C{r3NIOBlnf)w!@wd;m4Zl+(`ao!X0qQiXztSP z@#EV0n?nx#A}xJ)@y)I_1F-q*>h0@}vgQ_em!c3E@PcYr+8OQueiqq}t%W|0B_s^PbvVwcxha8(zYlf#Yd_!9 zI<{3^4V<>_2ra7BF~8imFF0Kr0Ql9;O)#QQJwH2QHHh)TwsvovYXz8)#}nz2>f;7> zQL%`oo)R4l%_66oC^M_j9?x?49+8EreAY5e_4@u>tACR(t*Z2z6-+CpH^=^61DWWQ z^e^x2ER$jOrZKkG9hQ&-(~x{%3Bu0L`>z>ZHdaoWkb6Wi3=q5)hBPB>Az6mZ*ZDK8 z-t(vSSN;@vq7*@c9{{x@H)oiES&N!F;V-W?3|G0zn&xR+L{q5;{i^hSUnx9#m@~P= znV4`FrZV}*Rn^q5J~>eo9-8x0WA<3GE})vebv&OWa|i_(>Bqp6Qmoq+a!z>Kf;TI5`klZ@I#oQk!q#yoC{oE-cAX$u zztMpHDx#Btx_wF)V33svjaOor&V)T}=V^_3w(xx7GLMU;l9)tgyZCRlpEO%hbvggk z#XvTxYhkN!Bmv?IW$8z|Oi4}j$g)RP>tIM{4%1ZXc{{8z`|;iNE9uh>?tO@>yvg`@ z2Y5>7)bPV)h3kfA*8jwDdO0rm%I~jdt>47z{x1p9|2+IBJ^a6CH%jY^TY@4Tu=_5n z|1$Z$r|=l#$kFYr%t1_*t0#NdpG9y#grET1l0d$_>BKUvg1D=eqp`&&nEn{3B|Q$8uSL;VdkU0*FGK{ z=%x`$M&k%CC9Z4M!?g)sCt8>#Udu7-}4^~J|;TeJ^t z+9c;KHi`S9h|!1`egIAjeSh=-bT9zWP%zL?Pmquhp1?puLt{fh!vJ70vB;P)u*rpL zp5Q!Xk=J+r@^zi`rJ#bnqmzF;hyp15*1#dRid8QlvFnxHgoq-Xl3{g1_ZlUes9#>~ zs3Ddl=agEtbyk&1GR6663+m=IU$p`PzduNG0& zMx4uYePfJ*lwoj56^Wo&maB&mbjMzE0^$>O<iEa&4$Q(S&PmBee*ikLP15_GGW#&@D>O>t-jL=Qc=#*$4plExHpvtiG)wb1 zV@@ZXV|!|}wFS&8#0_Wg_|H&ZQ*>coeD!^IYr~K4uT*i5!Z=?B`?Z?8A*KaQjX#EQo~L-1T9nHJ&qpi^8BZ z3QY*sj`U7>*~uV4KbH6vr2U(dj%0?^v-m0%ad^@IP7L!n<_O^raq*qIKqL3?=j~pY z&#gHaGV-Yx4MA~leh>2K{jbjS3I1X-+MBn1fIfWxsaTv9mnC@6p1}* zKtXEv*k@ihJ17bis1?u#34UzV`@h!Wg$ON596tUL$406p!z7-$_lqdu|nS42R7J)3l{ylQ-PT6tMI7Uc(W7XGPcz&>0b^L3CPBEB9v z+_PvTk+Xt?Jb|?scjF`D+Js>`TvJ1=1gUG|9G{jc#@8oTCY>JzpECl$1l70)e7}$6%5I}MGu~g&1^;+Wbv{e{2_mWL-+v@uP#%mvHZqh&bp9v zrzp{@BbLLDxV2yt>nCp4Nw}8sax~tDjtrJCJlyhC25-&%Zgt^Nq$;i5{Ru@FAz|I@ zsPGs*tPSK^X>|X`i(tru# z^rJl+336C+Od-Gn{i}+pTZC&~W@*gOFT^3s zpwogtH{J~*T{e=NFIz5qq(T8$FAum=f1U%2rCNEeS!%iDC_ZX6I#BZ|PeJi?4EN;Z z0PF-^@=F>2Ppl_QkE%Sl>M1+t>vl!{wMsYfikyGmqPJq(_ub>(vKh>rwrk&X=s%}| zNLn&9c?X3dy{VCpjJkrGuB0_%A?eD2>$9JmgFNpte5`}la`-+Ggyr(`WS-aD>AGJ4 zlZ^iowve*4n3t)5Jw-9j&V?tUIou@pENME51r2TOqrZ(%T{zMXy@Y0L+9O1ksO!*1 zUxc0Q3T}p@2x<|M@P4EA_@J{u*_g&8+Kha_PQ#_#oqC&*@eMO$pHuoQwmEM_@>n<2 zX0$-u-q;y8^jsFaf_-e7dboZC8Dv|EL~tXEtta_Rqdo7rr7HJzLl$SZRq#z#5)>}` zy*g~PZ5Q1a{=M??M4TY3V6|d`XReBax28>>s`GqH<36@g9F;&mP8$k3ig5ITb1cOQ zOr8<1^A{12>b63JiBz2wIkdP~Wmq>2Acb=D@0OKW^jh}F;|MQ|`S_go=coPeXO_(( zGd&v34Np-;H>qXt1H;suv3igoU;U#I;w!93Ki&_!SG)|F@PJ+YUQJk|XPASQ`5K+M z*#)cYu>QRzdt?`N=NPv-|BL@kx05j6C0d4u;hZ2GfUugWy!+hw^#GO`B_6!eTqWUElEM{k*%tt0f#@7S9)#%{DmGAXV&tN`;KDEM(vyBJjl@506nGrUS7qfn)}_%<4F@aI=q=Q!-fht=i0ZI&uglw z3mc>^qG85tZMZ>vE*Mj5O<6XO2`LYN)X}izP@r%I;6tOs1aM+X@1-wbC-VZ7VXHov zqQCkQY0U35_fxXYDC=&*=5+vOq)EW!)l97#!3NU#o?s_jin9KZilWf@saTGR_6a=h zbGtA7TZHLPn&75^bU9VTHvGnFr+44H^HBCDKqx+@!1^~fPd?FFrHD+6d5iMTytAvS zg_gQ$j6tk{`9dBVPJbCdEnp}9xSLxdEpO1daNBF2uvom_Nk@dq*IQYMj#-J3;Yn$T z>xUJS5*Avg)H>C`wS$RfCbxm&O;~2@v{V}}PYB~)P#$f!-i~?sp3JAPgvXr`sMblZ zj8g>zwDo_~-^Z_f_rx1ZQ;jAmZw;+l@~zM_)=z<$M8m#0@n;A-jaa;@tKgcC4!Jye z8Ou-^`>;8iH4O=CVo}h&@-i4K;#W^0vaZqADC0J_5(dy(u}dg4h=-0k*sehGOP^?2 z)Cxmiftj!ax>bN0OeLbDm&o5&_^sU1@?rU4LhSGZtrl%;)8Oba!Dvm;<6;?MW1n8R z9PEjj;;PD<`6?Z@LkU0$*qHX^2RIe2efG11lPY*GUM$%V{&l-}VWz-)%BSDsb>dAD z$?Ldp&vLBWLqO)cP+6MVgi8qdw9W8frpIOG#T?A&(UD5fc4GHL5V?+gJtZ7Vb4qVQ zGf34A7nhe=iH5FlKK0%UTcXP1PW3u|{F@@{&x0KDIj`Z6C%4Ob|2uWnU{9Fdko^Jh zM|?e!K8_jkOb7)E-oNV^MAHA~ExHNwuAn?>w{4Rr>iOEQh@M6F2o$JIO;mfY5dFG5 zGR_-w3kJ724J74-!lE}j#wBlHo%78ZY(&3ZVZ3YSe3K=xB@&_ozXA(nfV76R zLx9s&)b@~ARAhloM-=NMQ8@Qz0l~}`StUF>Pr43y#L&0k_X#%nf~hEY#bcVW@A@;b z!2|L$6!0h7%Ygkwesy+)fHwS66~5gyO(t<9l17RcjTQJ1{=r6Ab|{u@g$37BruOfp=mlumJZc zI{dtqI*1wGNb(SmwWbk{wps`X@NxifjmuHyStig)f(8pov7mSX3t2g+5S5$$X=36L z744+mmDVZV@?d6$@h00779Hi!)H;B-u!w_xVPfEaANe7OeQ)IGvN{6H6RCC z#u4`1HPMe7!}xtz8ByERfZqdv4-Z-*;*Q6~$!&IVjkfs;4ZS*Xf+|n=M2g~x(pwfO zYCq`w{m@)EXT50WN66oB%(?6lvQWa309p}fOAhEsU`YJm-B7wf+mE}-vN@j?Uwfp! z6&9Y2(}xH68K1K~>Io~URL(mss7)pXQ_*orVj_5WSSwdp<;>O;EP6fM7ZGay2^^h| zcyKZ|CuFn52`S4Wg^x-y{Jj6IR&2CQ>s8ft=*AL4Y<+qaBxY$$;p5UIj6wX8AIT2Y zNkEmzz1Afqh`%fXm|d{FZTYvm3-L>uOw6z_M&N43$gc1oy|e%7fV`&`ogt|jt)K9| z8FF}ZZZy7&de<%_Y9SX}zXOoGhDvaYuLOq({v`+Tn*`(UJeOTJ;UPm9 z+2&(VsaK1by4oh5B)1Ofy*Cy;l^A&ZFMpYp$cn*@qY8G$G5R2l<#c`{Y%D~U&UZR6q58+%6Yr*X>Lisv7srjm$tNL0`~Vk-+JoM077knP(FlzyQ(ZJiE?Xcp znZM#nIe`j7-3;!UNSt2DKXH3p^lOa==f@vxgDpCBbcGm+v&&ymtSqqGlnJm1P)rs9 zVUvyV$b9@)I`j8+uV}&rR-r*ejM*m?p*xoo_=KSqLo$ znh8T|JgGf?N%T?pFahiXB`GuX6+PKk06hRZ0KjEn4|EXkRmXo8fUqJ|)S=RLI+7s= z;CP~I9nul-C~)DiG^0WJOSc{5UKoX~-#FjDL^Akvj1F47T)H|Dg&HA`8yH+O~oB($kodH@#I^f9RW z?fKcHZzf&Ql(>8@E8LRW^bM?4Q9XHnlMS@-@s1r&}!#?n!xD!pK-C%aTFU$wT}c`jl_8 z6yhWZe7cMOm-*t~4%DgKxBZvg`~+-cFTIteIDaCANcvw45f)(cBMROH2eND4% z2WT0cN3mU5g9LkTR>E%0OK>|fZ$n_v!ky^WS;;fglc4D@6>EDKrTR4OIM|TkW7IT7 z#5*@IK>kk`mh^;JW3ur1M?CK27TbS;`A-5W!RCCcu_nh1?*ASOc^Ph$X&FQU207C}t}w2N@uh_eU>wRlDRig<^Uon6{{ZBa z%5pK;P}D~aNWLBI65@onN++tl91q`g^kb1x{!o>S_B{~V8<1ty!&vj3~LxkxOT}h2GkA61u&?W$c!LTrfSEgHBsx*sr4j$ zrgG*jdL@u=x31NDrS@vFXVf%#! zvNiX)X&M#NeqPImmz7MXm{XAtG{Nqa_RsA5KBUcN003)J#fl7OiSHuN+c-?iMqHWY zfE^J{q-A2EA$GwkZewuIQtR%%CH`c^0wKMmM>pBJ4+B^g^gTzv`Bqa;JT(Nnl~?p}6KX!{%{LLkG)!5r^9V|=a~#1^WuzWOS)>=-TE4?H-BXZ_q; zmQ4_hf3y(4+)8tIS3Hi{ZpYAKaUC+9Im0&TEPr|h!yWKjF zvELtxB@Q(-11{(DsH#nde6d2EAcjJ=fAMP6PS#kf8?CV#;y|cw*!*TWV}t-DPErh& z(sE#ZT%VM}K(7=5j8%;6)8HpMpN3yblKYs3l}bG(;}`c8wRVZ5t@FN zjhOpYiS12UzZi0TlG4>LIY|RM0|#wKJ68tF60z9do$4bg z4_#)aMGw797W5Dbh0b9;S=7vrM9Y8%^D7`w?q10~S@`gEXIlE}W|_^DU1DJ=_e|nX zpP_bzEf|y#!Df`&ZfG-A=}DAAxUf6Oe0N;qW&4=9*m%ql@U}l1vLt$ih5hwUOcT%d zLRt!X3o$XdS{DKqnS0&DFxHb8-2eW;_j=3_;!lNJMOKk%uE( zp7)LU*C*|piHS`v$2}27lxmGwDRIK7~ZIWbT?_J~ABSw$*6&O+h($C8NlG}t=Qn~2|F?v0on^)s;-T(2igD`nw* zA(AN`;N&6hr*=t;FCczP#TL64xHB{8)cbbeMp^JlIQ0O4sY2klcP4d>qtPs%6vZY?D0CC?PH&LK4>qzk1*$%045V^Xw`=LFrVLu$s%bbbiUQ>-VoLB~mCy zkB|a${O5n?byXD+6JB#pALI=xu`@u-NeC_a2_)s#O+&m znn$dI`SmMztBS&g=nc{;C5N0Wk+F*t<+j!aG>Z z*X|^258Vpf>@;;`m~kgYNL;t3BqEz3g96B9DRoQn4vLK>rMieY*F}B1-u=w&5PI6% zeqF&;ReOKKwF$}L`16cz?1;_U|IEV6FBgnv^gzt~5Coeb0imqi?_^SE3gVoy#aJ&9Y=>0@T1W4x6F?XAwPe8QEr%Kf5v$^%5^iN9c z#Kuj6f2`Ech}yCDJWCEmY8Ev3n9%tdXl?wAWub}C+_9e#Z`duSJGe3~zZOwPp-Lfr z&N)uG*|EN#XRV1u=|W>C)tRseaxAqZB zqk;fuIn6q8r^;CbqCDGl{g!tsPQ?GXpBtErq zw{ETlQdM|Y&dBsHy=eYa4{7|N>JBpwL{1T~fOZwZR@2-dvS)2{hNLATb|tr0*%wc* z7Q(w8h!VrCnTUm+{aW)+1O4>~|D6TvEDMNvsIs^3!gt;F=Wf>>*lNw4_1X_!Z^=-( zDs~b*3B>r)rdlS8=)-a-gJSo&E=Y?lFrIAF3v>Dx<3mGlq%IYoMKaGE5gtC~=(;Hp zQlHhcTAt6oKeZi@sL&^;QG4+NM6NHVu-Oj_Lxe3Wbm~&^J7L87`o(;*M4$)L^xJ5! zj|+v~3(9VcnTq*Cv?qzrq+3AL)mj|Be16_?mL2ueCDD8t>y58}fEMsB{6+|sgf^Lb zpV<=+JQbErl0<=OB{WfUS>K$M8dt^8)9y-JHD9p!P#3o@f=4dKf1k`Gy~>?=`r|rn zM=+aBroS2P?d^JEn$J|w+-CDYTM@8bNCG#zBW?YzgzpgL!$tnD!esCdc^@*F)+TFcF%I1rR@~O|;RZvi4WZd7oVZgFERvEd z$*uR(!>-U_wOtqveITFE1pLn|@B7`c%HE5@4ewouQ4Ao?=X_u3x>+X3cV@Ajj2LW#u1Oi!&drtKrg_{wdtJ!%H&5c<^v-Xau6)mxUKS+L zKj!w<^L1hwZ!&M?);IX|Yu6yGjHNT6cT7;TasF*wiiC5sJIZo*>SnBY&UTjp@|V1~ zZpxSIG+QZ@0+`KE5EKy7)HuH-1u!;PCTT3@#OLD1cshRYSU;=qowxtdJbsp3Z%KVmbQGqXzgo?PII?G7m0W^$&#HC4YXv zf`+x1C=95FTVY9HNrTJeOylxhad_+ zw$3D%z@79t4W*BTSW1iP1$~(Q_xBxF+m7a=eeSRPe}Hz1b)|^xi=VsDfIvKP7JYLR zQ?ViKZ;5GI7ByE>@0t!lkivU^*lBm93X97eI`$9mS1S*IlsGC*PpiLX?8ts^y>EFjx6SmQWf~0twxu;gFj&aO zP0P5Yr`*PiUk33L>;Rl6iKd>&USwKu`l~2DgJNDU;ER=4bRS?QIQR7QrFV6Z{2%yj zHZJ15Y)^L~S}T#qMu6f73E zy`-*(hMPp*6o@^A!Fn4=XCZ-JBmVAN1Rxo9%kNEpmlOp+axQOpe@1@X-;AC;qAxB7 zQw%=e4BmL#?k)UsV9DMUGg7?}U-xEY!+*;Ca|5AI3{;(WOY393$dEA43!ONrg@u*yjD zRrJ+_-Ms>!RJuPC@cbBoKv!8j(rTQiLCYpEmQS}_tMu(2_Mq9CtAk!cP%$bfja z+sjT)$fNWYl~)`2vvK1-v!|*KVgmvjy>t(ui3(+oJjsCHNOtQspXRsT*@OqdSxzY; z&{SZ%g~E+dU|avn8^Cm|M_`A%=rf889RT{))tik3u@u_rQ)9CSt91kqdZfxSCMGM5+yoJ3H? z(f6&O;v5uP_9Y6RenfA_{LbzG!9?|cx|rV^?ABU;wm~3S&u`OXg%l|W@$Z9UDKu3c z$EfOr93qefLG=vN|TF!qrwO4Y>g)*cBpmAr%yW8c=Fb0Tc zhtGOIX_b#;=|3-ik|2~RrRW^F$-BS0p^q%5^NJmj*x?5VNM<1o-Py~Z7l+D~wLL)*YhmJXxEzWQlOyA-fBhGS%+T-@{sC}=F zF+%`-Ga;~DH|HC~{OBx1ERx`H;$Iu?&XC3jo||mwKduL1C(#rG$k)$?l`DgRY^*#! zoIaS3vXu}sTO;mU1KTj-a8#>-fxUzI}gIr%S z^lUK5DMtj`M@=A^z0;cDBq##wg>tVe=KDIjd!SgJ2R?NA{c+r;(&1Qd25?wmiegIQ zuPEbCv_9332|G45+lg*orU4DKZfiVHgX_!Ucn-F)#OkI^i44+lZ z7?Bx&k=$%BT3{<>#@lPTtK&3vSrKrXcq)M-9VQx0+Z1Ezjb=i&-$F z-bT19#uG`_Nc8ycQ80;55)ZI6$Ahhe%F&2mrgHLx7iC@$u#h;@kWIXHJaAfkk9Tm? zI?N1-D7gU3@V0}Z{}^c7{VV&DDdYSd20!9ZSx#N^8I0I;-y57>k zxEXA7aED@JI9V4<;@A{Gg~E!CSzef(>#l?!#Qi9vI04GEAqXA>|Fh?O>lJ$ELR>{% zWhjs`g91pIoo$eJ)PVwYM# zFI87{1Dc$+Pi`6A*~3$c2bZJ!ZSl|iyPd%0lFtq}CWEgDw0Chx`H^IX-aJNbl(K3< z-##b2#1JlygAb`%l+MA?jgp)2?PPhGr|;)uu5pB5JvOD_qZ$W-?T&f<_MlSwl=g6I zh85F6?xN;f>Vp$$jW1EDu`qsAU(H(FC(;5m5T0^#jS=6^iYAig`FQ&T&b;rK$p0$p zr}zj+jL$?;)voUoO>dMmsPA?6ffR!ZFbjR?W@*uDkEj{j8WNhmr9B@0Kk z!ElIDo<0kd1+@x->YXdl&>U7nOozXyzu?fg4I+YfQTPfQVxian;>-Nvj7@N@uf8rC zp@xCmcAQ#nj2NWs`d}vrlerlj_vxgQ-X8u&1Rs_-1Wdq(CA|38z9TIgR`{u8FJ`qygHbW>H zx4H3cB7Dn&u$X?3ly!e@JPLFWDsKUwSg#yN;Seb1xat)|nNzMp2>*cTjEIkr`68s` z8LPJN@Z{9)1QFm)0SF~Afel9m^n^$T>`SLZ0qZzlyh{&8B(g68h?+o+0}|xFg*D_n zr=iM>MH^(vcI+X`SL~eKH zkM~e(#^XsZXAuA08fu`S<_%pV%RG_-Qg?tflT1(1-+)SFX|@vlu3 zM5|)r&pN=y(SNtcl4zE%n&$ObhANb%Plo1qSNdnos^&Q5@L&vU5gH?NX*NK8I7c%R z!YpZpwGx5#MEJAW?f!5r12HHQbD)goyYv5QxLIxV{47|tOuZ8t-3HvfXC}m?)&9gW zIP8q8Bhb8sHTI(tKOK|PJamg2kTE{ExpN?guDny%&~HhohtDYMS3lH6eP$;I5GXj< zMdB)p&s0HpC)n9IhA8R7G{4KkB!o5`PqYh#y8b8cHj`+U(XaejLEel0rJ$!9C>cEsdXGAsFFdc{e6rFYCu;g9D(}1xUfN%P(Y1h7uBdRn8sVpU?;pgUr7$-a>Ez40}9427=pEy#LfI_}&Mj ziDvPl7_fa;_7fZw5NHwf?=b{#pr#1Q7Xw=H*@+VoxMT;gY87?MQ{wyThlQsayt=T;aNamZ7l(p@=AsOEBm`}<&3A`@3)>SxRkt)uI?@@g-~C>JawZ*7s27%; zKp>oS+Gad>p8&sJ=vQg}6EFBHa{g{Y{`SQ`rww%9P7@*4q-A6aK}(s)$i|fR;k<<} z_3e+n68qUcEcoj&OZDzKp_j`D46T^tU5BU=M1dx{!?{4cyfmvM5Wr?}wmBq60sI5h z0t1eJ3yPNsuBj0#V~kF0s`z`O1)x6gvN!eb5kx_`|Kd~Y_=Xxxx5uADANmlhjpJ5x z7ma%}fLBCQ6jSDRMYE_S*hpcZC}dZ7k>l_?XYX~#4E+vU7#rlk2~)>2>J0D3 zkgg`~V?M+#Oa}bVAO23LFznd%Lxt3f&q=%G?(@c}%OQ1LxkvP!tMtoIwDgM}{vU|H zS&q(s|NAAs(K5sJ)p}hH6Km1caDbO9<1ptu{%Bcmm-BS)hg~_BX@PI7gZARO#>(fJ zXvh-p*Bi&v7xx^~p90sh_yI~0I&K<@Bmj;LZ}w@W73RXj#P)?^^+;t<-*UDx1bLBt zfO@B$JG6QYOT~~T4*#N~Eq5q{aRnhfKHis$FwUF)+v|?2`44MVxQ@} zNpWyzJiGm@9vAqxI=8*YH z&Nl*kiX);bMvaGGVX}kLR}>H%CckzW+gJ_MIj*Ej$^z?CQY(YS4i#!-hyX@44Pnsm zoTpho*&128(uJ&E31MBid$v)e2N4P1`9t@w-X+8MoSQeSM-0Ha71VIe&Q!10HE=nW zUJV%l3k~@n3XaEDQ<2)M%BTz_gpGWGxN;?UOYh^3F^hEzx~>W^(u!TP}B{W%P7R$$`SvUHO$40j*mM z*lRm+wtPe6xe_e`PY<-ae-AID{-bF$=9v0sJ$#dp-ow|4#yxE!BV+*6%Jr0w%roep zPtQ`-dN5qUGCbFmZ+Kue5e4wUK^iJ7Y5^UX61|aBZ_(!Rbr?c&bVSg;<~u07>;G?! zBke6$U8sws*mRI6s@Xh$i4p$|Sw5sUP`&QP$XIO~g-p%~mcyA=>Cx8$-F#XW_2qr` z=XO#)STwubqUFWpZz>uPjKqCrmkfvo1m8m|NLa+tcJkI+pZ62=)|6} zdS%1>1CI4=d@J~*f)Ep*HrRwqiqy`f>o)jrpO=J7EwEFDHV}3qOgt|jrlIGPbzhs) zBBGGkGe(=SmUBMs8@yxM4#cE2u6lof^4Fcrrmw7z&Yx3DWk8klDtu{jj+|cu`_*`X z9+8sJJ{;%~3}UJ=wIyz{CWi~lc?r9Sx=)v4AQs2c?guALc7PA>$3f0V-W(`XuE<}& z!k~o3CQ#nu?k6iXV74_VESS(ct^W2E*xPV$s1TQg2L|>7aJ%Dx@*iAG2oKnv>UEqN zq}Kp2-CI@AF(lY|-AqGtp;i$^dP3*cB#n;EN*Ds`F!E!fwdA|j2K7JnTMunb=4#^( zu|f6&usGf@J9gGOtPgDP#U=zo3qIO5=a@apN5}qPc=Q}81N&ByUGwuC9+<k;z+>!4}(UTB{#wt)~x8OkOK;wu{BFqKbPuj37-O~wq`06Y!OEve|%&fpNI0Gib;4P>}9-+`uL;&ko z7)UokXg^8G4oRU86{l}Faj5zEi|R*6i!8TgfzcCuYM*+fGRk!hr}ZpSS(BZ$uw5G< zB&H8xPUH2QpZp`H9QH=q4dXdk5k&-4&cZxiJQ8>95V5qz8Zvn~Jm#leW0my2%T8m9 ziq1gSmHR7|Ssi8;2nPfBEoWR)!g>nvrr}tz3EQVlFFOO_wI&uTf-1yTrG$HHsab5A6nLStX`UI|&9nd`kYLWIbBvmAEV})XD2Vs6aj%|E@?o|K6te)UEbg zXr)ryedK;Sl#M}ZX;g>|1Kqf}iDVGM_FtnQ3OhVaV6q8{7EF&DYoAl-F(q45EuYR9 z+d(ycondS=?>WABAEH~@Pb@+R9tptOe3-hucGAyqKyw4a1EKnY&=huLgQ()mVTs{k zhV*`byzf%4o(vg!6zH^<~GJ0VJ+f1DsA~2sHs(^;#+2UFxOmzdaTY5kO$;P-L>U^fCT&gB-a;Hv!y&VWjKYi z%Fy>$#?|6oI7$HUfG5xp?LenS;@yo%!bjoCKlR|)u#H9jpfeL_a`rM z)4ml-9&p-?|Jy7G{=aP-Pj{UC6?_fFk((2+Yo$qTD9c&AU{vP=5^K zs^H^vA7a%v7W@8cQ3Iu`Q7yda9-a_-k#p*f{yT$9nmpQ*fDsNiIh)B<8_tbY7^>sl zXusn_(iwX(M_cl~>jka^-ve&ka~!wnM;(5c4t8t`?GEtQEq5hc>yld|ouy2v`pN8< zz>M`L&ID-qxmQ|3E_VTZ@6Zx|?Xa@b2RdF)Vup#~>{aR!`ANwju9qH3PViL4QbO2a zwtA=MCqMa{3jqY7@2{N6daf+bqU3$hB|nC~Gia+h2FPky)5F#;NlL%w_-z(Mycyjg zMX|c53y|vVIQ#*EvCqDgL+rWi#J-`F6pe093$hEgqmv8{M2Tw_HNQ}H-qrU&E;8KfU1WN80Pc76p-EpX}l5aH+BYVO7Ae9|m?E*?Pfhun0!-9sO#bFc- zlv+(a8@Cw5rGgMLmQtkok7`%n=9+;=J2~ zSe9YPa>!jU%7AtCkz};4qOW&sTkx(V^apf&BBNwLT$z1*`@(i(n? z{KYpcaG3tO%Y6K&H6<~$ZrveedN35Lk5K!?8^e%_h-Z_KxL|0CREQd#!zk&&6l%8F zFP-J_C(=^wEO_UnRu1L{6S~1uaZM_UET1;{$?L^?2t*#vtYjIkU1>L`D9z3dCs#YZ z^|JAlg-qd0a%R655p<%~!;8DOVN!O|2?Ah8u_TKImHslPsu*dqXjWJ?vvRB5r@%xy zlES^ciFBV`%VPE%Gca0YK!86NzrWDe*I&ZDGeK1i9Sfs_G*10Z+OC)6|)gyQ0H^?$fqt71BjB#M6rA5zq|9TSi7nTDB zO@$z&qYqxDKR|Dq#x!OvhYEs$19#F~v`IL8G2lCp0Q#E^PJ5T*2Q)0yN~x!KhU4BH zuj$H*$$@Q)XL!ikQq=M=yBTBKdh;aXUeFdj5vD;U*&-lMD)imQzi77d5NSE7&xOS0 zF!c}(y4i54e;s#?5@$s>`=FR01zEAg&!R;r65IC;n>=wF%NEjk#fZgW)mQHeoKq;N z_EbT$L}E)_m09B9BbBd30U!so>=rNTV1(&s#Sc)Rx@c`+`sDc%K}tNRQf5rOU(RK6 zSK1KT&pUlEK1UP78y`pAdu5bC#wL|6FHa`*j-L&C3TnF$?+K9{!QAW*5GJn>p|Ls8 z{VP%UfS{vbak0l>x_D&1Ka=NA+yDPr6T zqCEApsdWi3SY-9n_@d%(jJ4}(HzwwF_ps-bx2rrAN?H?^MlA~s``zjP@zdV*B9)RQEj^{7_;z=hU z0q%ki!sp#mKK&HS))pZONP)J-ssd7=&z7Nv!Nen}cvyR1u5hI6KqKlER)%%4Phn}9 z@r>1LvAV$i?iwj7I%YC_f#SU5>lSfc4;ru}DUIla4d_8#=RZK)@BSLnQe~0OiMpYN zC@g@kq8nU|b+y^c@lJ&TURkUUGP%$0uV*fJMow!+t#9)HdW1bFlAi#jM&9{kI(IR~L$Rp1I-K56Z323gg4o`(h5S6gVDw{~+6EAQ$D`M@Ob|dp@H&GRo@mz+ECoCu*1u8rZyWy@ATQ z>3NTCytGb=L$(Il)1<(ZgcBA?WPM_}Sg}ZF%N#eGvhbIWj8+_=W`2O4aGZYLK-fYPbv&>v*6jtyu>$i$fCyro z1p~Di*3D##mPn*%NnK8=IJbHThEGk_-kwGnEzP(u<|Z@HjRtVd0i!M0>f zS!xeeH1j`(>OtfwIRE4wQeF+CjSn(pJcr+Tj5<3`Cg~>~Mh)7=j|8diQ`!M6UdoF3 zycmnehI-mBM{lOWMyr!*DO|4*WRYGjeY80>0o!eTUD%{qiCx}vE-iR!+O69j7y>*;eBrnpt-7&^bMTp=)@=IcHlSLhVoap5(7-|k?>45P*QbKk1F z*em#*VTJORyiJ|L5JjcMFvL=XD|_hh!IM@tUwY>HUV@X6$V-F5(&-IYvQc4*yU_SaESNZ?J z2Rt|Zk!R+iDse#&Vl~c6ORukb`T^&c*>L*Z6^hZ5N-U{F}Ip8G<}goxWw(pbo0t@^D3a&z3w zr!MyLxIe~>6`v-<8w@2M7hcpCRGUAQzNfbuT@ZfS0HwhduQd>u&P-IK2h1MZL{cOs3=1#t3$e-MSH8tKhnMXYQNahQEp8{XmU4AjCa*$sqf@3aZx(&1Jc>u<|9 zhlTI*0{aeUh6wk@W*p4pwL6`W#XB7UWo+vhvnu`&DsmHg2hIw35@X%(wd`VpGP&z8 zB= zyJ0i=`Pqw%vBKASH7m_iLvFe5Sbw{C@lWfQ5bdrAQ-Y9TOx>YsH>363=_AB=SY?qE z-P3`-Nx=-4g>*W^F4haGw!aCy&oKpRJ4AAal=oNF%i^YHhLEno`TwF#NYunTBh>kH z=}CSdLeZRq15c1b5K!UN3;ZgGB^w2TJEDJpsG}nprjv^_21#KC z)vwv&&`Er!D=IjPUOHcwI>dK;rFCm+{Q(LidNM7uN}cNmbp_wfug1=Xp3C8?dB#7o zt=t`BPu=`t|1wyQ8+sxbUc#MdRE1S;ZP9EOC-1EJsToQM8Ws}qV>$&9cvz+F*IhqA zUyJs2{Cv?>djxK}V#l{QkpH3lb3+NW925W%;bZlI{w+F~Uwm4L=hhH)H)=J)a=jZNOW zlUW+gWcjAA0I4tu=iu6P4_{+kt z@(VgVw^(S5Y}*fl6o1LHokZm;G$7KQq zHqXs_Lk+wp1)eOsgAb_v`(!XrDWAeYRM$182fvowalioHO~sdQMXBiK1_sY6Q{zync-~0UCMx*@JanWMTQMuoB*UZT+o%(a$Pk}PxTHxZ?v!D zDJ<-d8M&hwd;5jv>8MbTD=3Tc;Gq*@0}Q&QiZTpnc`7K8w)sj1qZF$2o9cRTkFVf9 zTPADZBumwZ;`U23Yoq&nkdvh zo>4-CKV6ijWL@tWx<|~q<_QymvHlBVeY0oZ6R*&A#00LMuI~6yCqwuHcS#~-VvX+} ztBfft-5Hfw#OXMp%>*NbC995JHv>Izm(U(PXDO`Z_$vVJ5F6tHR4>yaai6DvDomu6 z{@y2;80wI3*x3Rvh>Wf}L&qFyPWCV96FKDE?Jm}wdpW)AsYV}YFT3^E^U?QpA-fX* z)3VZSX%0HGGAJ6#u3UQTa6D-A*Mps(`#|=S1UH0>`%IIJS?_vCC`%eAjtE1j+-1#T zvWSH;KH!!Vpe%EYy#XPCNQ6N+K4;IhhL3uoT(0y6wNFLo>CMlucmMkVfaR_}eLL z$;G{S_#aj$-&@2XbIK8;{{d3Nbw$Az_Vz&N@R=hi{bT;1e68hip$H&Yav6z?t2gjr zDAwcv)>PE{#aQ1FR2-ju*Is4-ZE-4WAUjm)QI7>|`WkKCrYds9dFu93v=^8;hhHiHTE+)Qg-PBy!=G(l`M^~u6eye#UlF@4b_gH zEbqiE>eJ2k+Xtm8*0HG(axd>krwpU9dt_S(aL#>UQh_~b3Re$%!rML35vLjFnHOjA z7sF95l>F6m5!)7=n307hnhQYluzBJ)vH*WIZx5)a9vh71h`8}2eDv#_1C z*P+TcZv05$Jl`bm&&B8-3Q(9NnVr9yLt}ZefMlM7ngg<-k~$BxV$kM8K0lZCg&j+B6UZjl8e~;?Vg2x;;;?uUc}ak&G&qM(hk1CLZ3$|&mkJ5j3w~BGz%~Q2@9XxvpG5b7O)^I(oOe8tjw(4uw>JqEb!((5&Cw>iwY&6#hm8vNadMH~u)x#&07++!Ea6kdOpLvG z7{W=HB}lfX86R=*=-h5HguJ#rA&GcStbKO(V_? zhO`4yDwyl$Z3TU~nKNdX6#BqBV%T$g3ExDeh?PO!{9_t_UL z7#mgU?4Egc$=_f zD?fCN$I1*J@tWUKaUMT~EgEOFWJIYN6MgP(6rB-?VM>+GmK&Rb-06LNNJ=`~aNVJ7 z$G_cO_+U&aQ$M*I@m=>-k6nMul>uZF<_C!4cH%AgFY(rIIa4%3OTt_t9g8QKycT;; zAJk4DPFwe3#JmUNiL{X6d&xU#?i$C^>H0$@PmKPh5H(KjobC&h)>}NWJ*pz{*@lq} z(tM|O4YbYTwHh{fKqap>v%x?13CL(x_=JbC4^)hG*}DMIYD%)NuAtGtj*6%9&C!A{ z+bpsXfn81^@8CYi>Zi1FJcWhme2rM0i2Vu}u%hp2S@cJTMy286pZaz@YNmhyV-tQA zsP2op3Ok7T$fN@2A15EQSs~{UDeX^-xZ33EqBO}A@-lPndA}^LUz@9c7RLQDI@K@h zG8LAGcNwAF(XH!?dTF3>dWm{OXzpy!}kJLRJIXA}3tSW7=Ot8cwd7f^?2 z?@p0KM)jG=i`Xa%_?JT#wz3=R3CZ$E9(7QNU0X(lP$GQvJ4pv?w}^7tTi~a;QoNZI42uf3GIEjyg%q`kp{)Qe%?tbiGFJg&(#&uQsBn z`kq6D`Wmr2EZnT2c~OQfs0=*@Kc)LS`n$5-imW2KmZ zv}eS}>Gnxw9@Jcz3a~F_h>SmNtxdc8%+aQxom0KN?3)C?{oEom;k>gE>Ua}efLnsC)`K6}3Y@;GR02cK+l;vH2Q*e5LYUhQR6-3`}6K#SHY-fWo2 z0-gwt2GiV0;p3_E)E!4#AG_5RL+XMv(IT=Bn>Zorqa#S9=%5@qq>pda3zRXj{&^&1VZcGl zd;J2Wj(aw*E?#}qp^}&`5Yu+jJ4ttRo0uMg&bH5%wL8|uR1Z_2@b!@=; z!X&`%9=$o1B(E`qoeq<6WO}#kgcO;>v#Gw2gC+FnhMTipfes3v#A74D$pt!!$DVLR z0k@!WX-Bx98%i-F$*0D|0*&v`lMzv%`X6FOA<>V9lf^pI!D5IUVMv$s1Qyp( z3B0if&KC+9>L8F$LM9%GtH)377*~Aj-){=y5@9>LsKzV_EXpOH?4VVlTVn zuNYbem?-(Ztud1jB z{-iP8{9=`Fj zSOp~LMNVmMEn%=qMuPZm>a&jQy5~`czFg2DEoDB-1YWs`3iemjAw3*!VUIW+d}I5% zWxwcr3y@E1th9yMG z3(BCWY7KhC5kG0_S?m*E*a&~uR#FNyK$BCnivBGuj6d2Lb-EKiW0`Si*eVfLmURpr z6*j$N1ql%}R9}o6`;$HRtsZY9C>l{B3*_yJ^JH$x-~4{Eqg%EKp8{hx*-E+`ofi*2;Y&L^Nh-8f8|4ZgdRJ2I0DquSrG(04M+Y& zQ%h@}wCCSvQANeQ_&j=gV4qp=q^JmPh{bIv2z!m9E0)rdk$xVdB^tfXFB5P~Dtq+e zX~dp{qvd0wx9~Q&L$se05n-Lxc{U0xR6Z|#)|}lP8(Azb3zn_xU(9Fi0|eW^Z_AT; zz{E_%PM_Gw+dDc|>T`)<)+*v^iRu{8}BENRBed>=GgfnyiZ(z!`5u0?3!b1lcp* zq-*kXT}Y;_x(lMbfo3YTXoU?6+ztY8Ddw~V!kWpO;2$6x$nku;hq>(GtaO-rVnk7u ziLhv()dLzfQ}O!;$u2FuZIMGQsX(CKm3D7Fox{pmdcn4n7S|v%3EJmU@-V}GflmsQ$2(@i5F`%-!xBMDg99N^4(!oz=(*^J-6g6J{a zP6J>60R7amf~Xp`y$jcT96QAO37d@QSqOefueL@jn8}TPH9ijo#OF)&ZhL)ss<=cp ziN6xY7Z|tc{frgk_3d2^dkTvB+frFgU-p+Uo>2Ywaa={U6j>`O5CrUXcEX^*Oy0o{ zCk;2_XB5eT)R@UcG6~A7y#vxWILsqequ>Wib-h0<7z}fV=46kU%6kr&Aq+>0v?gLw z0pof*Mda*FXwKR4ntdPV6K5G38;zNTDl)fTUNwAN_qnnJrYQ`7X^NunPxR(Bw#A99 zb)lN4!4+pL&~=Y?V<&ufcEXnhy;7fJw@2s~%ZB4;v?(}or!fs1yno|?zW!{{d}1?c z=6;xg>S9-CV5O6@sc~$}6+TW0gB{rc?j+9Wk*``I^^=$m${Qs*_)u!zi3@Z+m=$B^ zBZ3j>+-5xGAE0qTCbNzvKfFwCB-jY&G!4W=ieCHURb^uS6b}_{`n?7PmsMgOxd`9o zkY3=l%Qx;(5}uo$s>g*$lxno-qRL0bwMma{b`N(FM#0~#nzr!9SI#C#sdaQ}AC)(J zNvZu9e%Y5X6lTG$J(neNvlpOh3IKYp;rgs;7BB)*lxz>et}g-DA=CLXB$s8HGolLu zNKkI5s>LG&x{lyp_A@Cl%A{k9kO9MBM3|Mcm^Uu*1WOq#n=`!l@WyojNcP9*vX9%} z&+>PQ2d)torxj)zXvOha+&q@?HS)ji+YZZpb zxO>aoAb+Y_{QKNY+QTDT7O@T^E*IH7=gU(rap_9DNZ**p!k^GIX)b-dhL}Wk;v%Au zp(rd!7%CEoGaADxL)E+1`BNMj4*2~Vu`I-1kDR4GM(OgG7EedbE!o>aTV3dUR7dBG zm(YHlHeu^fFebPmo)m4Pw7Ec-OeKSp>_4x+{-uQxYkuyT`SS?cR=j)KW_h9Odb1|Q za2yCNMmaf1Pb0dd6R?Azg74wO!x~2F_=7B8x$iiZ8s(ym#`|3;9x=r-F4MgU zQ{)+jLxGomoU+zBj!{yq@17~G2ONB`XvHlAV`e+X(<5*;8)+rScYMg!4LbZ%A2O%I zGwmR9Fa;oto{kULb#?PpOiauz;wY@j7rLqLZQkhlc}Z3<4&<0FS+M&8C&lc01hDHp z$~$sYf{BmAHqmwwxZ*}HSKg4ah~1s$)G#xnL z*!ys-(@xTc%kfV=>>`Z^t_|+vIQ0iOBrioWyw?fClfwj1(&ZILHrBQVtv7}r;LMGS zv*|n@B^H>dnM3EFodvx)$F!&G2A5w$seg?!Y^qPD3_z7Wv9_~Xi{;wrd1CFh{pkin z9&?^X)a^S@`*}Ea-kPNYdDrWN?}?ncRpO??acdk@#cuVN6<2BBk9qJsC6PUyM!+0nHwYi#LI>}wat>4l^3l% zO2h#Xmy|UJj}jsL71l?^*F)bGe6GwNbeAM^t7PxlZJ12m@Pty8ym0uQEN4nT+s^~9 zP>-T^T5Kg2&}J~oee9@V>q<57whgn8H{7+TaT@SJCdrcSpR1~-p5jsS>V0?;mhn6c z?^&3u2%-X|@Jb_aT#_=_Cg>h`U7&eaZ^-4XLmzx-gEzvaAfTghw)Pg3xlTk)_`{&1K74z!S#WI-D#hqUa1;_!_A7#U`JF1wSugbhEemCek*VtKsH^d2*LGf4D00$Ej^@`U7 zX6U7yDlgIIqXP_Wq-ctEGDech#Hl8YO`-4fk3(`Kn8A4{OTsrBAS?!9WvgPMA0T&E z*>qi5B|}yzlk34dbWvuW%;^1Ah?6Yh)GU0cEPHHa1(O*8y`^TUI*+=%tE8Ip@Mj+9 zh%|gBAWgg{WM7OMC--`vI(A|k*8Sd)n(sXcy@xC_T@N+xcNR!>IVLA$!O+4-%dTNQ zz8Y&%kW1Gg;_;|&w2U`9Y6=xhAx22jXKdlVxF2o5w{%~xr{12i*QqPuRqaXJlWC98 zbm|+2ms~SJxRkBKugDNzqGp5OnyQ}6omYOWjw8l@E#l?;sJCk#2?#38|qwlo0d|o_o&sdDs1)#UkE$WAER7o|Veq z05#mtvjQk={=%PiS}82O7=>0S6>`UFd&5Q|CpL_Lm_DfJ&cVQAz%0Zg0o8;o9c~&I zdrS8A8qO_fuu`X40e9FQ0up1ycuUX{DLgLck~0vmZM2i1p5V-TwVfUtQQIF9pL}SK zg`GoQ7(e+<*|H)Abw*&^qB~o>X(A!yG7|s2>)El)TqJG>`^ICP|NZ&F;_I1ih84!e zp*>6q9&V;D`WvnL#9N30BVi9$(=e)#H!yJSi$NeMp1 z%@nQ$*%z2ptf{j*x-vQv(XQcB>goRlI=6tgl`N4Fo1MCp@O(UdT~+jLZC{Z{_!Tj+ zpA(C(v-!_*sa6a!uVT|K(%>Ji_byKnsP_kRjhB}*k4+LGqZN-`-9l}^&9XXI^RRJY;DOjg*-TgO2Q)te-O)KTQzMo83H1=eeMonjb>fD zvS6z7%VV}x-fEnzw$vVJG<>gMYz%MjuNFN^UAaCjsv@y2`ao+fxi`-m(L7pMF-(;M>A z*#g2T=mwlAzHmxh-%>~G7Lzt^kX|w*Nv?>kQ(F`u9(nvf_*l{^O_FEQ<6vGS0LECP z!@#DD??4JuLpHal4%x-=Cd-S>ZXQz&DyuLb-D9DQa;7bSq#l#@JK$C>)6Q}DTttYc zgxa;;*<%}vgR#-}vG)37oXa0P9auGo#v?>|G;cgj27r9g^kr?YGlXv@pxBwHXJ0vf zahAjzt4FxO3Na(c7`B*wG&cZF)hNrER@C2Hi+K`~@YI&iygZg0_z9*i>caCBB^*6} z_G7ODkiT4ePf8TJXIN%%6AkbS?Jk*x@Rb{iBe&&_E@(-O9`9P_jP-J3SLhSr=X&TY z`KWcgeh-SlDLQxdyP6LPdc4?ij^|^sv1sb{-28AYwakjiJiZw}l#S!t(4$&d82Lid zk{+VXulsFiIn$gO>(Sfspkj+f2wNH|pRwYK+D~5Qdd44~xgx1nzKl|c{-n0T zmDJ-lZf*OI-*hA|TIiFa(XNUnFR>QUQi-sx){y^y(+SGJJ@I3jJu=FBtZ3I{Y`&lh zX)78cL|hfUpe2p>W1Of}aLjD^6H1}JP1twP+Wvk)OKLVwqcChn(ieX*oNbw2zL%bi zs?)NC*-tX0Hmx~!D~`}pBAIqR9T5ZiQJ(4$OPpPsE#=hz#qlN5j-YQ+r*6$p-TcW) zhK+po3;%3o9$FD4eLEjfO@j9w9WIEPo(Q6*_YP6h8#}DHKJT>7`UU4`FYHPJxyFv< zc0R|)7e94a-y||M`6@}&7p+io9P(B@%N_j)r-E#S?Rh%JF9o7cH9Om)Woh6XEjq!0 z&z8cj$+a^Ai(fn&*cidvW_;qpbi$Q~)=k78Y`XcZojQN1=C=+NnWG7WYCUQ=`5-s(J?2qJW>*;|#YUF^%E(T`V=4W1Gct&(_a>f;OREp2#< zPz3BFz4 z@6cbA*zR)OJ<2$^(_=HB&|mK0{J4KM%k_t5+kcZU4~@0?;%DFgpRW90IIMU^HfYd$ z=^PKmMuS#?!sDt|4p$63Df4x@bvjHdIu#W>Bl7j*V&bxvZ$dbA26dX}V_q*OkutL| z5_a4aOR_1~QZ7F!56I#ny4&q;I9G)B{ZHkJPuduY^$g-JDTt#^oW2vrV{J0~NR2kF z4Qvx67_6q(ITn`_tLI2YYzRH*PF#XHpCDp8=3MchaL_;?kca#8aI+AKJeYO1(80l>yz zZ-Ri!u6{Hex*e-HA{ox-`CrKnG`44h8CXyYAuG=#aMZLiSd_{T!&#=*DU-<*F!u)yX!DQzSjF6YTo-*+CTl=+; zW5Ez`){xCeo9NxOPc7SC7Av5glnIs?Ud7H+}l*(Qdr6 zCvxWjLF+Dq$GqF2?${d10dK;>UV-~^`YDrw6PJm1gk32&4lYB!`3Y{(q7+G;a4CNQ zY&`gb&T(kZ^7SY??)Ea^mFpINaF6fW^)Kbs-+-uUD!9dND`^OlR~^v&qGmPPYO?Z! zMCX$E5`@4Xy!6FZbN_iOl$|?4IEWabHN$JCa8LOVm7*#T9AO5XZ+lc_Ivn( zJ)V(>hhu1KG|`Fu_h|PZ?3Qf07mKK_AYI($gO*|HBxk|TaZ}2qT?yCP!PjN23faeQ zfxb3bo9a|7_k;naji&Y#B+69mW{w`TzZ}#K6>(j4V=p%3LFvzJWsLVs{r4#zE3lPEICVg`S{>v##~bnan`Z! zzKiO<`@>d$7{`XkbO1fbWT?j8TuGm^oeq#FTrMh#fku_FVb$*OAq>2Qv$KQc zoR^bukiO!zBP|=BL1d=k%edyk-++(ynF;HilcEB9J<4|n^5_udU(lQ4F&Rs?HH?w+ zp*Dra9o-i<*E75`&zR_6j4Bps7P;>*eQ@4@Zihz*?YjCN6qP>DM1pl{ip2c}*aj8B z`;!+ioTm!hokn^=F+3otTbP{=?ir%v4v7f`x~TIB;Y=IoEzZH+VD13KMd#R+A6{Nhk^mLEw_bt{&5%^~)V z=fOmQi2c?^)G$UFx8)Qn%Fy!MemBT%h`0>t6mRKf-HhnE$*1|J_<5qm<)_7}ec%AY z4eezJG?xgDbsJN!?m9|6mW<~!EhVK5y za=G6C`IPGz3??wOHba5a&1z&(nGc`!+sx#`atY2){#%((u&YI#8U}GI9Y($JlUa8#qiD^O=WGI? zfai*oM0MlBZEXr?*zjp{`2??OlL{w%GewcUWPaQXQoz-HJwTkbh1;#&a|4z&N&{HMR`U^nSh9n!aV})g zwlt>KSybnX6gTjyX6vwJ6+%7~)>DR=;NBp`=)6vi(_LNG~IZZ%ifd#>f6mAqcZD!XVk6;whG5(n`? z7^dN1m70fx_DXRV*e;uis9)3-A*6cJKBzIM7;hNe@Jao#7OTLRT9IKC1kP0uVr-C8 ztC~A5FnB8FOJdQ;QrH&FQz*Coy^k2f_^#rhJQ~&USqJ|dHB0VT_XX2e5Z>cwsOgVI zs{|oD67gJSQbTdVv2?kp!GQAUb$iADFamszAVfSzq6AWR)J5E`B-K%~qbuLVq}#;e z*g?PIYw|`XRotK}*>~cO3^-W!CNG^H6!dV-h*V=(8A~tE)tYD-I*K~ICb}}rS#vQN zv&R59WkF~l;cdkpH9bJoc}R}Jm`}`aY$eL;zw;rygZ-q zznE+KYV~XV6;Be^Y;!#u$8(ShtN3Q>Ngd==@>Krlje-((9{M})MoFU^f;-(E)H6M} zAdPrXC984C%S$)CkqMgvO|E%GA%zny_^uo2{{D}!<&RXV3&AvxZ+~cGJbI*av?dOU zI;tO0?u~InV7^*xD$T$~ENdDRw=ndWG}NRa8gwIFeoCTVA`=`%OyGzZ<)Yw$L=5qf z&|SZV8zPRhiT=gvvke0Lr;r2x;e&;rO26=eaRfEk%pUDPG&l0_gm3t{stsnRKB-(%lY!O*@SoB;mc0sy%7Sb zmayiMud7}q)b)jDwA^%$NZWRAwM}&jzdErd2C7V~NX6{MSx2&sTKc@m+vrvXwBhf$TrN>!MH!x+#|tEsNSZ zQ^`c(k0lvpx*E9y764ZHQ)jLJ?XP8x6q4(0+bwN1d(3ouaa=1Ic=WKE zD=T5&uh5A3|Mhb!moz${3bkr*^ViSzxAkzo1Vs6j_v^cY;TT10DrZk4oyU_M-(0&p zD{urQ7gx5<%&v4RnDfMDBT00iK1KOMJpYpwTkd%)VTmnCMM-qF8UK?@Cd;4JQEY)h z$Ps%iv5I=KKN4rkj5dV8fbT4Unuw+PF33pmy2mz(<#^^F&bnhwFZfPyyveaf>Pc~3 zrE6ilsP&O{85F&s%l|7CRlzH^NZfDU#l3kQ%Ay9cN|FQAbSZO!qVekM)5Gi;`nF@* zn}Ipy!4EU%xL38sA1&6hQ^Z+9WOf%sML||ApiPQi9z-gxhIgdX@MP_v=j+Hd8-dma z1rlht3EKrddJ3u-! zqS_(5IB1Ao>nygEMOr_uZeVm&m^7{i1sT;iKj1PJ8NWD5Cp})ym$;k^wM5C#TrsKD zB&vTYo$d`!@33sLm~hBbc2O#PNBM469nyo?5E-X_{Iq4=VVMwi%$*b}+@QPvL47xC zocn5^R`Ugv%ll77IoMM#k7;_B5jQGCtOezn@tLCa9GdlMvEd-Srl(_8>W-)8CrrRG zUxh*T{_C#;Qf^QVWG{B{OQ*8JmUNsR=8)~Z(}aq!l zN0v}=q$uE=`80>zt_h-k#0eK3PUQ)LkRbrQ=wa%eUXHBKC|nis7^yOh1 zPVSH3Y29e^NuUjpS-EY+guEbmP+t=ctKn@V(kC*>X35i#Zlh3s^6{)0x&fjzGW;6f zv3HQ>F7>jQW3OXwXjQmZQsxVKn13NPhj0YWsgsj6@6sVF^@>-R>-jHk^lFy2TA`K* zUrU}M(Wk~>gZo8R&+=q;)H?84xwtmy5)ji?TzG7gN0y(L^wh2dh(!HbdDW>c_&tda zbAhcuXv^Li);*26M5Lqh4S#7Wb`&#*=Q@tvx$_~X`X{rm5{d6&nL7Xs+cVXcGRSdx z))vx^bsT)Mx_&w_4v^^M>gr24*_*f&!PhPLj1*CNQi8C0GsY3OYNepJ$GAJvdBQNO z@k~0$>;%o5OD)plMXSHFQ%MJSv?HqGC2^xzeB~C&ZdEidf>xndUz73cCl53h@`A}6 z-JNRi#)dEKmI%FaUdop`XuA|Q^gh+xF&AE3f4L`$p@z?~fcT(X{|5Z`&Jnx<7H5u; zp~1cnknhh3q|yTIcHi2vS;YxEJ%l_BbE&1Mt~YYYPi2JjjK9mR!6#$I8cXy}ff zPK%$h)2}3zLIY)O+Q=xOoc+R2084@x5Ou`p<4{x1{tu+PmCMU!bvbdioAd54S2Pg} z=O}5J4afH)l&n`S4+++-KW-)rglmh~ zXD_=hv;M`@5F}K;DB!$@r%+|G_R~xWJCwovX_J^wsS7fB3Q9Ab_Ww{=KHIs6+# znVs)dFYJHt-iu-{min!0k7t^AE`dpQFy2w&28aq-;ZF4pj|GBqo?R_SQx%;MMR{tl zF;;Kz-VqvWN?C%E?7XAs=lXS$^i?tbjz`^0jRKLxKA~bt8K1nJvjx5@?3c}8UbooM__dScI$pAZ4}eIF{8M169^iN*6`ITX)8M zGl6gY@maaMFFzTNvZleXI&qBL53mwFfrtnKqM<^D*HW(;F(r_=6UZxTKJ>;>Sw92C zHt;x&p8EJGgB|(RH^nLy3&&JnTzn!2R$^uFON3)^5Eze24UN34K-h~Q%KbYy)f&DC zf0)CA5nAX^E8xMAI`8?taWY<;Rz`S2IcfYwcgXR5BvkH2$xqwnJ?Up_GB;B#d72_11bzOwb8YbbG zx}RE8G5E0k($4+Z`A_lZivKu$q&8uf&a)hsG)?TB$U;|8DDX0r^QpK9?qkr#% z8n$$Uu+@Hy_f%4;h^7^Zr?;@(t0H#4EQnd#$Xg&yFIY>9Y-q^R_L z`g@XG0wUBkgK-jx5MJqsqSUBTMeJ65O}>FR`Vu(}ulAnOD=wm2NWQnToOGY&TWp#f z{Okl#I7IjsPqmun4b?S5QFuj+syNg+B!M?b_VTb!k>)Z;mw%0cN`#It?YeS{$IA;1 z?kZ{5PDlT=^K0TMvgs563 zc2}q2)-^6fdTTGB$W}Fg`xsFR4LOvQ>1OWO|2+cZ_#2SY_UJTVyscU~%FG75KvLRo zP+OtxI@M`>p%Hi*|6zq8$kKzB%7n@{KX$MwArU0bnw@x`1agvJ zd68S4$*j3*zd;J;9sVSS2vhP()YK+bu!BHM8O-Z~ON4f)@e;ccHZ*7HrP_N;!Ui+P zm{L|-|HE}q{FThqxt=&q4sN=oMW1f@)^L1xdqGIs(zCW>%-O1)qVHYn349yR8~VWk zq%&fqLqpw%c*b*J#vWS;Ck?v}qv|iI=)e}u3*QEBNPCFP|aa9x< z{KtG(@?gFrrOTHib{~iaCmYWmPEkR3Ktuz@KtEXPabqmS*StB?!g1Q+T9#PP2_=h< zqIPb{9O7xpI5=K?p)Jy<`#EQf0Ph|boL3@E9~2ssHg@P1xtrEQPZTxvOE zN-xP%2=P>u7X*C>U!Z$6zbk7*drQfjBh~&%v|E93|8dp*71d64VUt4iIj7oE_x~07)>Tpx`OGV$~g>V zR>SQrDJ0Q6-qu#5M+>5}b!lsM0sVRAq)FLGlRi7oV_c!yDi|YTJ%6RkK@r{+y z#BH2%oU56V&O8Xj;X^~{$G}|lbrbg02_JiZH*T+KUcgpmNL=650C8so7#5xzE~()L zn|W4jF$5LP(tqC(|I&yrHWkvIy;6|_U`ozhe}xbEu&E0ryJNOU&=C*(OkdpGdG7Cm zpS0olL%oMzWRl{8B0lk`yyz`POv3=b8smcBP?5ME@2}AR|Iv+*WoFm4#BcKfnbkn( zfVH?f&WBNQvX*8XhYwXH0wSgiIgSrU$Xw#~A}e<7Z-B&vI%TyJA)@i^^Q2;ngvqBJ z5(x-$j}g!OBm8psw}_oKNe-xdlBI`<1@xr!s;y+?mALBtmB$bTGJ zaH+0_X2xIEm9)yY(#%EAga-JW=W=IzYh^Z67UZY1y}Ik8Ox)I(KGi^3d-$cD|H$8d=ER3~HN4#s>|s(gBf5;2{i)KYfnPaq;MLCc zKEKZp4RVXLwNINJ$-D1wa4^`vU0WB=^`!fxDG)w?B$3^P)`+ z=d9TOI8^bigM4)$K2!Au+kWorqb~;R!xc1KED%tVrtAR9)1RL_@dA&`@L12tsAgCa z%JQQswS^@k;`_`!B1oZ57*(J+0UIXy5+wOM(=5txt?wkkCbcl7-kKH5?~{@k<^p>n zpSs2RzE{!M)A%#C^@^&g_DFkiH-qk3*A)AQ$>+tGy^sn5y*rD-e8x`ad8PLZ092b(W7i+`8z|E6t|(Wp@6t6slCsU9qz=I|Sk%j>AYKTr_&uHx|Evyb@kH@32d z#Av7Lr(TogWj}j|wh0hpPFKVf-kqHzbg)kB#t2B?qFUj)hIOvY^^K3Ljw)mN+9FMx zV`r9z8|HWxXV%V9S^j`$Y8H|NLH-%>zh|Tna1K`QCu=|ReM|xgTZSQ@Sk+>yth6hi znl<^b*HFA9%JyMH$Y8%-0qjx$V$wT9*vW%iDpOq%n=p*bQ!%n>5n|PX3mX71*`ql} zN4>|Ffsht&nrmZ*S>fUU&3X`{K(>&P1k;+Jh_^%9=*Uw4V3n}(Pvh?_qj5XDe4!K@UN>b#dVwJq~a zrpNm0?lMJ=nn08}p7EmMOXlfvi!huVok+9gz6Ae^I*b*DXq|FJDnrtE)S2U*3hUrb z5+n8+vEl=UQ`teL0@pLD4O~4}?+fB$P%sL5kxbG6b-2DZF90P7<*&YATYw%#)^Z|F zDoq|XZM<4k@|!o5p##(cX(KN0%hM(|@twkCkOoZlYYw|vnnEaL6B%XTIiJiMOU)JP zM?D$4yyEn4R?6qFJai8r+Tc7ogQ29D?RNL2mMHOP+I!8%qdcQ;-ksoz5PD0a6> z#fomc^`tziELv#IrG)O=$85dj>u+z~xa;9Zslb#P?r8PKz99xB0P(Bwdb^WauyLuw z3n*3<7wB?H712`gD1=6s+J)VX`dXq|w&0eg7!hsG2!Ijl`1HwcoB3P-n)ia8pwm~b zv9V=B{6G($c-ggDeIiPmJR0tsBwc0&nODpXQhdPHY=|}clmtmq34`d$4-9`Z1)GzK z=N`0AOYIukHj(P`L%BRo?6_ryFAC+!9?OSdj?eAJl5qDE=F79z#)-*O?ihQE1-W(>F-bg$* zeux;Kd#8dR+0Rc2p1uCz6cOGokz&l*`x((47DLx>W4~f&YNPJb;t}=D>=k$J0Piu@ zyedC}T(2Y6spB-?1c`jiZb^UINymAWqHHA~3|0B%{IO7`ObncpVkX1tQ{anKOYf#& z&AYbBoj&A@)fzWq-4-(vOd{-s zpL^9^QL!c1xW8FTlr*j~dvDNBvWs(QhQkQE;LIVI%qN9o;oFTXgYN2lE;v679a33huTo`?K^G{0+!yMgI+O+-NIzW8SLnQh!tkD`RjIva#bTf{G|GPVj~e7&Q|uDOrQr zY%L3NP?|JkmrrJO7$=E4>S%eEKh3O6Y@6-GfbEPLUNuK;&lxJW1T#=sO8Q=xZPMvK z%3Du|l%$y#DO+Q38O^(ydbE1k&8>UHG#*b84w*Ps znk`0l3`b*tTa=ta`OPeVK(~qd42boJ!TqH!v?j2_uWJnRtjeN>+N}dI)R-xkID9u+ z_jrlpG36cWMhdqlEm5Tw*-MfTUPaohN8B%ZDrbKZ9L)I6qxIU*x%2avyVar>_P%1c zvjeU6I&e@MLue0CckD@i_%d9?S{KVZ%cu-)(Cxb`NFD}nc<-AB66?OmM9B+cFG#xj z%;`x+2!H~U^1%9j{ow8V0srDR{a&QbM;x#9P_bu(KcS<_mb7ZyI ztIw2QVAKSiT^rh2k(T=#9pdka#VaH9N@(GdrF}DYrkR>ZgpKAv!|hcy#B``~4j~@I zb)I;1sDK=Zm$9oesG~icaI3w|$o=`p1O{^v&UNIQdX&(D<7~{c{S`q)VppBvEYDc; zB%DzEpdvb3*Y9pFU>&o8TpbB^q<+j5$T*Sq7)#p%4|7akt~fYSlQsE_nTKnG+`Qqi z)r>mCwn60cY@I1YEVNupJ-E0W1kn9hMndzpKmG`kz#+J1x5Q%@csZE$HjA=9l}#3> z$C(E4s{fbh2;z*^LjL~4VobeP(o9)RYTbePqY`3F(5NhJ^D8mLOwAC>XR3ktfnob@ znlj;<=P&%QiNFPP)H3KF{Kn{ZccJs;@ukwd`g3QJfMT*P9_rr2QnlsdpB<@Je2nOn zNz7Q|iPqp$&4|{fFA6EG!A$dRD8(5G0#3Cm-X=!r5|v!G5e67frUbCqH%O~|zBy?& zGiKx2r1g}ge&^U{FRYu8QF}>1yCV)OM{jHXR@UuTGqxv7a^Ml?`F2{Qz#&@U!|{;w zS9Hc|;h~WsJ*%7(HS4z)0`Fyg=IqOusBn&NgNCyp zuR0j+FOI!}omga9bfDFy*FV|JSYpy|;mcP{7JK~}ge7ujONcKk->sYZYhC_an7lcRQ1LwI>_P zkUo2wxXGpi(su&ov0qmm=mt_6-){boXT*G6GLnmd>Y&$Win<;$hoGXi)N zyjqRO4pQ?JUF~F4=#(wt^&0jdU{oSw*CY1XRK+J^ut>eoE{>H3^=Owzg*1bz z>}3CDN|4bYtXlTDZ#IaFhmz?wQ}LQ77M!Gj0wyTCj$$zV?;(Vtdi#7Mg(-%Vm0yD- zWozzExPP2LzVy!*YgSX9y~mS;w^Chhg~X+j^v2{Hi4Zkr2?QA*528Whh@8)pI%wo< z8ZK4F0wOkN{sR1R;7J}z9SCd!c~`V!(u877)mN;Yk)1SaHnwG+%T%bidj$t!XaB?- zsMK1{Y;|q&q;t<@Y3F0LA{hAN1AU5W;>~#)h)6&Gd5jNv7MjZ2+x!_3Mk<>w`hnX{ zOfthjFFatSXO(-R7Wro}f+RJ}>iVgb>`T*{3~1mfo!G}IC6mS?G=XC05(f7@Lylmg zT@`o8wn}9!?5eb!C8xUgB@RkHy=Uzw46;) zm2lqci%(b|BH7Re;b7v|mbOUdr~F@6^Fu)O9x>BQz)79LypZ=^FN`e4DqN)>A~^X` zJeFU`>XpQW06l|j;d}*>j1w)NWXb(LX0>9`jy$)~P|LSSax?ZjMa)k_{MITMXtzE> zofi0MPO=(3a*F`>32RRF0ZU}8k=^`F_Lm=z5YP4|M1-u8 zZEp3gKZK?VH}vV_DS3uV8pB)0&u_WESsKM5O|kc$dkuk}8SM#)P77TW0uq?8L1HP- zlp1lT>BJ;*&*V@s-n6@%DihoLto~@<{(`v9HlOn__YA%E>M^h6%DB~A8)8Qgj5qwD z0Fn&7nW7}*Eb9>UFKgfT7`!w)sVp#0^FwDo5DKPGGbOZ_KK7JFJ9IvpuM0i>8#PlN zzCnzWWmeY6S%L9_s*1D4S$FZZxw9vst2LS<^w_2uUxheC+-)YR(hYSY;NZO&n)w$o zPA1zA+*-Q8K{{0qBLqwA+j9k{_SIJ?^udOE?8w{N5idOXP_;Nyn4hl7yKvW(etUXC zShHiI;Snb`pU8B#s5ak(ghZow%ls>fv(@|To4J`?kCnQpV*`of$5^@F9Abjt#DSjWID&%{B+6t)IZ7 zGk@U!qk6q*X^c7uLmT2}xkWR5+)}Cu{0$fc0Yht1LuHB3egiOTXb>QH7?wbFfAd_w z`eoh9>zy}hMAPX;RC!F^E|H$e7aAZswvlqQR5!XuNl7YbjqQv*VFu^CC}K_;=C;F* zAIWw|;f_d1tS6gu_7S0_L7uD68&a^IC-}VFL`6dhP)B=7k4WXch!+vvbp;TL2p(eD z&q$F?k8L6;8%`Cd9>B zdlZR-e^fJ&#L#F$1+8>m2;4OOvGBvGs}4j=HJpl-U!_hM*2O=pB85j=-+SgUcT%MC z9oIo=|5;Ax-=b29(lL(FNB^s zT~DE-Ak9|4Wvvy;APpj?f>he3B%fi^amHA7O`ZxuZ*zqpSs;=5SetMZBMYStZx}iE zfcunw1vp-10fB2t?2HG-ypG~(`_AoyuCFVO>Sv~}6^IrgRGjtf3GS<*H=oIt_nx(i z@GsG@!<%{|4CI45i-deYa%w)Da9Bc>qKL#ZcdI(z!lo2diS}|H+GuS-7Z=iIpO8P!BNstQAmSGY;?Ac;8I6F`Ce*#Q&_ zw2F}@M1<-_xq$V*x3QF!ZDJdEW#fXjoXxw5avsq4$IdefvgCON1UrY^V{BdHa00 z*DBI^mA?rgr9RuDsWS5XnMZ65YuQ*(&Ha$JEG%M|GE&A5wg^-4KTf#%!s<=W8C}?D zRd}i7H+iM1Ti8r)Ke4FfPJ6PA$?@Y^js0ORy5>?ca?xy6K{m+l`PU^S**VA7GqRM? zGfr`-Hy;<2RTha&=RHaMJfCUEx-f5TnhdM^Q12x6bFADXiN&f;Y1B>^Gc{mU?`V=J zK#*!@J3}}hdJA_x{{$z{&T9M)i+!A{7h=37teYC+5!rlK)!-(Xt-pBX+QTgJc%Ks7 zW)|Hl{Pd4BTXECpYJ2v_o^I&IB{hl;G|c?%Ee!43%gt>kLJ5_nNyfI4^p zN&Ay;X-qe>r=>e4&>u^C0PN0&2=Jn*NXnA!E(Dk)hy$BrnYcAI0SnHMYqo6EW<;lV z7|N;wrmu7Gi-o;td?F$#w+{xsl`BMR!0{rQ5!M$Rm7veF}1FFaX`SOY@gzq}us{l;B03170R zF0lCDwVyOAKdtG+jz%)$fz>CaqJ9fTN2)#CzX6bI@}_f*;vIWkJK{Z}z)40a8CTLC zNm=v`*JT}=rIob^>F$jdkGE6uS2MxEx^KJ$tdrD>EkxnkXQlUPx5kHTE~Cn6(E$#! z;VSb0f6IljpI8TaZZC?Jf9&l3LWv{lr9*NIoLB|A`Y(nnY$4W^M@vl+r90y=i!gek zrQ>70Q^~ipm)SH?T?^Xxg`I|8<2<7#(Q-`j1!7)#fzWOlVzWHH8O;X}R}}~)1XB`I zviTEpf5Y@6Yz9|BO9tXb=M2Ms0LB!~q(5b~b3lQt?hf5<(M}y#%sa{XfTebmv)D~- zstqwJLBXbaL3JbGCWq2jnRL``z+Db zEx%_MtfQgiXxe}&y)xn05-_CLdYsC3gkE37C0@G~6$sTGO?OTD#bHOidMv(Kb{sa1 zHYkNfWAcWhySjR^=1`6ZqyZ0Ops(4QBLVKp*0IP?bqBE>w6@N?RXR!?|6mxCNe_R^tzJ}a6Wm?$o=_nGA1)E=TvJ+&DW z1pz0lYNl%*o!O0%;XMM!dn0=^ME{f|xM`(4b90XVj2I5zOjH52f(1}eUf$pgI1S_w zMB0DQ@&=0oVLAO6=mFt)8G>T|A=NObL6aW<+x5L2eQ*mfYCzet0I60zL>9z~aYgY@ z8C|H)#yNZ2Ymn-kpgkVFAV-6)F4y^~CjZIR7l5S0K2z&%_JDzU7gM~@NE=BIfEH5L z;~^n58hXB4mc%d$1VyNXn-C?4kB z$8RF)^M=4DU+6X!CT?cy=lvnhLw>fSS!)~};)F;WhBcQ6NPT&-#w&pYx`fn;ET-)Z zalp7~)2-1j)tI&&0SqyODV%-N(qHj6KvH@inoBJhh~j^nrQcdrC8(}1B7Dt?k3>bA zDCbPHGZ`6c$Kc`c>aTs%@JqRf`4+B!f86(j0j27rEhxW<_#mAX>L*=%tljKSS%4ig z5eb_83IBlt_eLMga1u5l5HE3TM^9l*__^SxtkjPZYz(E&dFcUYGJxLzL$TUs6~B3K z7A8&ZQ0F*OCoXnt17hgi%K*Iv$nE(N`M7l^nPZ#Ld(e~6dIh|T*Xeeh{N1aX3z*A$ zKH7RlHTi*C{Y9bglxf~}Cu7X+<@iP@o$UZTZC$Mji;IbWoV;JF@OmwR%!8D?6&eb5 zS79dJLBvC}x*d+Kfm+m0Y@+z{!lWdXlfSRvgrbU=&-i|z*R)eo1@gD7b6(!n8O;6| z7cARy`u-ks!{@uZxYc;{U!fl;BmD|mn+FhMWmH8*RQISRX}X=qSGRn4JC#f>>Grr+KgkE#RhzdAnT{y~m3 zNHm7!T78*C_6ANyjPfV-6p)(^90cDQQzXsY$3{^A?-S1b@}bBl0J9U;fTNO``!qnP;== zUVqREvq~hT!`Bk!gr-6>7 zot3QKLNo7q#r%>RJahXz7H4!b^KZ{daXE7(vM&sMjdCpK6Y12FH4rQn+)7JL)F(IVR=d=_%TDtvfw25Juj*_sYD0? zY`+{(m%)`jpt1vVw>#C>)$nR~$ec0I+pgp%9?Ii}TF3~{1gseR#OpKN70Na%EMpPA z2>H+5$S8zMf~l*2 zIvF)0_+bnKXOEu~c+O1{$|*d@!{ATZNl`U&7yI=rk?;uC;ythDaX;O%L2$q#vbTCsW<&j-vvR4hrd{!f77v;-DikcdDP z<6|xyW8V1JNvckIG;D5O*uF**$ZRL(1ZYX@V*!-^DtqW3GVbkz6BYWW=F zc~-5=Y)KpF+4$=I9TxnaU9-HV4vJo*mm7lx!8J^&QNS<0f1aRs{Uy$+-Wks;J)mm4 zX2e3Fl7W&;gd~B~tDf39bt4o89nj_=i(E8@*ExWxrMmc=cZ^S5@jfEtWe1!i4z3{TNCbvD-z{pncE-b#D7!r4v3E}F|{>zW;T zx*R8@3r8ml*W-=0LLVVmoakf-)7{5t4ny`JM2BP3clC!awtzik;QA9vr-m%G!#|!d}cKn|f_*=wPbF63L3Qc&GQfBa#=_=i-Ob&&| z=}GYL^q&-3mkyd+^dBj4)#4j|d z!EZh^ovlgx6sAuH!ZAOiePn~HOD4A0@i?em>6l}S5<+X8HY~yT*iv=k9`(oR@;fKg z-0epqZbtD6+Kc^EgBGmr7{*l<>2^;c=5{^6wPTKR=U2`zeFuI~3>E{dHQu3k6r8A!S;?l=|GR6$n-`^o}j$*8f7zt|I}>4K_=E?kzW?XD4w|Gnbl z&lhChfNFE1^eZ#ubB5|K8keu-EaW*nnS*Jed;92*dGva%j;+a?J69?gaQehZU7(yKpIEf}tfQH|?}!%KpoKgrTqA--!#h`aj_v03ZLQqn42n*> zpl?|tv!!CF5p|~#BOSgs^LX?$BIK~EoBoXxNj;n#E~G+`aF-VOzP3%|C+s0Yj7s(e zj$d=9VK)Z*8~lUhY$d6Ug)$s)Q^&8-brB^QKbI7=tpY-F`qIO2h^GiZ*l*c*vXKN& z%0slL@6hLvh&hU1XUW3kA=XuKC^Zyi$H|6Uhid+1WkZ0h=ISsD@`&+kJv6qZUp4%z zDzL%%B>gXQB{@Xw{C(p@BkH%qYV^jW=F|w5@0MD>*o02TLSN7ihx5>#B!j0b-O+Ik zbR=uh1kK0{QKM-?MGM1>mbk#Tlc)$XZaW6P{0h4_;3keuc&$NhEmYL-XJ!I)s|mOVV)0mez~nX3dM zzMFvzy^&Dyt|foDRs8y@f|$;p2-?8l6s+6;&o)$N8-qLk|$qSCM@ zUq@d7{0tXBPcD)eh58hix-6w)YCUwsLtY1yf;4Hljcz~1MrIJmiy#QC%Kj=q{kvy5 z{2c<&1KYU@g@+Qt7uysKN5)I7t}BtaD#{qzW(+E{!bFl$u?4qHV{y_=^l}~FSwZA% zl{qaJ517d+^58dQRvj=Z5}q%foe%RvZozNB`Gn)wV_p1VN(cS?m>vKQC`W8UY%0E_91zqVMCB^fR z54|l33fr(cXj}K(X%VLnvi)CSIXBP=^dOQ^Coy*(lF~Wmh-EF0V2?4q01mM_Xjqv)^EDL4L73~0ZAOFNpLUnr(HoY_ zLy9|Y@2^4a7eV&i&Egarkh2zbje%Gl%{+2S_YSR>nSqTCyk*}waq!{hN)&p{eFc%D z=zZRYu$IrUz=z`HBHEwbXUeS8+~VrJMJ=Mb%;!X3h){N5z5)6|HX-jFD!^vh=;JgD z@S(fBV&q|c$pW0F^aa#P6MDZ<_!ufuW5q=iI@&H$&&JYY%}_-U1V26hRe+e1u~q7UFSbB8Wr>fI zBf^${uTtabtr!y}CQ-qvDLwARtI+GN!ZYv{X1|AbIn$%0@Y88}yAEG9-@ba9FUbAw zy3V#qD?|d3Iz>9Wv@`3;<(KO}BFZEA1DO7g>Xd>3r*qr&_+`Q8Aug@gCs2IRB*F>_ zNd;<<=EtnmbDTvccW0MS`2UZOoS{IB?Ms{ev;)v`2!%#A*~$k(>y`A0_eY`q>P>vnTQc6A>TDC=L&Iijkqm zgakvB8RtW98{WsR<^S~yR?(20UW~7QREbW?A^$gv9VHg6@U-&&H^Ah-Tt4*}WUs0;_^4z8~4ZOg-&&W(Y)OFYxOyR7S2 zoFipnE;Fxx}D9_J}wiC(E@nzTye%0o8^^B%9@%AK_LZ0<8P=w%mHYw7< z*i$+b$%syl5p{gYwAwVJSsbi znyJv)jo?dsR2^10d3_6KpWsxqh1}FwNw9hk1~i`IettL#K)}^QjU~h=LzyyC1h2It zraec3N15;ome7o^AqQyT!P0)IFvs`JQf~Q}$3#%x&Vk@_Ob{6P5cZ(~4#`NP`_m}s0JFv*-M z&OUGHZ9#sCA-jwxBVI^#8-Re2@%UTr!2PEW!juwmDaK=YM&str1n61=>oji$0QVW| z*Aq)hKO#Ug_qR&{)3D$@jP99?RMrgEV&80)H)vb8edGZufMu(I98Z4}$bVb#w1R7GLISN z@-t8?Ep&b>5s80&G1^3Kvw}X>Hs$PF&sdI{uIJZJs~+Yq$qgE1{!w_O%bqFJwj@c8 z(H3*+^M`({<>~mJG2BL(O4Ll z(Fi2K<)d+Z-RMMAt%Z|dHab8PI4xv=5UM0QRP{J9*G64r1I}UaM;Hg>}zSRrMn})=;|k2 zFQ;#?#vyeP0O`VuY8~FD1|BtvJxe6CO}b6~oEh?iklW81 z)(0=Eb%%nqAOwOtYHwpv0038jyEy-}Senb%#SVO>eHr3vc7lvQiNsBSyVBrZh9X*a ze#|H+WfT)NR(leK9~xB?5(?>ZG{Peiio=`eD@)z*+M zz?*a6>4ht*G}b#eVlVVa$J`J5o@P9V*s0%#drmD&Z_G!I@+aJmXm<(38T#?R^Sb|_ zpKmbTe1OM1b5sAu4aoj2huPzoWwteTwaNdF-6h>SAMma8`sjz~(|lCGkvZHgWJQU8 z#+>7rol;Y9ikfm~25NX#XFLW${v5h31ap27pWFpU=4`N7$9g`<@~~EF8tHf+)#@6B z$cRqNOu!U=0~9Ec%g+0p&f&BdN}e-*YnO{dKP2-NoLH+f4p(HAnZ9IId@q>ovApVO zFPo@i!M0>{n;;ppc^hJ(+6CCsH&-&SY**(h`s_n)TUYRI*JXIf^@3*7p=q$9t~1GGUpZC zRDI8`#MNaY2E;(SmqK+yb%pLh{C?BVrnCg_?XU{$qUfX4jgL992&6*4o~;ewc8vD? zfj14Pk6qro7`-xn)R-#&{dAtUK$Pw}cFtvf(k6MmANifbj@qao%vX-KjM!>}!`_3Id$0|mr`-0inS?0aaerT6ls9gQt?6F^MK_iUPF8|+3LnkE&S7$ZG8;3 zf;1A_Tk})>pWcb{0I?U*;KhP_Gow{lT3>poY46cLAM_bWQ%Kta@|E6`%F~aMffJSK zVrdGw)~#NB=js-yScN)K0-&V)e6~2>Dvp5;MCG)JZ=>zJU!|TxR|+uYplJRYf!jrC z3Rtju@~CtvKoa*fJDoa*xgs4y^a9$*C48L6G=Xffdig$~012V~$ZebN^ofEIGg$8- zsx+5dnI`E8qR?2-+&FipZ!?I9bd&aBwlskRoC&r*3UP~6b`_uv61V7LCQ z^wNU2{Va7(J3a`2*TBP`Kd%=<9hy6NGxbZ??$r&4pZHWKcM=rTNFi*z7rJlIu$7&G zz)ONqk(_*xv>P2WbhnDDIU*L{tEnhuFH;&&b$(?jKj_GFvWX_7J|96#qb^ttGH2V? zk59RrL(h3G6CJ&!O(AcJw0jyi^71Iy120J)2@XeP49}X8=L#7@Y3Q|DUmRHf^3Ldx zCqEd-R#I|8EiXg7m^MdRGMxwt@VzI}^>Cy65V0HWNI-_t^Z85#LA0I~vP&SUTt1?J zug(L~nG}qknCLO1r0N+D#BgAbY{@`LH6aDKQ`FfIi!yBxxMxA8!WNzj!^)SZK5mPD z4|F5lWG$&C)P3Z<^kafoa%YT^blQ^5q4*XU@}cHPBY4}Ol`sd7!`VAEdm*K8_6}v_ z$;Svq-nh!A&T<2l^)r0Q-eSTZ8pA)W6+*u8lcs;fNS)GR5{FL)@*<`As(H#}qg#54 z`BqcyJ(;nsf_uD5v=1csHwHe5Tc;#?`ZnbAU7~5}wefI_-SmzoZ+z1;J(W24k*gg+7)VF+yxvm0MnNl*E6cwDjer*y)#+n4i=RLi2@e?9LIkdeJkXWBNdqN@(bW7{rNr`{b?tjFi?(@l>`8eV z3ay;{`Ru z{FkScAA+vjB7Ou0Y@<9}FMO|6TYgx)(vyfT8gkT}V!rw;Q+dY}xjGCSC!Oqku>)Bc zcFIrFbh=Or^u3&M+Hy7E<#E2RImd7xK7f}qoRGWIn}#tNc60QQuN;4p-TK+YWZ3nk zSC}wxSB15HRHWhJ>gUo z?P*EKA*gACB0jnpYxf-`haEceNTG&dCOVmv)5ZN*TSwxYHR$tBdMJ5k+km$RSoQ^y zYIHvEY$_g>Zu?d)5{*FP!V+_*9!R!;n=a?$NBe3&_b6WU$1=qi?zc5MI-JYgZ5Ea+ z05sJRIx3tR%l!rCvgCNYfNAjJT2AB-+%o%3e%Lr@VSFk;{4gWGG!Sj^ZhtS9 z%*Z0bg7fkl>rzt8Anl#BYYb}SmlQ~bdd@VHC$KKWW zDUF->RsF#G5U_xNjJuk96?HeWg~~j8c8B_Ussr+HE##rx+?Fd0hR&6Q)emw*v1{v{qkP`%&iY}xy#Hm z!Rv@g;5{$#pM%$EXRUnj6r@MAb{$P{M2FJR2B&WoLimJe)K&8@s(!{ zItS6jJgZo^M0arloikpOmmM}XPh)zO;Jmq&fa6r(PNtl}LT3ell~_?z*s}2Z#N?3X zo9!TMqwen>^aQ-)`+r(co_U!S5^ zG)(!FjVYIi@|NbgiY7NeEixY9?h{ujq=o!ZWkSi%v*&z&y|MOrV8-@r3ylH7_y&qC z^8Z_RdAYHLNNxpO5NDv}rm!M!Uz||7X$a4R_S=KD<_~1?OomQ3Ub66=RLgsKQ7Y+z ztWX%7!XP;lI?HZw0}D_cP|zs!$J$&0+uQXcWh;)^11(Gtu#|MiWdHFF^8fqgKLQ=; za+QnOZz$H<<^vh>E1%^}zH+gE#P7*VzPKb(>u&w_>gF^)Z~1xk(QM>Uj>%rnje1;D zhU+SkkQ>aS;^8#(GkkU+qDN+7<|FCqpk!uj5Hb6(6gxEPbRoIg1v7~YVHkWx)gk<+ zR@G>tzMsZlg!EHK-4qk2kPDl7K(E?nl1}Jn;E$IV z=1wwjV_8HJ{yDdTJ2w~)z;uG}_25a3Fl0*6IYo0L;jWbCU2IYYk~EUkG}YRdgAq*&+S>g7zX2$N zyKLJCENol;q182WPwh$LMG)o!aF7$BKe*|<@rR}c5c1QdK)1o8Rn)c;H6BCC@GlAu zm;&27f7^LtL+rbY*>QhG>L25(F}E&7Qqn;jPgqI-9a1(JfAP$B996g^hxRjt-VC-6 z*s<~!t_?U8Wda`6^ITsTUYYDVj~U;jvZI9Q1lt)N#&~A3at0hzrE&r8A|jN+XiRX zs0Snqa`kpPL3|Uz5Zy~UK#s;5ae-LkklAkWqqF`!{zwkuVF1YmYLy|Ki%2?{0 z3Y#hGY6D?j^1w3rRf;2Urse zg6qn2L5as9xVZcLz1mMOO46U}3xytvhx8`kuzHaxi#vH~y-e2~vA&4CpayTVVb6;y z-ivphJ8S{A7lsw+;n^(~8>rjT!RL-A&zoswSly*8{9hlr+I=}`dLN^dv&3Fuz{C#Y zjRZP{NsV8!-9|T%j>hkymq{Z$^&qezbI7%3A{*lo6(Fflz~+8aX>?cj?gjN zXhD?oTW&!Rjhf&&apc~C%ftzbqP8dcWMLK-N3h6s$XAkRht>p_Mw=_9YXs32L07cPm?HFleLD0IgMnQIC zAnkRSz$@aQ+|e{dwD_^ghmRqw)_%dGRDwG`s=aBNg7J!8Jn*7sW-^QCJ^YS7#B)ul zc3|!^O`4cD9qDMz@ViK)Dz(hM^A(M#mzx`R#FsZfZbU*HGF24$+U->k6p)~fzm9U~ z_ufOgwifMOD6~m7h1uZQ7lM6-e+(FlqMZu@%k_smG;reNa7aWxJjNQ7rb!)t%oBBV zp?Ql7l&NeXzKMN!vU`Udh}f0PKDA!pF%ooLc36ge-F}648+A(btL-&;BKllOoB%=( z8B-}ZR%?W3J+>_nUp5a4U;I&^%w`Bo?Uq?X@DtlUna4%jBMs}iRiGv-t_7>;m|Aw; zAeh`RD{~6spG3aZ8V{EM!CI#RwDY^~4MqLdo)+~Q8{>a?0_>{xcMD`h|DOWaxh`ul z#Oe=$p%*27Rm1Ip18_#D`Prq0tUk58S~w>a@pN|W8St(P{4jtguK1lINuzWwnSm{8 zrVwD1_*C=Vr$JzUPn({_)D8L$OIhTI0t*%p`&JO4#|)$65WP^h4?;u`#c(vg zhi*Ip$r%v(#S-T#pHFmH_Xn)0A$J-m4trT}{gK#5G05*IPL%oE9{$8IShVH%6**Hzs=8c7w&H@$=}-wxcP z0fK<;?Q2Vxk*Um>q0b>SZb;gnVN#pC+xl0|^+1JF3;?8xOa+IpQ$>JH>Sr%XZLxk) zAfs0aR#;f;?q4D+?#8okVvjm#p(U>)$;P25Z%@;B28Dy@$%vN!{LqT-AMxuX?cPAd z6^zDK*s2T}oWDa1vchg;Z#N#L9Fsn^BA?K}3Vq$tQS~4Y{*e>4?yESKn8-;*@Gk=Y z$x%_95Q*d@lQ&rAfC}LSlI;N;z=DceR&}Wt$PbN_Z|8`l%lhG2OfPqvoK4JF`cfMz z7Lby>DQnc(oijsD%cVNuT|#teOaU)OHjX@6B?CDD*__(6Bu|_kRVWv;m_&h}wijs) zoxL7zkyHhc)Y;PP3lu9VPlDsW1{r~6a~hnif}=Z(E@$%SDlHV*tZJTYUqTw4Q1me| zW7)_Db{j32m}>MepWv7#c1h7l7hPb1#GYHE31Z1ni~9>wp9wK{JBFmrb6kRaip1TG zd_pZjd z?Pz_6PSBSyJ#Y$yL6{TYm*(gxtw9({8a%!Ok2UA7Q>9q2U^nFC4Mhi8R*j4v&G5^$6l;Jm<`wg(<>TZA=_r zs`i03Ld-2bzAz9h;2-`|!-X4n??#dj?$c!1Y zBz#fva*P1S7kJv6&tq;s_+h%<_1~ToKp3R;jReQA&FqjP(U88SU&LQ7iw=uSILuaD z8t{2u_7Cr7vPkBkNneT}pu5YU1J>P9J?+dFMHrX{1mmfQ#f5VHYSlrh%s>UgR2a7o zo=^S&;OYFA0~dP=Ju{=(hJ7a&*bu9CjHT|X&Y>z$yOgQGb`{63Ed;B!tV6vPS#>m?q zJRCHUt(-s?>?#}jul+3kQ7L>2zB4(uF{M9~qzmV#);;7tlMP8Iw5dSuA!Z+7e9EIM zK*b^Suk>he8%=PHsrvJ#Y8HsL>;$=w-%R?jlEG{*RmjVL^!(1$RlyB{8;O6wHCX zka;$lbn?D)R`7ghIOUErP6D}?t!|t;@A~TI$77!sSs@gSLOWM32g-g&%0%mcj#nH5 zDF+|r0f06sU#E5MZ+f#(&i;cG-5cZ;d1@1T<9Ce}+j?ij>o1X^wMtf=^hwB9@z+mH z)}bD>@pwh~adQ_oR0%<9&{%}`8R>2)nhG_heTb0eDbhWsEW-(+KZ8Q06^Yy(O zysAl(SH4<$rDU0}xP5LzVt3{<$A-YKfvroDhHo5;C`FFWG-x3eq#QTz!pf&AP!q42 zQu*ct+H7boIfAy#5LHme`(u!F)v9Bw5dd3Z@OmRwq~ZLQ>p}MPZzE_KoV19LbA*wh zPA$J#vCar8cP`g{w+8y|+YW85+;7S$hfHl8n?<58vGzmoxj{b7VmLsGY)r%N@ta3}8;iW2BY875+ z(jTm5f*eqOiAl!c8Ngbc7@yF;VZWjXxx5c>W7eEELW(!`Q8EhQL_hb+`9qYx_b|H+Vn&lXKo|Dbt#e$72xE=PP7u`ZeL zK3_he3QzybTm6&vT8=pVX;b$n#{RR7jQM>_7!L%NRDd#uA$0zLJboAp+E%@X2mM3< z=zKxSezfj=&=G`@ODDi?Q*veO(^2^$6~X*PHWIH;R_&5N!y*fTHRNC<%JXBSd%=-q zz6-P+c%ga2id8a;qZI!rzWlz~a}GA6SFvMUIj^ENj-|0uRq1S;04UI%dc@Aq5G4A9 zDc0x&h6TM-j|gHOlo;8kyw{t32rAvODji1JtK>LMiLx?$tI=zdXDPz$PgOUrnHHJwXzLT+A)^tm#>bwYIEYo5V56ugX_Z1s6m=CwxYABtQ}|vRL&RdyCks52Jsj2@f%%9% zErkbukiwFGp44tjr;(LXK(iu?vxun4p_(Qcjj{O}=}lluX0 z%SI`(I)iI}2%WaOb{zT9gcYO{OEx}DE(eA06)A#?Jg<7ev4 znKEhC;xalZ89C~Mo1t$UYlR{k^oLqaH3$z-x^FCvt18auqmr?;moCUJo!IviiE;r$ z#lpoAkyzzp@)|Qg{vRule|7zgV7_M8Ir4Hc0|e532n_f%_V1E0of_EE$`r;gP?__j zPbn+v`{G-I4dYhxhoumm(PE*wkA5@U<-_M)^8aRL6mdqoRBP%d`|Xf<)xi@L%Oy6~ zjh9RMYwzP@qHwtG+TT9nZLg5Md$T82#)Bf@0~i#5fP!%oB~gXZciUr% zviXUZ;<>=!?eKQG_6B7ese^dyrH+;jadYgwf#R3G!u_Zhm(Ok#b#ON?g$0f2#pcgb zC2OyuIt7D5k{qWNe+}I5+EzsEcXJj_?rmd(P(|bpkT|>B1`TDRs8|l@va@SNOM6#4aLfG5Z`ej5$$EAeiVRmK743v_8{BDMN-ruWE|`q z<1g9TV^oUgSzOSN@pB_ldH*7-eBe;my_Uq!MbO6Th#p=$3YTX8-<}X=PxJdDT)~rc zW{z#fqeA(Vshm+Ugf~_>;ao%Qds!iQEO1nJFgh8Zd*^QeMJ7$AMr)$rjs`r}3;?)+ z7FT(DH@S&85qekPRVRX?Xw0xXqL&B*YyBq@L)f~heVV`U3)Yf#lbzKDY_ez3@xg)} z)MeC~Dk!SR3K!9qSU$Hai)xVBkr;fb>Z_Q`)CvN566PD!|5`@gTfhc+tdIg6Jcsta zQxNLRa&Qe-&rlh;X;<3K5kyWSOFaUdYfDj-XTdx~I2bsuLmc8JOT#0^+Y6Z| zFqhrW?fo2`T@jT;-45{cK9Kl4M`sV#&s3xW9Ig{;6vBiU%;0%>8AQQQan9Kyd+k2C z+yJ`F!W}~@$zcDc#by4YauDr2oA@qpp=mucVA7Hm(Qcyleimd^u28LR(Gbi(YrlR}wEONhTvSBAg}1GAYhLU3jVb3&>(G;k0D^%SoG!M~9FLj8hJ~#H zk?HOvM*iHijA3^mJxsRnDWI*&x4`9IHQPFhbMo!Z@LB#mXO}lUUGp8tRUcX<0s_%(QkTM2|vR$q`_gOp3$BAYDEs zB~d!EkIwoA9BkKOOhLRu<%rjd;g+L;j#*HPl&WEbSsM8T1_wF{lMvhEMCF1KK@nuf z>fzMZ#Lj4`1%w{6uepW68GE7YvPU9qp3b(0#afu`lWy3}GbbLjO9&vsx9^21a*x_l z1MaDC;$dm@Cb!)IBkTJ(wN9_`{bijH7Bp79PSAV7RY zN_6o~b|(_%&NASUByiOa3?@=Rs1-&<9BRF(sY|$N@~S7Zxr44RKU}x%Z=O>+M)A8M zj{ZnU2$*Zta2!Y97CpB2A1T!aj#llUYQ^QaMJA{LHkB1V8c|-F_AOp!TFNKBy*Tcz zr6P-|6NGyTh_CH`17d;X8*URVr8bck2cVeyGMoTVKI28d5E)tTOp`<2Kr-(U?|{k*Xv?0lV$AQSy}8aT?aGyv zX3^WPx1;)mV&?AtDJYW1>c%sf`CaMw7)qKrKjF}Axg;K4cwrri4$bxm2EyvHmkZA? zfK=qOuk+lx?q7G)SHKDlt`_J&gd`4sT(b40^yK8PUt=W;BHA6ZI{JoC^_*y+Yo2`- z>YmBwb6ln`3+%j0cf>2;(^twncJ}WS%W++yeur( zahLx6@>q9my3+K8c$tjNGQGM-ouDTTmTSX%MCe^>BKkYv9R1@7>pj1uTtc^w6ocWJ zf~fP;HJ=Bc8guKs%KbuAkw3&iRlFyassAOzIfJR}xKw=kLqD6w{B z!!}ws_;|G!N41hVkn?Y@d6iuTspSH^J0O_HM>O^5fboeYlPh9EdQW+*o^qY=Pf#`o zKVelMxaN(1QEE4{FqMk@lgg_Y`X#tIlGFwM93TC%MD$3nZqvDfVW?73hU9+n6L}}2 znY4)R1J^7SXAHT%d%(b^S_)N2o>p=e)z59+F#=o^%cYVVEr3 znY)6+-ZSt$f2k;`E`C#F%`yv^?S38)d(I3TDij83Tq6%Tcqa;3#Hmy+2#n749e4v^ z+!d!hL9YLu(z0J;z)W6n1iBx;B6wnkE3GJc}%{FOsILC~$b>HPICT^762Ds?| zdj#ZYo7wuj)&w2b1T%Hs8BKyq`(3$&t-mD+idG!NGpI;?$S{WV>F7%=ji~0_s}iI5 zEXez-wGthI&TrF3P-?3~4;4OOYyZMh{)r!Ffnyg>j&Xf?NmXD-)duB3pz!mUs>pO2 z(Rt~H_Za{(a0_NnGRC(^vJGg-1`4moO!O6WVlbI&m?0y;L*UY=7|NuAlE%yovdp+K zeg3H;VcUMEGHROGi(nG-h`ol?ijr!$Ctq4LQa#1aP-~TvUXcYyS1wxOD&u5$1%== zbu=#`NiRW8WAGahA+#a7CkQDP;l%?ZG_(Z%CSry{-(o~E-LdC78e|Z$hw9a#C><#T za<*dYilF*K0Ae}Cb15HUa&!~SD)20aSBn`9mu{RPK)J4#rId6!IXzKX{t8;* zt~$+(M-<`uq>Y$uR!94)uw<>rId>*6O*?Egr7Q&ZAV@I zd`npC*R#bQ1KMr4c%A50mNF!RvF!{!s++O*wn}l8XU?7s6z!fg@sS>j;!(?UWtg79z8^639lP5R~PkHbv!9>JCQ9}ztT#o|`J<@yHo_z-0a|U5KCvDm zLN96nq56R=$$7Zk=x7fG_9#CQ_i8Va=3y@Qi~jXzQEz@f?>;%ut~`mlyqy%KOzf$1 zyS`(h#pDw?yBF@)9opg#lpUF-*uv6sgZCXZ5=TLqRaNigWk)dSv3 z=w!G2vwaPj-+&U>zyB_57oYdgF37MPRONVlBSBx0s%x`K7s5ZyRkWeJ9 zQbsx6w%kS$CH8&iw2(qo_O4HndHol1mF+Bt>Hy6xl3Az#Z73Vk^X91Ncq??mbJiap z{;mh@%XhCF^Jd=&ydt9!_(1i|arV>qH%$WTEARJP+XXzT@25j+D{Fd%EPIgE6v^2T zTD_>Q9?Bm1>;KeHhURjRh!iop^FE7t6Gv6;&d8oD$#a*(_9*!2q_{OOl06L5{7Lk> z0mD+ghdk@triY9f^l;qE9WBu8(F`nuR`l`+R2%?y*n+mUg5?Biyfyc>k_#HM&zmV? zSHu#=6I?uZvmSguc0Jx4I|5e48@HKGViJ^Rx|(9T2UYbQ{&Cj_Wt0Wtt@Qxm=@|$U z%<^ed_$!b}hfaOtl-8vhFn`yjsG*{PS@<_#tC#tVxn`*__%-6Tv%RnBLxx0_T5}71 z^)|kIGQtaXN&r7$o8bEEaaUjmFCw*EVf^scFeuQSei0Fv8X0GFY#14x!|&>bN{aC}ChIWS)~gdve1qoU9Z zfC@m?OHQJtz_hwY<7p1q(LYv*K#OD!Wb$+M9AGa8fxpm#U-3X_V(F0|lqdgzHIDr= zy)6E`zBc(swgd-^1i#WYJlUuH5Y0GY5VBlyB)ci~<56?O0*jIA`XO|tbE?rjN)ko$ zO=+v4Z;>u~25tV@p{C|qD)ze&1_snwCUHN2kU?XY4CDI@6m-rBDJAzHtB->6$ZzH;860W7>iS?kXb~(tY4?EvmY%Q|6(=V`fCDG&)WWmEHp`QWsdR-egjA1Vm9hp{Sd&J4=+RajeQsh2E1#QQ@CF zEFOeJ1S;z0pzzOAKjdh*aW7AeG#BEw!u z$|kjq_QrMaXWsoLLcASqVQHKWGs-7$P!_A2$kbcL7zAOkm9&=ozvHzFSv~Ddm?ghz zh^uUy+PDDXq0~u9l!!uVfmr$ujtL&ZvY+>Ura`F;`>{)(xjD1BA|Uv%kbGdotucW` zEj_ZkN|60Us#s3NeBEU^NePRjNQfaWOhR8{y{D#ol=5)@yJjxwhFUF9C|358QBV!q za~Xf`6+L!>4kNCKizc$ScUSg=K^bv>bWqojQCplSV!gvp7RE1u9Gq%fj&8-N4BB@T z@%6gnN`seP$JSR}Nj>LI^djRejAgOf*FI-s5gd*G9AR{LK!DDG-iUOfkb}}pf2_q` zST6<|MjX>Orawygwo4oAmX7}Ub^g2KYJ$E=t zI{$l}`uEjOXl*fYKGG+Cdx3sXevM2t&$ym1w6|jW?0^j?CF0i_6Mw&``7C_Ui!bH|YhWEhM6ANj0;)N(Oex>|aav&bFgOLft;~lP2mF?coHR^s; zo;)>e&(6Ox$J-DC1wGtYkA`;vYMbJPvI{sAxp2mknHAb-hyIEvO{ick(2vGC9P= zRC;5Zi++PbK{%Bu{1)WHrRW4-lI7-Ungh$(JZpZ|*zqY7g{fo+GMMmTBo%&GdZ)h0 zbuC{_Eq*yHipk6L9?3ikPX-{h_}h^-xb07B4QCu(Zt;=mS0e4}jV){a_xWB}@%>;q=)Djm7CZn?@K zYmwApWQEr9RY-G(gcwgjG(;fl((Q`XX7C1az(V!mOaljk4udTl|H4r%1vp!_k@FXA z9)#TRjQ`)6cwlPV=GA;kyZ?$v`~j-l=)d)>#dp!xVfu+eQ}3nE8&HcfD)ncJEc6ho z!Bbj}Rr^vHeJ54Nxp;ql;AUcJVqGWV?l(>M8?cn_V}8#rKb+Fyhnok_@}%NN732V{v^K4S z$b4bk&;bKu!n$7@p78$YcZ7m>dct#b=0qN&nfDr98!x`H!{-n0M{6wFBZ}cxdO;>JwJymYi zs4ltJ2e`jvYd#g*$Zsx1x_m=m9HmG1(nR&o=vB=b`$E3@@B~cZXduf&F%GZ^X92(< zWUAL8BOjkRzZ80QqabCjaiwo)8__-+rTNzk_JbOJ1k}yI$Nad~B`aUl5z=!tQKH+I z`iDo^(Tt)(FApf?>@(fn0mKZkae7G+y2C=1-zmXDLFJSksy5JHXi#)B?)i8w|P z55=|cMX-c#6q0E_fN`iN24(e7NUt2jud-+8yhX3qfJN&@+!@)pO+E9nw({A z#bK6-sucQ9vaua~z0&%N;(hnugsbnLgzKlZ;g^AAzX5M9hF%Zrdid>T*i$}m4CJsO z2{023;(+&6-UOu^8Zk~NH4@L$=Y`EO{DT7=oJQp(BHVb+S77D}!5ZUHdHb9Pow)#? z4au!jCHA@Mfcf$1HYuZQa;IBNuA)per2>F1!bf?@K828THfq2QMR@aFkrValObY4K zovi*)nNxhe7Rd!SHf2`^^r=?TXQfVUB3qBH@)|!r3;4n#;&978HKg@J#lRDWN^0(U zV@Owt_D1OvbYp~;XU%92jVJu)&W+bbn(~W@ijb||o}pVLp~pgpO}I#$nuTxlFZRw4 zD#E^G)ND>3-R@U58*2ERQO~G<8S{9IVidLs&*zLL$6%#A!R91X{&z=mMXiw(@q+4f zLMHPSQgW2`zYm9xbImyVkER#Yo>DJJWsUOk5bD=crS0B)gP6_vvw%-u$l;MfW5cT!Xt626>3Z$d{fQ+VljHGKvBf2gJ9HFq=mcCF*$k5 z4!6Rg_E0HQSC2_}=K$hoxf!hX>MAJsUl)s==iYVlN47FE^mxLYsiAqK%vYtEdzDkpNA;R1BA$B1pN!qV{sWBHc^V|L z%f3C5^`c?(US5kOqei=}zfZ8U+O0qxb*1ZoT)~YrlZKpUr~-)*9w_ zp5Hi*&+$qWx?QA#ZWpnj+rEM~H&HK@ln^nY|*=rr$CB{YDXsu};P8wYFJrU8Oq{RtY(zas#q(v7> ztYZe4O3=01?gNhYcp3btBUD=PyKUxjKvQ9{JwW^cSiutB4AMyB(}M+U~M?3 zJr@bR*n*3eDxn_cCg+8+qEIDQGmdzo+K;FcxDJe}-0qQvLbjkke-(zl1FwaJGnIC` zzwz(VP8i2_sqRcO^to=&xnbT;+95RvuHH?q$o_zhv{6cvyj!ICcJ2gRQ3P zr~wQ~p^hQULoCfe*ys;k9enZL)YB8iM=`i-u;n+>h1`swlJ3wGKeUdyxO!=BWnG54 zH~A6uEs_xuem8koN%?CQt~FPnPorWd{I6_8eDKo#!n3klrMG&X)goOnUmZ$6jJ`zq ztUD^(EI^G!?QXjqdsT6TW|_jY z&}UXJa7-YCABk^mE#jpOKmUi1mOSatgul5uU@%`k)Zf$C`e0Dhp&%c8xY}926{J3I z&+Qb;PJeJYD2&(Kq{{K%#5%f7>9E}-S!i2nnWP3lK-veMe)DN0)vR{vC|Ykm3ppE*&Yax2n)Ua|Bwa7a>3Fv}s(gdxL< z7OnE6LIH+gkA8q^CqSpOePh0k)73=2pl&A_HUiOdZX@a^pw<6Z!dPN9;{8s@i$FI< zq7rf7Y0Ob3nj?y8#o(^Pxf<8%&rtcOlnGRK_!8e(}lg)*h?9tqFZ4&bdU^( zFLdGKF3@yj_An-{cC+|9sVlp6VT45yN|Wg=2xehqK*{BO8|mUU%Hpj&W7sxzf4#$U z(;QhojZ0M;0y5^b#wklx2dD!s0f34cjJzT&RXMkSL)_mXLI$q+1qa?;2E~>a@BQ6< zlux_>Akt^@1XtV zpI{qph3rpknHV3_q=glqH$q97+gK05+{i-M@}O639ZeJ^{@S++LF-IfP8MiQ^MnJc zM=b8eaUVc#rRfGoR@4a+l;+5Hzf;e5f2W>zaqxvvxx)Lo+E%r7UMlg%1rVC6DCR3J zS8hk`1+e-m$g6v&<+2i&ViH89(`mc}va!yj3_*k~IzR^MzPfWs@pS*29p1xTf z=VkedW=UR1SL9NZ*$?d{(&*VFz@KosVRpR>Ti(<&9V&33GwL0c$_C%AOSsTxBjrkA zGw=;=VR(XFby0;1o+&cG%48bFzB82nvH!*!XSxi4!fA2nwH3aWFpm8BD|9Xb7)2M~ zt*5`k)!;4{yx4+JlUE{zfDEPI_fZzP(Z;|ew^h~`EgeLyYd7;&QPEJJ3K#R<4Me!c zb-`2gCFbx=zK4(HjY0Q=y!RE)@*)%v_VI7seD)u-V15hF&L7!U_c1Pqmh<5(9xt%4 zZPOWWZ476 zS^*6wrt&8sq@G$=o4-Eb+mVR|uzRB0D#e_oMFr|q0aQ51)W>c;>&dM8GHzmTVfxZ8 zYqbkH&?}$@;+^l)?`BP1)4MJl+I^Q30Y>8Zkk*&_bOvl_9KXriALxB8Y*P9^F(5jh zvO6SJ}7zh{4J@h$a+>xZHXXB}F! zvfVW2>i2)2!eRC)7`7LR=k@cH6cDlC0XTYD>V0n3(_R_+AhU)qW1 z@gni_-a8CkRD+^cdaJ((^xpawG9$p8Msh3x5S&d4yrrdxzAj+ySDbg7T$(UBg*>J# z=KQmjRac{*0MGzMV=m*qW*=Kl|F_O73LoE-7RhSRcL9!5_VC6rX|Dn`Hg{N?=&yxZ zEbKp!2E~u4`Y%y*ER&FCE?Q5hoavm6K9vyRH6L)>Te)N`H)xi1yh-P~n`%SNfWKH4 zMSqQ6xpty3m$~er!0X-QJV#V$>@khE;Th8JwGjkoygB6TlhWxVqV z_GB?kWZ`uaRRe}QKD{x6rWjUU4u>4f|3BO;+*?~Yvcyo1>yB8&l>FZ-1J*ViTJ(lE zA54_XNp!iT@!!L<0PpX#FC`_MC)IjJsCwF;hXcF%+tDtj@~Ht^Wln8ZSjXz>ofc)mhucEsbO?RlP0(H%Rj6WcS^bVibK4Y^?_%T@_E7 zswh}vJ6*k))&SHH%=uVq78|oL&bm$S1V+zTdpj}WN?k515*VB)Z zjLJdNeJWG@4zZsf+{)i=<=C0?$y_xf{%z@XDS|0lf^lF6vr=CsS!bN$t z4(;NYmdB+qD^8pHSC+a9W1Es5a>r8HE!y}R`q8(Lu?5>0otf-9oE#nX-4M}o0rZ}l zr-s(JJ+<1ncub@vi*^0$$0u#yu2k>E=f;VFn=YP;z@W2HSI3JJ75N!zcI_hbq%RFp zHtx0y;y5zZ@j{Phx{CVlwP~6t@HqR_(G5*WmhrDFVI>6Uiom&7LCvZ#(RVeyE5$G+ zwETvY&AUn4pH~daTc-;?#i7NXle;i}9lM=#f`$X>zsCfOfW#yn&rH5jt2QDd#Z7b& z-CLB;&3sq9XxPiau*9r8UZ+KK8Mq%$&$HYF2eqjtl8AeN-;TO+GZ) znNb(+X_4tBX;j)DNY7uX4n0J$X8tI)A1Gq<$PDPU(McJ z%TIJfcC8z5S>m#n{tkCTA@Igd<%cg%Rpkc3)srlRTz>rHx$u?DU&O#X2+||T`c8n|sNwPW!?(6W zCka;uwa?o%$kMTKMV-h4v|rMjhn^`l9%hx9p#&d4n|L=pN%oem#0EChk$w$>wL58} z^#O;<0R#=h?N%ChrMMc8^UR*8A-z4CxZTR?I2aGh=@PZm&lkM02xc$v!mFE*{|VS; zP*5~RM^2O5-(HZzL@F#VDD)4LQ8u)|)*qN7=D1eOMeE8*vbSjgk3iO9$gzrLs4U6D^-r0fjZk4GEHND0OGyyY#1iZ9SY6== zu^A+|1lubn1d^3nLYS7;mKr$GB9Pcw_vb9tWySFAv;+C$8Qmv*z5SR7%c$VfYhIfy z>?3q?g#&jH=UJ|SCZUKKylSMyU1ch~Eu%4dFg$guDoqni)7!fbt|->;-LQdK0Y&nt zM|a`TYUsg>da8Ds3Z$*cGeUtMJf{fHdv-zv;xyM)I`%~Mf154{Kj!`fcq8H3V6hW6 z1W3Rgs|)Y9+NtR+>Zwd_+aD;+@^)EnqHaxqpL#nRyf$2JGXvZ+(-hqEa=i?Q-wyrU779=RX z>@cyHR4pl-XJOdHnVa`W3VQb5&5b4Oe(7oNG_0rp1w3CvPIHX!Xm+8WJzhX`Uc(=R zr(4{=@_Y8insIUJ<7;3>)=_44PZ=6H-k-%Gi0b~)-Lvl&Hd64EjG}PAM+$$$5{*7} zL1?y>81jQgiB_ai1zFx+r@WM(_|BmQe1@ugi>enR3OQIHh^^(BLd>=n{Lo5irj&TU z9YQr*6a8rT{QG&2^l7}5UlYeY5Vi9O|NbG z6@=OmOJ^tzoBUAb`2E5-F+mW@_7CB4?bmBtHhDsd!I=_FwIJW@f2Tw(%`U6I^LE2r zW1?F!ZiQ(RqIOe1#&zVKSvYJ+>4iqduxkehcoLwJ4cC+lxQU6}IOoRF?X!B-p)2DJ z2RU7JFBRSuUZ5F{)J!qzJLD%YcPpIU^_3M0%e|Xcyza3m@R@Bh#S; zmX{^<{Ga)XoqDwh>p3Ngn;ivV;w0NeMc%kdN+>0{Yge_ZZHl<4Oci=cuh&EmL{qRJ znaDR$M>+Wa$4%1L`BvN)Z@hJ#3IHYPfLKe;;e;L6&JdSHjsN@g_Ik28uBF8H-l`s(MD8 zYf?&3XX--i(C$^C7u(ig@vik zjck&3chd(GVik%}{fQ%F1eVZ@D7qlT5)~p1nhQqb9Gv9qK+hT7J(K^I{}&%3xM)Za zWohu}=!$D1s6&;!x09^>Hr$tX2JZ2F-H$2V`(DFpZLWOidqL}af9k@=IAYD5wU|kh z{E~UTEPQ!zt;_ya@XJfWGt`&FGA>tT_+`wlN?{U4T7|#(i z%v3(n@=r<4_Z^du^-zpl5>U@y$xp%!lS>z?h_q$iMO^rq+bT#P91Dd01TdFDFjbov z;t{11{N?`nXI=(SWv^x)v|g=<`T@_$J~(pA)U6PY1C^7NczdQ#eHNZmGQQi)BJ!Ot zJw@wdrW0pB8d4lQn<0g8=xQP5cN$$y$1lA-@(Dun+vtAl^?`879e^k~>;lVA#$r;#Uv4yl-ueap9bLQWVp4aD7_Y$agNh?W+>fjXu&j4sGN@Z6R@b| zC}jt-EzTRml`GeA-l@1GZC9@;Y-&i5fT!XDK*7BX87QSv1@MBA0Cq!_zj6nvM15#? z3{_7vxmvHlXtxK(GN^`;Ko>_7PLpWcq*K+L%P&0XSE)$yy-$b#ESnyO4#0JrpF2O9 z_B)$+vrf|c@fxCc9x9_=iFlXP@f;*ily#1Yed)I`iafLM_>qFEP@>sO{AC~EVYT$v zz&1FUR8TrvEhpla2lX-TIuq)dIi~s6LB9zk+e#IhF5+m+!37 zjy2z*Ig!EoWRTW40!`?D$gnYPOwP#=TVa1W$O^2wwjLP#{e~#g(TUq3tSviJ{MH%4}Z7 zcOF1xqFC^MC0d}|CHqlq9t90dvmDcB5zRp7zQbUl_=NtrZ~VX`&QHe_A*dfxH#0$q zGsjM{vO~_ss>$UUrLIxL<3Kd6i{VlU zt_Ym~wFNV>edp71!dqDk;nk%mqzslcLBwd$s@Ydl84S*9JBAxO5|x}6%)SsA(Ls_P zu2Cd|tZ2|#C`xf@P*O2taem^z!qXyct`YKR5@Y!uO)P8~g_=p%^4C552=v>xi|WcV zsbO^N^|?$@kr3tdDxvgLP=fh^+wSddioABI-rkhW5D#Kaf-|gjF=ta2+WM#54J3I$ zA&QP_{r55WE3Ntw2vT?gUiIw_T#<>5wAY@*6WhuiaIn?-H&s+(=@h0a!-TmoY_+Qv ze>cT!07lSH@gtL*Tdn2dYZp0qO~lX{V5PbOdE$F$#ve@(xdi^9MT+r@>cC2R-hA=| zENNI35{2`*Z`;IWVj_5IY1}#F=M&M-CPvoLp0YFf=o6f@Dl92B0;sf=sl040TD;Xn(9mPmWyT~mTpPBML@F0PYAts)Hm8rD<9fpU+Ba5oS8E+p{?I3HuO19-$%%bb7lCb-XKpOEq zpCG1r;pX$=gSQ1P>qR>39~tUuXg(~K3xZ0vs~MEudZ*aS^^7WJ5?d8=rLwKWS;YBqrwcC;_po_dgZ9rjBF*Bw$V@9`9T)JesoL+9Mv6#g} z#^||`hpjb^AJ5n3u=6fDndsBsCKq*-JDJyi$U53v2L%fH(*Ok+f?o{S+k~n8XdnMq z=-SR*VvEy?gFhSagfT1MLuqcjc$EO-LhuA|jHyMnAO zS%7}6G1LzZx{dztG`h^0IPKU9suqAIJiHF{mx7I~+m7bylnR~43le6!m+2QEEdu>d zV|)%&@n~p;7DH1ZA=kM4GX{Ts$0|PRbX|?*r~&v9OdY~Mrrer~4m$ppMEn?B*<6+( zQ>dmLn0hK9tQrYxLfGoTVZ^OlK>KD&CCJZ7PQk$K64w-;OSUTE!*aMo6SR$d zf?rI#Vmy6B#q=XkUPLYkpGayAQl3*;v!M{JZWZy$ZU)l>s4gn_#a2{!J62{PX8l8rGT=Mtldb2k1f3!a*uaQJGGKd6G>*)O6n;kq$Xe~in$ll3$@ z@hI+&O5j9-xAewDS<~4E?+I=fH$+_l#T4Jy(3CbO4~0FsWJS&Oxz3F)_i}BjNzV}* zM*5`25C1m)|7yCmiATufXrNGLda3vVuBBb|Q>%fl1_kPQU|daqZp+I`_DjZ&L;KzY za~C-&36sWwW3phSzTkA8`$*9B@f(lk#st>b+etCX@KgD#_f;J)_Kz<>@(FMQ+F++t zn@uA_uEi2QH|!g4ejY5aufADHX2%8TznjDsmH*@J&rKv|w*F`3*ap(ejx;V(zlLPWk*nb_l@r~PvYVdob@SAuXR~+9Udgs&cV*G;;2F9{b`)N_~SD_xD4AZ>w+p^%GhI0(h_GNSSe!P;)&mbA&XM{f7BH$sPB&r4$}@79s=bVn|T++KvyjyY3PlvR9}=>-&A3utT|M$9KsEjG4! z$d#&IOjEpKB48v^khhBuvYwm2GIp|of(Bm~JTGE(tPZu@0cvj)TW(h7!K0EZ@Om7` zKlSEZ=kR^Kp0hBJPke#JXPd0Vk`vUrZ9lq0{Yd`yhm^Cj_^t9KUnn@I6(I$ls&IX{8eW1g4lo%}H`6}Rohs^uE+lb`3x?e+c-IIx$ zt}n05{YI}UgGJ30^>m1Lf_RIlAE1fAWV7pJ!<5S=@?S>}XM@RxlStcISc{a9^FS%w z?dixVI0IjtRIjAL_%y3W!o+jU^v}%I<-KEYBaj8x;_ULaLG5W`q~Nz0(5yr_5!te% z)kI7BQA!FfY7FDvk3l~QLWOyxkGDnvpvB|IP&e=|%&ERx>qeA`wINHLk77iUZ7JIF-?LG8F^`L-=&GZq?# z{skW|&|{=(XtAP5-YnGTa~H?aX{opPdOV>gH6h48gF&<4v7fxE4(=952Yc-GW($&a zlsg4!XJvRvs)@bhw;+LCB)2)bic*fxBZS@Ff=N0zyy~H!@DoNN4=w}CotB;^FaFBC zW-7>=u^udsgw`|R1Wsl42(C>o80$zqrxR5vS1K)nVz^X~?(3oZriP)g+9Pl0?k(?r zBOU*<%I{?R3QVID=;aMk4HHu`^QLZ@7wib1WlcKe=A-7JijNS)Y?l1!lc>R-5{n2M zAGm{H6kyS>Ws%iv%dgS`|3MtGM+Hww9gdhSVxroPm>T3jVKMAmR7hW9evI$uL(!f3sIfiheZ zbmKaGZYXDEa)$?Jo++>lxMVd{N4N(h{ChFfwcamw5^fj<{}A#v)^`fkiRDqGx1nYv zUQm8TsfseiJJs4m#1dp45|vkNMiTQynyz1R6x@-tA^RRfHtU&%>l537CGqfNN>F#g zyk~)gvrD-oveZe+`6x!f^hw(y&dQ`4D4C6Xr#tX#X~Rw~YZYP$@~%D|)AUFQm((>P zSxo%;(?336*1Ia@5*V@<)2}aTv$aS?T<@DiJwDx{QZ>8{8u3s+^!6E6A!p zA_gs&jYxfuX5j$_08_7}UIQ@Lx{ax`TCy|K$Z}yd-qXCVcIvLYrAET`6uQ1|x!Wl; z<|QJs&P%=}XXsJOIH|n8YJND9SLKSIX2(m~b06S=SVS$71}!WZV8y*WK41%2#WIjc zrF+kge;3z&f9sbj7Pa9iZSxagFXPv~vsedpe_kUdW0X#){{*y?FC@`IBf!=D15<>d z%2qDMZHjlwyDRGm(@&?-%?`K|-^Rz8C-SKVcBdj~^OcXIvjM^4ZW=BsL$2AEpK}I< z7S675?fsEKuMX}|ZhtTSo}_>Ai^QO}pb#UAzzlZ*%($5G^KeCjps7=Vrk5Qw4d}Wjw+s*-yvZM*9}k@VYJs%U>T)2)k2CU64wm z{K&n>5PImDs^#k8+PA*J;I`MRErc4r{ihD+p*SC1XK{k!`(F zYgdOeXRXFWI>PVx3Ypq8vWymS=uM9jkvpv0-ZGJrs<`x?IQc%ytONHdp5}5&h__D= zYkCekvB2U;fId$?az`TC>R*2XfQyqUd8wkHHhizDm}s&Ly%`DtA$as`%wa_~#89 zuzyM1-U|0?^waKh_hd^bR-g|{sN)O4FwgSl@vgR6ZLF>ehiB7 z9xvDT{99ZX=3Nf*Pd%DqBtPq2icf3twK)*ZIO8?1rVL_5Gd+cy><1@%F7@=#E1-p# zK%;H4I-#1sn!k;ce{}(sQ_BXJFoP0_KLOYwr#`CttRBNU@*4bKGjSCF{}(d z66Q#aSVp~bo-1HdaN1vTY;ls*lnrS=BiY284 zQLdyP9ozL~=Que^36X13z{M^ACJ^wr@$YCkuK=7yF6+swD$uugrM-J}fTeU^aiA4f zlbytrnW$!HVJ0`wvd*qTv=^ne0ef+Z^|a`)-EfRqiM)cs zGV7|wdoKFY9^V^F3l%EzPucYw?6%B*tkUF5w*~fT;l^Y&hU51k=vk5~WJ+SfA-3-% zyYq^f#X4cl**t`gd%qPCFRROE$QO7DVk!(i#sAM`9R~XIsGv>$w(n~Ph8lO+mXH9J zS(tKurf#(Nk{Bz=2n98F z>kcKek-vg9ZH@T7C*bRyp+KKVOjS4YR^jtFkBvnF1~(P>py~HcPO?Kza{a&CX~SO; zz1^FniQy9KCtnwyW`3I*{{I(HXU9Ju0?VI1vLVJ_NS<4rqgs8_;OLHYJ>`%>#NkYU zH7a25FLT9opDX#VoT>jYUhRb#2oo0AL`%$_+J6(8vCN;V^28Z-&?-Z5%9y!#?m%tZ zZ(`d-A~ly@gSBz}2`HV)86si$ZzPvN4$90fZ@W)ibd?Q~AtnYx6KiP#s zx*#Uz{>9E{s182OuqjStYke{jgz{sjNW5>?M`Y#DODItC1S3II*J~J)%Tp?)Q?o081lXH3`i6-;bSiB{V{cL3IX^` z4>OEX#%*;ALMY6Igx_oM#ciB?pnEK+e;$=P)7-0MEWtaNB08-gn9K_=lnYkg=q7iB zp^g-7H8fy}gO{4#zkW$U_xsf9r>aWN^dJ2!y@U3V!8gs*{${tQ$23{UI{-FKj1tAu zx?8~w%T~&djkhAxxqP9CVa}1wepHNK4Xpe0N z6?##2S`hG+E^0~!j_joNfUDDzjLDeb!ihC@?(y*-1R6tbNnHbpak@B%t)P)+oYoKR zlaY2XMQ&76mqD>Y>OgF7htt$jzlKODj_=IsZ0eHj&b8{rhE)G{4gQ;_j-g7{Ofbmz z(~CMQA*9V_h;15MZ(>^#`n7EzXK@j;lyV{q7~#>K{bT*YHd-yJd^C65U z(&z%^)4%sj{9)5)7WXV9-&?4xJlWW#b>s9>JtZ264$cRF8QwqZ%;u`-qlqCz#Z~c5 zg}S=9I?JrmL@Foxu0F`rn_%x{@fF=O6MGk?yLtObLESvPL*HdB*zUULSdX7vK3+)e z=a8N-xtb`*_#UprPZGTM(jwKG7}w-;XWe;@ag8zHEhjxUq1S$=Fizat@P3$=e;?&1 z;5bXGJjbe!F(cZc_uz+bNC%D}If3vPIeFs4o4RM+6M0i)l zS5&=j>CRl?Fh0VsQJ{>7Hg`}nU~FQO_YI{<@P(cB<=LHE+5P zm&IuyVu4ZES~tVgCUW98`}PnMsZK4h;mgH=FMAWcyPN9V6Id!G*&MM%KxeSn^kJ{S zI^;}c9U5Ygg#uUnVskS#ZZkgOw<5&%x8DOgdW7QBM>eB`Z2a+68BgQ)hR)gc^|gS3 zOWQTUm`Qwe(44bGd*&qX7BWH0pd3!RwAr>RD3JrBbb(uXkjDFZ};{Ae_t3kKG&O_L=?=^y<#+7DU z-jzwKoC82B)$e6E%SUB*9A2N5FmA5=#o;K5RFX zvEMO0Wo^HiLKv{@&Dz4g15LXs&&}vZ z7~+)v7@~7BQWliSjC_NHpMY=vK9ScO2b$*qU#^COSISw~Flt`?I=l)8OWX&~0ZD)Pm~`WRYLbtM-!n>tR;kdX69#1pN(vd<{(k;PAB z-oo>r`;!-3)T;EEK!VLR@ySWEraV!*@v7C<{bsua>^vKaj&C&Q|8zV3m4xii{*r^O zK~EaWc2fXG|6_Q-Z8( zQ~}QJ9^fO*MjPi1g+@pJUO>t2p~Q{KnYIN|&v`8(^jlH5aC4VC*CQnfALf0QjB6tX zo3$<_DrX_LXRL8-F%)WAz#h-B$A4?msmWW|g#hl6eME(wkoP36xvWZ6ygRU7<;N7D zVp?#oj5V;l2P7t_-qLLnTH6nQ#j#>ro^ub%y|nvl0|`^oXX~0Gb{YYKFVk~;UAACx zj}1uW9iA0?gVNS-eCA&YFC)@ z;8MJH4(Z?yv=KYXJ=~P)1h?YNZUwTp6O|Bvb^+XRjarHboj3r72b~yNC0!>N1h0^b zL~zoIH&Ud}ppzXj@v6xfpOfSIu?0xmyh}ymQIWi=Tko z6J8<>8#09fho%_CX9y4*dM*+F-jTK+!{vgJ3W8!mOS5nj)WmBP4WcoWn$FXMt1sKf zs&Ug^#;Ko;$#O|7N#JN?Of7z`d}VP_u~7(g2$r>bmZ5w?1s04f;C^m|Hw-3C&6mIi z!^6E_)zyGarjd5uR8ZZDK}CXr5LQm13Ga5=c7Oc$ZV31f+*mbq)jo8Dty`-26}^wp z=f&c#uLdWNfQIQRZ7cA}-aqP%J26D(d6n&W#++G4{4b_ZCVk2amKYdgjmiR-`Z}1A z-IHnym=?RWDlQ?a0=TSLXW+Xm3DfP%?JN+JWjdTH-_mOn`Q#@ROhh@*o*qOD@4<$& zvwlzPgEu)6!Tfl4@+~RVj|y4;C&V%fR=Fw?#z|$6tL=7q#%qmDl*o$#iaUD9Yo-DB zxO#E3m#`mkt}Dwfoy?3as;Od|qsp>WfQK?9jBu`+TQq?JR>537a*&QtXrEo26(6@Y zOz%1;!4aJE{;Tjz+x`pxCJ1y-Ed6<*W-$+&M7iSp3z|Kod~{`n&g_(G{<7se5UwI) zen$6&@UDpJF8yN%ew1)f-}A73ejND$&FrwVIhm_N38uWl@{jqtDs)Z-uH} zzHuom{idW~^WE#zsxXA3mbVgzK6=C@a8QACEQ1;|=odA8Za50P$XLTjX(7KybA!H3 zsl>cpQOF%3;smE z<86N1nm#^oc&@y+QldHUH5!7w5_RKFyTD=yRcBlUeYYpLln4)j|&*r*Xx>VzF2lhiD?txJL&zF+pqv#7T4R~ z%?H5q)`fEZz% zDeb-%dB|TEW(zUUuP#r2!yjw*QJzijMC51;-Xm8YD4@pwxfRVj<)(>L+A)Vnx8 z8fFk}+WOhbw3_V1FWWRmY+m#@GLR`9x9+tg+79@n^x??e1JjMgje)VvgPoc^czDis} z+JQv)IA_PtvrC>M+xy4kcrKV%&`q%bWlhR9yww z%4-oP@C19g$*Q~>^tUb=*%u5lh5Q7lOH#1e!E^U8$kT*TjBL9e@Cq;26?JBm63=uZ za3IN2M@PWQ1+Qn$9B_6Ye>#B4YFyd08FvE)f3?=_)v;O(vJ06VH z{b;{b3^4_q_J{p2C!T=qjNK$pUcvN)JKOcl=gF^LmR!gZy=GqmUD2uYs58lDN$tSw zi6M>Tp4{rx57Z}130m^lA+`^b;CsP3o9MpM;VB^J6K)j)#1?KFl)SWpal&H+6BkM7 zeWJP}*n3v-xC|)(jMOnwKVZPLyYuJh;yVvu2rS)Tfs6ayIg2l{jZF^&zHL99J#F-~ zZ?vsleMxrj7t8+<&w9Bokoe&{s4Po4d6rtypwNxb^Ta0cK+2h;P9K41=QmK_8XX(L zwM`Q#_T97gxVUrho5+lCLpf+6(?CDoXW}&t!cJxFGmF#MZAh>_knpUU$Ut>p2+BCY zt#I^UiElqDBBnzQ;hHo-PHqmbttBa12+}tvlSQU5gN=6A?Pv#PlA3hkz8X#aAB(He zCu`ox7<*R-n%Vsh`6e-Q#4(g|@B z*(8+#)o8Dqzn(w*>Iyl2cZELzzw-%%aTp!2dj5nQ|0?hnS8GLle)*nF9b0cszAjRB zv83o5*wWAD3A!hL@+J(tWz2SN7lk3|1K17R46U&Ag?WbMI@kZe6BxT8A`QfwbPb~!p7A9RY7L8nZ9I2io+AOHh6FQ)C!(3P?hh0{d zy!6k0irz4Jv;>MDR?yCZ7KB|NC%|?>IhGGj-~l>5{~%3hMDV6=g=P*fx4W*{AJ!~S>L+>^!&pB*R|%hm-2+n#*IntWt4$4W=(CQRNtkt z=G%=8i2+pd9O~Vm<>6!!eh5q82{d5{Epk+F*V0OL#~kBtrXG+M7<~`e@GtF4mX8E2 zfm7stzPa#fCnIZ;m}aKQty;oZN-FTR9~iDxgEn+9jFfaOgG0 z(v6b$iYKxpNJ!4-LM3Hn$pxEA#4rK)U#dD##=2XO;VYA&49}5ExllduT^w5blR!XZ zka3x|pEyxsKFJm0Tb0Y0EWTC#)6QQ#t?;Uzg!A+Ym|2EPMxXdIaF(3cVULECtcqc^M zksKeW8@7NN2lbrAlANu0mOlDr_kfW5mM<=%G8%F?5 zxt7X7_n+F)0#kQTG!I2HlN0C{vv_Vx>Y9{JLjfw{H84UWgF!6@S;lfWG!{YqbJ@~K z=)C1)EJxhi`y!GALWeVU3g~fZ=hbF8n}pOD6MdT|J9%zqQ!zJMPf7bm0R1PKf94`j zisxM$uQuRr;(Aq0|FP61<)(P6c#WyR-SY}#(P4Bx*+D6bk$c@&5cT76E=ccg%M@!o zZ}~I1$ichIgE%{t9zO`LcCEW5j9L%*3*E$4s)DJR>*tAr$vXW-+;A9b;v6}km-9+3CBj~`U=W9!|X>6MK( zeq}^3`0jtR0!kfSNb-WF?W6 zjZN;KH?8)-)gFQC*LMPHpt8$&^3mA3!y8$kGzCP%=v)yeoqg;@>D+_|z43H#E!J_f zZ%%yYxG$fG^qM@14hmZLi<$p5>aZK#RCkoZr++sR2%!N{E~->{RZgV{sQPEOAgRS8{Vc)2lc?? zX;|c(DWzn~dRZ%gH~lsKjNwJ%%5-=MC07FEhZ%iwE}o#m9x*JJAG7^~V3xfK2gQzhYE9j!?vBqMqGPW(cAC9$$Jdx-|CY-dYW!@vFs?vDaJUVx+eI}vAg+! z)tMOu!od^el^(vBOYl~Hlv;F*SGCGew2;ClC!QX88S zf)n@qmGTPk9$o#TDxMS}L12|12`Y}O+dhtU^% zq7w3)1?sgJ(B(w5!^KZPmQZkCof{?Xto8YspXLjW@Dvzy9n>duY@2` z;Mh&o5`VWDNh?*KOP-0m5@X(mEf8XsrbazPS&><-UjKI)Cr*wlf(xEicJv7oGAT1pt z-5?DrNVn1mQtrX?`UU5{?)w4kzu-8?W4`c-^SlrVhSMLW`E zhdMhBWn)&|D*CJ;h*@|*?5mp=S#d_Mg4kL}!<#>YM*mqZdFlu;`*YSWl>o0$_t>{F zr182vHclL8QNA`xk*o0sFN{N|zq?vtB_Qy=%-mzS&thmN!nYL~WQuSzD}HjiE=Oq_ z0YluY+TFghWS057(i2WT#L0bfBl|x8kmDv7O8ejhQw*XYualJT<*lhFl6ydUh=dj1 zB|Yu_e`Q67SJ&o_(?_H5WRAR1$?OgsM?Q!92<}sYZjeHMF$I&oK=k-}Aaz4orh%@h zW~4Fzu>3A0NNTJXg~BiIT|2M>?!;Sy`Bz$nMn>e(?`SoJmFwsjTbxvyJWtd{*DH06i`u8(MG`dLQ$x^9%Wx*6F`kZHl#f~ z%r-nqGNGPGUFI00-=^b@C#B`gW$faU#cycRKJho&ZTo4+g|8X6F{P#(v5IwneHCU% zHdB8Dz~kAZ6?h)c)GxeC7eOD8@>d=v0G5F~|42?ct8-6T96VEH34@Z=i4wt}U?@0o zTl(h-vBzLn4^Dq?RE-S3h^g0O%N(qs8F zthT<+Z@>Yg;n?kXo&R$WH&|Uq+7)O^(&2R3(nkVj?t`(WsVuSA;%+7v@k)mM$tXc< zA0clS|9{3ZqoSZl=H?Q>$G9ee6mY57wPi>f)*AM7X2q|C)i0J zC3FCv+GKtM5~ZySJ=8?k`-nkQ?wUKaSf%G>Cm|X%0^%jtI}$Em?gh=}KVN%E-}!im@DcnKg#&`%uPA^7(OM?! z1#6N+U=?ZIX%+t-@1$=W`mRghQ%4$BwWb+g*el`G5DnmYT@%S|c@n%pWH#p1s1_ z8Pyld5Q=-)mh!E`;*1blEz7^gb`sT+VHPHKmSyJ&LUJ#5ek-=kBHC*$GEP`BW05As zT*0eZ2k;JoS8;UowXkgae15fMxyoO<@YDtY;088<;_c5?R3i_SK1tII=6fO<)zr6? zNi7{J3f;nj<-W?1K3)$KW}bl1l@n_qX*dgc7VX1bght|Mp>=sH)SRGl)0mK8VK7{3 z75u{}RP=LBNJD5TP&L$=`?59ah0>BIXV?z2kTz&9dJ#5};rNu0-{fxM&|>tJ!oTZt zALwpnx^%W&Z)IqGRG>4hvWz~Is%hvrhNCq-v@cZzMX3;4eewRD69#zTuU~6ihHrB@ z$HxD>#0!m4VZ$X5^5-dB!stTGdb~D~FnN%cK z^7g}(Atv3Ov-O$XvLSdqu>s5+!{aEANze>1pY`dCW8Wv2P4sn8eV!2wTZod7<8@NEaK^0^9EbS) z7Gr(Enr({{H9uuD5^D$;L!vG*1k3?o#%aW@W_{wbT+=#7zx2dfKB}vwz<%{{EwfM0 zP|l4kfv`9+1mGP4olTf|E0F4GPo-ZSvSY8h>Tew_{I zY9F%5zDTMh2J)8%v%gY*+Rs4uRd`tum!UqJC#_3r%g))W)s*2kz%|QC4_6A06^5(SxReC^A;#|CK{1B_I>TYYFfjTJQ} zf?fiED{uaZ&`pAUH5G)XzAghhB=&?&5-*-AbrsQ>K?V?peJwVq;sf#0$bVV?bvFFP z>ZP)Z;HpAm$zD*s$~R#D$tDW)wf8CJ{X|r6SFuelaS`Oz>8$)T9o+Yebeo$UA^n=Rl* zSsrmZqxH6k#xdF@A6O@;Bc?t-FH@C||0+n|-vd;qY@(*c&#M(s=@}FWm2mG4H{Y%- zLxoEbwi$tpfx-;oaG+Y@(9PR;LXkvsboGK;N+vf(GDV6ydW?n zM#g|pW3Z3Sk*^xPKFt^Ti2A)pOJC_!)HV*F!Z&b-3I)veS6$>_coelt?hT-l&4Gf9 zCf)1Xi4@cc6dfO5u}?~gKgmpoNd}@N!%!68mwskYDT2%tWJGbk)m_IqvuAkVKCRle zP>Nswgmz*6^p7Ai^K~cGt;iBb$(wy6CMl5hIGdbFdPPJA1EUS|zn)LE<9Z8(4k5TT z46u?@_zae4jcJMTvSq837+j*ykO$@)mnb>LiYa=7=-xcsD2Unq$;V!NMRo6k`TmIy z*Q)K-mc`?-{&u6b=aamdZ9c-d%I-56MNfeH%x;JIJnm^~;{Y2f{4%D*nn8f=VCApWHdmF3ymm559KF zczh`es#-4rf0+RB)i69Z*^OVh|Jm@oAM~r#bs1AvL4fR?f4=(nLHl5ZfZEMl+E+5< z-9dTk^p+kAD_MwaVcOwHLo+3T#mBxgpalLXV3y0^7%hCtv6k-aAX-xzAJ5F&Nuk&B z9)tuLepg6fD4%#`scytMa6Ngf7RTHk)_SVkFAP#!Em|jOdHgO;(v2Y2$$t-DpwjB8qp|*8XoXhwDd@{)i z9q7&3F_I5z4Z`huhjqFhTQ4)%nM{B%ns!?0p=gnTq-FUeDSg42Zh{pLoM|Gl-a5Hr zcv|+%wND`Un^h9Ihy+Mfqe&6XZM#n&#55cCNx{~AA5n={4~ ztBnopjB00vIo?<~)%EFugyWEFX0OMKk&Yfq5J8wmXF`ULH8de~E4&ei6qn2eV5 zubC8lphdI02+~1zm?A~3)H3MvUU4I2mWUw)OYK?yao1N1e3<>(zk|=X!4UFn9`UCh z=~FXO?%Z>_$A9Yvod;SB3n*{&$-zE&8BG(u$0x*m#2Nr?Dkw0J4eS*roht!=4MKTHR%C zupnU!HUOjY$UGUwOD!f}{)upzLB@q!deltg)(ZfO{CK^mTveeg(xCvQuS`VDOew7%MN68mO(|kNc(3jk9O|gEpnd@ z0Vj=srJiyTde1pt?( zql6_yL6h|5`^}XtOCt65&MkfauE$34df&s&6p=98ne&F)`~l5o_+Iy(g)6Q3i*1nr zcWfk1tK{2Wq`}-9VN4kTpBY#?0^^m4gD?@Fp(;ud9hBv|!I3p}$~Nyc!pus-#xCR4 z>vBB}ZxeY(?h?9{?_MO))kEb~I|e-hK8zXyfdq-_bn@%5lJ8i_00^B3BY#fljK}oB zKjkNdSWIy^PJ=nhn^L4qV|AI|_~BQ%#{`wdqZlT_oKXyGQcv8KqdgeTlS%x%xIPJ% zKZ|uTATM*e{shE*Z4>buF!SNT*!z7u5p&)bBNg<)g#-5KR=zI40PJs6;ue?mzCKMnd1V*B<+!1kraq4?2}s5 zjm~uAnY)WTP4xsjw#&h6KW)hle7iqhJSVFHG3HA+tk{}eM47Oz_-5>HaA<7j6k+AB zE7dR_k}#DGiU}_Xi;evjjcJt>0wAuHR%HFG^v ztQLM^rV3_rWl3S#vXI0>5y5TcMvf=B^!&bu1NcfVTq4KEKS@=2cT*$o$ez{an0w z2t!3SqdH%m02makKK1}|SZ^7|a@&U`(XrD+E9Quwb!Pq7;iCf}E_kOhOTK{wLQ z?Uw}}?QNv?lp0*sKmzmRflD8w&ikQZd89U5L`FE#P+|on!Z89UBchxBYwSb5w zY$2#-*~EF-<)aG>VtETjo1op0vq8BlG3b&sKZME@B??j>Ike<17w+80)m**4=l?xL zETvAfYkBxirp#~%2;+tK=>cKhFt~YzkU>cD%hR~{sO@k++XY^l_p{UOa|dK*Q|if= z05iQL+>lXtV_3NF>TJ1d-RC$DbXwVcXdil4r2(9D9Tt21fuLd3!q=ydrXC!}Gu%TL z)rGqBmO-4~F+_Tg0bN_@Ivk!L=VjOL9aji_zD%u$rAGbYQ@(1C+Ts+ewl*06H;-LU zI^LFEEB=;*h}d*TJFPSrM`AK}dSGH;R1j6T%8m=LD?Hv~aWNOm-;XPsC(m-&{|*T_ z$3sjNG}vQxf)~*OA|vOml-EU_EYUy;^oRa4qLap7{E|&@(Yfcm4AxS)Cqcruj9_#y zIv8dR=aQv)b`EvNj(28uNHA#wqAmAg;6r@IA8+rAM>;<=!?qw~^iravbe7rgeMC!M zP;bum$MC07r1-D+FwR^&9gBYb&HICD5J$v%oFM0T?+O5oP}ziz@LizHdkauKJ@0XscT@ohX}>{tc?Yc_0- zPQ6JTyg~AO2z302C?E|ei$9gy_P#)3p6e4My34WbQ2%eJj3#-x`{kC4 zE*iSuA=k0w)BZ^DeRQ(~r!&@4A)6#60=mw(0|HpCI2H0b5Oa}5-(kY~$5gw;>n=0? zYq$gJ?SGpcF2&1#68vE>Z}iP?%=Y!VKs{KZG3x+^2TuT7aNDXKoiUWQrIQ_Dn_p}0 z?bkP?S@Vx%$31d0RIa$p-R_8yEU8rR^iEStt)5KE*hnM~0)Q|XMc>9vry|K#1>rr& z(7g@%-S8DwBq0wLi5$G~8Ac$&@@n{(r2N{umoqbJ8B3yHw7L-yo(fVsaNIB3aC(8r zeT1!vA>in|VcgyB6F-IGt-C8UITOj0s)uf^P1!i^q5=6WhR+-PDZ zY6WM4w0$>#`Fmxjbv#!g5{V6&awZz%9J(m1)l}M&BB|gYOr^tKl~@M2>KQ^E>0@BU ziBT{<)XyY1zX9OgIP~K@y;fL5`3?&`0{UaUpSuVsh{0=ZH-p%JqXH5k6367w(U1iE|=p zr_W<@-K@o+7h5E~bo-_K&Y&da*$omF$;X@f;PAeA*x^kn- z*+*aSQD&z^Pj)hn_GGo+dTO3~BzIY% zjK-FaJnp_Znin?NM_Ri-4n@WZpX#o9%VX}`y5dI{D1Uq!Ub^}y)y7NyrFT;OpBwb7 zi&L6sBLXf^R&9kGSKx!5A+VKDiaZgr%Pa@z;W)vv$+Rt+g40`J&O(A52q+acr3BiN z+gLR$6dh=;DGnu(z7f2X>%f)jbG)OU=cLh;5eO?2_BF1Jte<$R=2N;VE=1?g=)y zfB^Aun(FNyoMRec!~O7Yr@R3Vq{gppX;g@BXji;D9>j~st;o^}VFNlQ^sE|)eR##u ziqM>&4UH!aC)%uP@+Tn~3iDnD4(1^`qnJ7j_)e}AIoYcr8C zL(CxCnNmT*EnuyJg3)mEHAszLs3FARCI)G+Jx=WCwLon?RHmeH$0x>@7@#^#3Pu%S zacMMHOB|pG)l%aDAO#|=_KK){C$`K&NScEJG{?EPW~ki55IRq}(1)~LF(!0(M16G7 zHgf(7zBkWGopN5iwPGRH?Khn22;r(2VGjd1C?s{PUoiMDeu|Yt-c|2=16aXMQe1!i zdHv23WVK>P%Eqa&+*=ici%ypr4W4XkX-boE1CPh~D67m!m=p(>ON+LpsT;@2arSkkkW-oqh zlazocb9-WOxR_&B(Tru;`pr?Bx)eB40Zs$s7+(*H9eVRUd`@FDok(=h!b!!d*I4gh zj2QH^T(x&C0!-D{hpv*aTI7Mn20OMI+K% z7szKrwQNcnFbRS;3%to>L10|-zX~8_cGxK&91Zz3K=FKv-*5$VC3HLRXSeSm^yInm z`rqzTiT-s~+ZiBSIwvgVYn+EB1xP)YZ`>h;2OWJMm4Bga`s&^qsACULKC{UqzQv31 zn4_bfMoT~L`IA^7a?_!Sa~Gbh;zj8lf8^i__GR~m1{B7}r-MM)Vj9m~_e)Z@=N?Jza)?%kBr>XeAM}RV%atI3rfC$ya#r;+m~(%Oytq=RY5Qsj5ac z`pI?A<$!6Wz=?vP5M-^2PiC$v`2xnx$fzV7`>Erbg55uY`Bm4IEr>A0NiB4g(A>=! zc`rI%s?5T#Qq@>rJV%be_d6i{_O*`~%9iMb1l+nGpuNWxl|7}kFGp=>r_Cm^(5p6D zQkn{!9odNjuBqMt_@JTy3_)ws;7i6Vx3&%p&d8Ix=GDb59j(iZ% zn9!!aO8uNR^Kj0n^D26hDzq!{<53W4#iNg_*5(3a7Xf{OaVnc%cO&fSUr%iyZBrnB zM7!U-!7qT*D-t{6;0Pe@vFLa zqkrn{C_7{NSqy1`5NhGFoDrv4uayhTHYHBg7}cu+SOzo=BRN1t83De8~Oa7Jtm!Ap6DYu-}3qm;O^%?SU^(`>DZx=HyCP$Jb4zIeo6XXd`m&;@<9U?b%DaX8FPhb{5ZhQqhrJJkrj13V&@VW5*|2(1l zihw^#WaB{quUPZoR?(K}j!?oGMK)KF?m3Pn5|^P-4|VwtT4s{S-9a#@`d&2DX_{V? zg#pMoT1@c<^CzEP2lr?m%YUr9q1joRJ2Y4&+EVPjcaGl?>QiRx3tDF|nCur6xBy*c z``{&a!RTHL`*C-X91%On4O)ce{mDu{_9H+jU*vS<7J+$+i0P+0bra2%?+C zdW`TQfz*EkSOA24c1G$us>dbqLyX!F{}L<67I9n*OgG3*zj=-Xe}Yl$XKD-1mWL{)@X5QW>2d%$?^uxR zY|+3!*zGZ(Ga{e#SSoG^<91k*Q4?5)Cfap>g-U#3LLeu{d#2qfj)Na<+tnX-ZU+hm zMtn^vc63#w{|&&_k|!RNi&d8%?QlgAo^&h}VY&>$2i$U^sE(_sal?;%MVOI@4BH?z z9<(9w|I~tibn%iNXU;%VLdJNXQ%&>M{6vxeku6yk%%CC@awqV(hzFS(=xjAeNgbofir{n`92Sf_@ zJj!%HVDw_-T_o;$U$;55F=Fq;`Li76w9-acE~Mxgv#!=@t`zItIYkxU%Y{sjp8nY2 z?l5u$v<`$TNH=a(A`7)#`4G+3$MozkAJ4Xot3`4T*!v}pK_?qX7X%-mWQ?WUizpsR zwMDeWXhWM zNDif)3o)2Bipyj88atGh65fRYo9vGsd$=0HJBeD>+!$xPP(XR1t-5a7Pn}?y;2CekS z*3?hyW+W&PjLDK}!~cEt5)u*a4VLeA2ojlk8&nz5nu58*iKl^=F+!}2EyUXbwLrUG zkHAUP7mC|kQ27mrU{hxuHUi;4I@zIJNG(kOy7cF36JrAaD}bUI(+o=Knp(2q+)GhH z6gx@NSEf_D`xJY}6K{6)pESQlL?>vBVe<188?N}V-V|FzSF5F#mxa)QB10sFGwP(F z+jV!jhGh9HcD=Qc=;IouhK-|+YD7qNBAWV%Se4?}@a9Af??9AsRkFPcIpJlM*fqP= zV!2O(uU;_Kr4M40%#<=B_&g3P2e5y!+$jtYPZOwod%}P)B2}d!b>#DFZTp2AEjwz0MF5wvSjsmB)B%zVWUgt?hTRW0-8wj53$$GU>mwZU}LHKB(m z9buv-2j);Vf?)_ z&7b^gT7F2GN7>>p>C-{(=0XhiqY!}H{^6W6h8Q#)M?XH#&q)2SzYi4s(?85$&ud^b zz`?$OBaQfS@Y0j>1i~4mkf7r(`W*w~j~!32In_B0zcg4WC+zS8YR;l$64LnBp_UOw znkE;Op7hKm!C~-tw2V7&X$p!880v4ayPX-O`v%k+4`jd6^jMa#!*5HhwEUI*q+Gx~ zhhL!D5%ZLr5l3ga@T}qLxN~R+Np`7tEX`sek@EkA# zXW>Xo0>Q#)qMzW#o9=E$wQR)Ci=;`k1TING0{uc67e3>`n6}cQ@Y3(vO8hQ>D&`8T zu72}bD`Tjk6^?^mBKf%=U~3%vX127#Oz~~1ic3sBz_(GwYaC9|dyv4@A3jpb46*e9 zF~ZBQi<_R@;xwQJXjzjw`f^F&>VSzDdydZ#`T4z7k!Fsi+cf`EX(3huwPGPsRetJ z8q(nIL6j%+2CV9=AW5R;l>M)OZX{4*`|kxegcA zE-!)oG9z3Fjm4l0-+uoShQj3nmk)HER6MNCTr~m%%v4TR} zgD^m#R=X8_8Gac)F6a!%vFWmX`+`|^#V3^d%zK*PHZ?tXY8aZFIA0Zx94Q$Gse@i) zDbINco{HN{Y&w1&Wpy6V+k2ZBP0RM{KQ>TQgF$U#fLD(QWUj{CuQq{p@)?{{%De(j3SQFr?- z>jsHk6U@OWu8D1Ea0A8O^Xx75JbUnIR1LfnM8TsB@_38l zV{^`y!#V!V{N~KkXzV6yhcKah!)l}`nH?x&wTTaT+YtNpjHhAt`-hI$KW(V@9@(m@ zDYm>r)^@47oZyi6H{$oS8u(yJr7ytu-{YtPk5|`$?hys&%&WBJA$9#undjkQc{PvWfOejy?K9#8pxt zYxfMDLeVx+?wiH~)0=Oz3l(y5#ph>a`(?N$+eq+qv}^8HNYNcbJB%A%a_}2a@a8u_ zKxE@}(B=HmQyn1J`^&)VQfz^!P!FADV+ou9Y>!Q+SlX=50x#z{@p{)<&j;ak zunH%v6F5+O_VSKj45=EL`UDAbz(FP}YUw$6>zCbaizY zfH?wQYD1fLw@OaUzOi((5Fj6^n2=oODsM9*dW18TfdAf`$xv**Y0;8F?ANuskVvRX zLv*Yl2Gslp3)$-GDsaQzUBtftN~2S1ITC*ZS_*=CE;d%_9Y^`8PE`hc1T! zf57t@lLCZjvRz$Wl+<0cm=D%h{tWDAH5CfFf&8IJz6e9`dIw{9U9d)<8DT4rFfzWF zvU}D|5}!SfH0}bjtw@AjIC$P~5!}ijv#t(W5g%0h&iU2?NXAtfi&{02MEn{~nkyrx z^3oi6;?r^6BHyr1-e17q`z&ziHILL8;a#yh*B4kT^vXIl*K9nhQFY73Uwc69y`6Q?Dm_WBQHa@eF8-s@$Sk#qW+wFGQc~&SFR~N$3U~{Ijz|1@-akq?=D6v z$`HKfU@AqD`#n)>zkWaZ%T+(+id3W~8$@F+-&SOKm5ziy&9 zdY>UqTOf0G1v<2tKToWEa{QC0x^N{S<97r{_g5uOp$Um~^2Blfgsuh{9bR6n%KcO& zPyQ5dTD(PU-SGR=xl+CyWXIo> z^~*LpzVB;I%u+Mz;!u;6E(Rx ze1aE^y>sHAJJj_!+wu{-nY5`nPLIp-__?;J0(D$3w)WSumdrDh34)NoAgVv{+rN_f z#r3289gQti?w?t!P^3@?*ZC7H}qd2*?)Fm^>Qf33Wj6o zf59SEc8QIqB5WdlZ9RYs&?2?ExlMS99UMX2zihB4_EW7UYc~llKU+f#@<_-=8=9XI zToOn~_xM3vn%Vm?n55W4*$HEW2EZPyJHO!cRN>#$5QfSE+qX$j5dv9g=i;=mOi*N$ z4xJs4F|gP50qx=>#*sbhldM+$wStSub#2tCFYS5^#T|C_&uW3N7_;91XveS8?!>Vb zovDwP)uQt`vej!wCf`1WN?g+D(_Y!QE{D=QzJ8v*4c46?8(QlQU-PFPwt z=z8*~`@Sa=GWy&=FIDClT*ARvM)r+D4r0LV-O^BO}a&j&p6~Lz1t5ul#6_lI0uCrfC!?%eio?vyV6ruzD$! z(WCHIpd|F2xai9X$AIJF6{4!NpTuj0%UF$tauw$jkVgK-v*nr_in?|OXBq3CkIba3 zw~47J?v%93OL41|R)&gpi7R8Qk;ZDSY)`Isd|2myu&7sOdQ4p0Bt28H&^f_dHGg(bTA*)t}*Kd3ca(y?jjSU6kF8*JagD7aQvCI5$eF1ldIi zQ9=L^DWPpA!==7NZgNh)*=EXN59~eysQj}BgnS6DI_pjH-tB)&)R=zDh?Tt$6 z1#r814?Occ{@OoSIB)20eLI}7{(Tk^$xz;=c^2DN2@+-hk_C$G7UALobWL$j(1E6Zv%g8i zRVe`Mu$Voa-b=+cR}(bN`tpr?X_DbQ5v*2fW5&L9D3w$P+dQiu(i4p8o{HKQZFADT zB_l28tW&ZzIi8t@fsHW2Nf3w04vLw+;E{#`5ZxK8JU)2o>waf>-9jT8SbbK>)$^G= z$wW+>7PUfmk#L{GF40#4+4O)`QG2Wv{B)aHX<}dFN`5_g7D~KycG`Kw$Q*AXH*8>D z!N;*h)Zjs-wl|(i3~r;iqpz)If8vkFhxQwgtFO8G3+sik<|Hw?lOsn3rg&q(siA9+ z*|EceDY~zz+RcdA^FM<%-Fao1vCsIuc*xFeX(qgrsu+=LwSjmaH8;D8m9e;H#yC)h zKqEwr&@%o4EboyvQ_EG^ZBu2qCNQb^{Dz6$PMO&h=))8ig2W(WmX~;z!Lh&kQ!C>Z zeBp`~Py#{x-`f{x@FA|nL_2da_D}+FJW;8*guM zO9bEdezJB1aw!-#trA%LxtQPhl)!snlsgv_k1WO`e{8VsCx(Pk#zvC-MNg0pA|7(Y zYFg8{ze(&;@kS|voZ(!w`$gA&kNIaqM{^#bmcO9c6Us$>xPb&?+y(fS$MLCDZXb5xcK>mgY`XQJybQu6 zqkPS~xjLn?i5dug%=y8}e%{W$z?TwB%SB>7qQVR8+`P0LWpm|MHs}bC6SD$wJ7=mC zz6u0&907I^dE6}n-9lmzMyy{@w>#3KL=}W0uizZ9!SA>Q4)`hLgk*1B&-jD~Q7r^Y z(Bw$2Ae+FXAM@zKV*TGtdePtQO*>7w|2@ufcYi_K1Vr z#x0m*a6e|^_T9fRpgizu`+7*Jp6mE&i?;4nkqanV|LSd-@`or3FsIua3L~m ztXO7;ZD4|chc5`DK)15fygjqME`BpKiGs}TkQd}$4%k_&i{CLy7chRzIZsPs*&?62 zOn2r|xnAfAA9zuNete3^{d~vxuXFA{O#wGj4;y2nMH|8b6rFP4s0+u*Z)m`a?9l0s z=%%Ws^Qg~qK6vrQ)VzI97E&9Vye?bt<`LyiRbcD;w!k1dGG}UvU^kZvm)E-MGrDwF zg4E;6UPi~jV1h(~bP0gZNE)`*N<5JD& zV7~>U6}*VLdxZKil8v#)O1^7WC9uT?!PyqmEfN$o5+xyEWw9h_J;+3oR zLIi3`79+a;RQ>1u;`_4H^26i4XR-W#qcBXLG64Meq62TjyD!B1_p-@WI%e+~gm&GE z^Ed75?{^?2+0ptPS*2#JFc87e>MNDc0Rfi`hqX>7_j&2-$aabA_AG>n5Y9yzryPPd z>a2hul-b?*Sw54;@el0@g?7k6#YD)ZxT!GZYFVN{#W}Y2YSZBr4Xq z_29`>tvxN%T@9oQ#-PHz1i=S?i)#B+IJ|g*%wguqisSz24%63J~PDL4xl6Ujwr;)EuqZpWQ~ste7gjt@{f~q*zksvI09LU z#CxeFBQX)4T10Gs1FMxA)hCE|gC$PSF=O3NZM?>iYGN?}zdjlH{)#Zv(U;~mdMUe| z@VzfgTUgEdO^j76vx}38z?2Z0%Z7jog{U*u$7g)vr}7oll%;zDAee3QBL|{0%r(7O zTJlR$+9OtO%Yg&IiJ@AQ39 z(yZe}S3UAM$_qT-D&uffj1iFxf`$_tB`T$}6-O1f0L2W<8s6BYs=89tGI4GnxHTNf zSF?fZL6@KF#x9nIWva=>1qpH(qB;oCu_c7m+?ec;i6P*Ruf)p~GD!`}GM{0=TvAya zl4PRXhSMW;aiqy{@hRlKjCW=~J{z=KW1h3M?<`WwI}YSxbF_Rh<~~EE8U-mi`@U@M>r2j_%;ioD^cdD_W-?xc zy3xhp=VwRb^Qn9mT)b9V92(DY5Rd2BbHXZDFCPg{W*oHSEqh8lv_@>IJ(hPE2t#}2 z(r=FI$;BofG6Su$j~vp?Kd}=ytQtQV_sd9vGI@)naB{R9Ff_BG69$VAYFA8lKd#hO z%Am8K164(}Mm`TcOPPz|!^K_S6z|V3zocmmVI#RA#5|SB{bB6foo?}*7!~YMU8#TP zJAYJ2aoUS^4%E^02{_`YR`?AV%Ae$*P2| z4UBTQAH^SOF-J=Nrr?poAA8rL4BN&wKIH= zBBK+9^<2DwQ;~dg9@YOyyMQ0Cxvxn#?{zBi#}CP8Nj9@=q{kw@=c1XG2!#i(ZhCav zB14ZgT3}G1`JYBAdF zWc=Qp8(r#mEPA9IW!RU`SbO{oIY$KvH%=HZBj74TT@`J!bcmo-W?=YrZ2Sj^- zVjz;CPF*RTlk5E+h!hz|OYTzWVzlZKEL@S6XP}ie9_rW6qr2^Q8QZw9ZR&g?TT(zq zFr9paY;6{3E1&SSpD$*)zdr$9rXY{BN%Ob2v7L+7ipx=7`T2HJz+w}>z%+E(Emma! z`2GC8E#UsvG@CrKjP3+<;dGL8tjO*mDQ`&p!9Dhld?lGht6h>9?;q7dN27?Q#*T54 z=soH#N=AuneCCL6!TW=I`~;UbiqoZ&x3Svnp#$l)f;|!GD z>t%npU>2Dp*LIQV+!%*Pa$W?ph&#)c38F(|H&Q90L5H%WO9_T2-~yVLWEhbqju|)F zYpnUb@}gT-b~>EEgXq(CS>8M|_J5-T#ZcaA=8$$9xn!SZ&OOhuUKc0=7*HDmkk)+f zt@*!*?o+5Y)}QK>y1iYZXW5iXWWJMo16fMNz>abKX^zf~g4iL&;i!f|39dK}IRtgo zMJCaNaG*}UI=i(s=AJjta29o+WY=0M2RghoYmhET=Yff$^!ZrBhJLWTCNfynXe!ls z`?CUE_$-b6>G1lqJYvAlKAFe9i(9xJ!u7jmaPF1r`D}3vPapj%Xz4uu!!Udz)m8>h z5{>9I#ZT|{XH~u0v2RNpmCKF=%k=n=g z`kBzu!17L^4SFUa-%E%xUqO3D-Clii2&xu|x>G;qbnRtD&Ww!`3qw=HrTc|9C>g$` zcgoKO8t&)o|NoeCQ{8>=N?+Yy@$T4@lctD&=k%IAt7-?l<5_ zX4!nPP_LjXRw`ulO`{o1Z{d_Qp8 zeJ+;cxtz_0(a(Fu)a_~`NBHS2iicm96g|a`Fe>g=_105a3+98vvy*)lT(~9nPC`uZ z7ntnnsu+7g>1Mu!04>4|@nD#$&@$Si= z8gu`nUXED1{yZUDfxBqr!IppP5c`mvt)sweu}b$R0Da+dBIQE6l}b+uMH;#9?cTrdCY{mnIv-uQRC?gvrc; z_K8&{AN3Ub_R^lp^*gwCoSN_oRi}r$$)vc=c~z2^(B1|XwlL>C1<1uMGr=tQ#|Yi{ z2Coms(=AkEF%rSNw`2SBKQ3mJ(dr8_W9FJ{@B`ZNrkQIT&4jQn2TFC|;;j8--OGl1 z8TY;skKLYmkI3m`Or{L-VCvov%-o+1nKUdfyHBr0VJ5N(zn+&QF<% zA)z})Rv+2|eHE|EZwkE0hENAHiRL@_ zGwWNraKq5=`ZQv(O1?Rkm^b8J*|=e}KUVranY1iZl8)CNAYvZ`5LFRC;x(l{%ZL#K z7p`ez+;u`?>j}a^r=kJJ*wM!6=B~S}pX}*!%R^%Hv!ejI2qeRg-+u{_uWG(8>#;f1 zLqU1Y_h2HiQQ$?-hwEWri}#W0F9Wuf#F2h?tn9$}sV47kH}*& zR^)pVNlVN7XkM3;?vaO%g;CKPF+n{JP@B^N^!w(Xj%~@*QShy#eaf)hdw(MeZ}$h( z>iocnFcTON0s}=c)DuL2pz=mHTI&}3J{+#@0Yt>tTMOf^PG#>y6qqE>A9|{IRYIb_ zZD#dX)=*+xEW>T*!+f2M414_SiTOTRenVGLZI!^=3>Ss0=M)VSgnuB@|6S=9_IV#9 z7x)WN0wE&nus=}f_ubBWx^Q*v*ERUp3=@!~+y)T?z-_=cRX?WBIT{JwReSLm_%GzW zZc-5BIY32yeq*8n){eS7xKC{OGIJJz z;&FIUI4w@@Grj4`(5+86H;Kc6Oq5{o%+-7E|C~I+fw5#~-uu^@Opr^@jlKSuuc$~g z<7?PR>ymp@pXEOFdQ<2gJ&+DSZ63!rk!-l15Mk?@`Er8-H^mmr#akIvltsZ*N}Ie2 z!$bA_F)b|eYK3!A87JRFS)x7MZfKit!#LcVC*$%}p)EOMTN1UJ?1g60A?Bx49YXUyyFo}IW4RFT@Zs#OuEIG5F-(qE+oDo>%0(Yc_fPz7**a8z3c0<{iR zi6(?PFYWBFiJnGdoWQyU&}@M~&XCFPEp;Q?KzC(Uk9((OYdg0eh9e^V$?ig{OJ8RSY^Vp%*70ns<#3aB zHqPVr!-Kb&>1fv`xP%_tuXlMCI!gD^8q04(UT3^OFE>*31icg4UL0AwE4_kvY;u6# zjUr}^iybx$thQ!ZMlOS9fq%nmEdp7HJ*lzWfT=8=EF;icy90B*(xwmQuIy9NO(3cl zpZBwgT0R-}9LM7D-_H}abG!v>gIlW9TuD=BEP;~>IVQxjlW2^NU{MK3na1eTi#@`I zhi%@nv1tm#D7te4`AdwXX8av|Kq%+4;9um2CoK;aW_?^+@yX+APxrrF?=ghV!Bwp? zyqajijo}~6zwEwnuPppG$&bbE7IPRLMb`e7*KeKgJ`bJ&!(e{kn9Q6mQxl5fcp`Ii zXLi2wdog^XtGW4sVz5eD#h{ zbm>dt?Lc?G-zD(>+&2AxKRX)ck}KlKxxQ}uQ;+tVpobqM$E2$(5tK4+g*W`yQ+tqr z&n6ewFYDBU(Mn@nAhy|51!(s{a?8innP3>}w%A4cl?arzz`#&;Uk_O(#TOqV5rg9_D|ym2Ta*c!)?o6-Q|mZ( zI^%XOrXYXhhyPhk;LUO~Pv)TT-X0o~KAW!i#IW&5Lma6=mz1Er;|8+;hvdKD(>FGR zUHh*EI|RFNFG;|JhFHUlI}GzK6rXb?{g6gHj!$lx&2@G5KDb(IOSM8kl;51Xs%Kki zaEhLD17Ua}cD(pSEYW)5+HC!fd3lLGK_c+*P@Qfy^ZI=E zxn&fpsx!kmo{i-STd(>bE((19ebxVju_GyKCitB_ai6VM`aLS+%c~2UOo1p4d%3FA-Bf7putF~B5pL1l`{lb@TgXbSlY-7j}7TE2E`9Mw!w$)yR z^&IPUpe>i3tiWE*KI{o!tl{MDcdbEuLA0I1MNmT)$xQ+NZJ{X|Yx4A#n`f;&nezd! zpEvxOkKGRbxOFC|Cl3?$GFXI;;CI~-3af*Z)@|)ORcm1^S~o8cJd2?DANCon!Zk%cgluQ zf@x5IJR_df#=0^&_~A2FErD&{sm0C7taTyrek7e|bn{a4kue$W>mv%GaioL$g23ie zV#V4FA;dM#Luvqx)C|>@T>@R*tslhrYmp2R#Bz6%eXgqy;_&W%2UX$^+W#4Iu)gG2 zi~pw?lhlRpXqRz}E(~OnW`%+HQ)GgG4atsfhWhBeyYNzcHE13TQ$ao|+`WglVH*jn z8Rtx#np{R-BdEW1pGwAgwy`f6laBEeQ8@A46Rjd$=W2fHNe8~ch3h|qRtr1%S?0Yi z#y>%CD}O~19!?tGLyioh6nyl#_`%$k{VpkxhKkw52r|WN?B{Xidt0PoVPRv&>B3xZ z_a^r~a@bk&cx=sr_Ef5|U2$@VII?#nZM*JgI)G5&4q(vi;6sV&f`|YIJ}yW&2$vax zIfLEqI;COuV#a?A$g?L{tY9;fnK!#Z*uB5T>@j=CTx~!|4_G=QMFYcFdU~-K%+ff& z9#fxI+YOqwt#TJ6$hxTvw5>^CA8M|ljFX~hm`F{1AQ`^wQ116poV-RLH}dhSg6OqVZQ*H$>X*mg z*_JB3>0XG!W)qeXpCjH2>|a^8PV(gAtyr-V7#u}5Z_t0Jg}W|!Ec)%ytq|xm)!ok) zT-H}~OG1;ao;qEgH{uGiJzPa4%$AQ^t%?3zLZyE>L>T&om(pV0TV&S7Bh!rA_?cj*7{N;3{!(yMB=6%|&9ZwTwFHqTLaWcZ+6`cI(1 z;_Y1%Rk%M%KFl-8x=Qn6*K?A4U2Tvo`N(oWfDSx$P<6L2AL>@KG7RO$5wHH?IIYca z{lUVgN!fXnS`Ro$am0z?6QuWO@c5Hr2UAx)UZ5N0WZDa8K%K*lPK z+fj^Y-Oqt5!mzcOC(BAsV8zybhM_h4p3I^(_gcgD!DpHuQ|)i_(W90w($BoVHi+>b zvU*H%)3?3}dq%@lbi2h(g0I;9l3xSR#Ui$du-^Ox32D$km-LW$X~d8d#fAbaaFq3u zas`{j-z$h#>oQjf7Q*db13=m}PzJ+4n#1sY0P9oAR=@0tmWX+i3hPepAG#1Gtf>MU zp5frvn!3k|L>C~mtvX)?_-T~A*_<=)UMk{QFrOntX6#k@2&qQ@c{9<}O0 z_!>+O0>xGF4iiWcB}7J1@^uHtK_Lh=$l9YBMyE}yqoVJt;pSf*J4AyKuik2t=K8wC z6H*XaqFkr*KNbGJL=)kaLFV)iZEJo_Ai^|FSOMHmbbBh%+JN_o=8=fha}L>s4BIgh znjrHYNxZ_AeSB%iBZ+yx{xekeY6Rs@D z-a1(#Ap9KrQ!)Jg1aRSdzsV@&<^4_DuH6}`{<;klh6Be?64pkITRRRYa-A#qMqMw~ zuzl~%zk2;Q%DgD;y+bV;Z`S`U^dy$TZV|C-io`|$x-=f`+Cy^JiAT{Aq;q%iBCKvL6 z*FVHfEUAe^pYYoX+pc|`e=E3@Y3jBuDz;x$x?>Mo5&hi$yCeTCtK5nL+QDWZSIo-) z333yJZz$^iwk1RpjnZ#)wC7q?HyHW+QDk6gyLUuIS-)brP`$gr`p7>^L5_@+FVIGd z!02YBG+^kY;4Z^Y=coyf?^XfB}`Xku=NHAQM$PeX<-02{$WREAG^%Eu6WUDUs}8wl)K z7Hpn%rqc@2#hBz9)R|V9J1B^QLPUD-Y*zVq0?b1qm*X^keYoVu_anTz3(e4e4<>F^ z%`DvECj2ZidYFnYzn;Fi+oz{B0LL@|!Hoc>Nt}o%VPXIIG)0butK$2pG_nXe*sD+u z@lH~-6~&nIsmvT$z0eM~p+P@fQl}T22M27_$-SkY@U-FxzIv%WD_m)c4F14c(vbwK zUnJjkMCn>6)ssq0dX8G*K>KdnZ5Oai?e+5ihXMaJ#`-%3Tv~rYM11L@zry_ymKGtm z=XD*-!}Up(pysg|`35zBKLTjhAKpCPzGAom2n12vM%zX=9_F1Of0&qQ?57cGmBsRnf6?5STZq#v9NL}lI(pY+RRvXi*vWPLnWwAheql=^{*Cf{AO=!OS!pa|`AA6EvupM3MpxZ<1+c>0OnZ>`3 z8+Z;tDDkNwa(x153Ln?t*XFHc*WqQ;_VF1~JieYobE!y#MVir<(y!~XWvd}xNfhdL zA`S=>Eal`oDFxQ00y~qZq>+s}0z&sWTx652;fq)MciXe|nr||W+Fse$1Fdl3B8l0g zkS*l{jNBqCx$GTV1Xddja>Uw_q5wJtqt`#p@PhLIc=?5aUzV z*ElwpgF;dQCsl(#;{Ry};cpD?Ax#rQWjr5<&+ba!@9P7QUl`J;3YrR!+*Mw4ypW!T zmBD8|zv|zV_w#$<>z|7^{&CK&!}D#A<&3r<0k8gvW-Mo_#~~hyL5g^~2Y7KBSKDNr zanoc-bb*no?O%+KY2QkkcJFWX;`rwIy#I+El@XXV1AP6Nj)=|mPNL!~c3W+MckJzk z+6YbLWth&&1}=<0i?)G&g67u(tOZ4bs@a|+zPIqjyz-j-$b}Y|r%S<4-KcAr{qZMg zE*`#CHdw*-Hbn#m+V&&(fK`E`nPjRfa`w zfZReG)?RGtBxQT&{ey?>EOwpu{9m{L($o^*eoFw-(a~g;)V9k+ZI5KO6PCMS)0(4(CpXyF*#Bi>NYoLqBh_3+bL8OFb z`F+^m5H?XrsHz}GgukF^p(XM$?W=G=>R3#qm62EObGJdhG2reyxpPrh28Lpc^@Q0< z&6vGwiPO;@Ad5skOOS4AoTlTLk}s+e-=HW}NOC7b?l5gr@mbKqLFtf}a+cmS z_TAhO;4Xlajy%eCU)aC%BJQghgt-_)UU$1v6-c#|D5+#2vd_Z-X;FR%XS_SgRUc!A z(rupiz!sQ3#Z}mUadfloYa0(MJ&Vo_ZinCH|(;khX2QNT6CQk`c2wADaAWywR7_`If38BMOBx(@4*n9C+_A37( zGj?ibT5_;(8!Crjlb&RN$k`o969hgIpbMsk^FaSq67I7vflp*0=sj*mNIhkp|6>kg ze~LUiGE8coOO1@*GWln$e#_D@>z+gRjIf#nN+Ex~U)GXE6MNb_CCffXZ{V7nx9#0# zP-t;n6X33QD)`+lhud!U25Cz>rMtIsohzM)>cz?t7U%TCem|Nop%@Zks1c`zkek)) zn}gs%5%JX@{4xZ{3vu+$gVrG=jQ41cg5tl4jOCZgBLl}Msk|$Z%gZB1v;U61 z;Gt6RbKc;sv#)(rpGHu~OHiUhYU$s*h=0~-v_GIali6s4P(Zj~5awaU0QA+7bcNlG z{_`uAE$T@@0Yqt<55g22^%NN+vp#rPQkhV>6>^L5l>W}YIxFG<7S8$CTCuU=UZ;&z zJU6j@++O)7m29C>fCfEnM^(1Qh-Lc}f-9~}Pi4$;4p)w4U3^{4V-f6`ntP@Ng8DCyVb9uH8T z;<97CDV{yTUUa@j0)>*^?5%=WSpP_WmnpUJ9A?IToPhzMu!)T zdMf0?pjp1ibvBFj>OhJmID8}6x68o z7o3J!`2s5UJ9`1g@rm+>1cfb(rFsN9x}nc#FNum$mh8HpC8r2MrC(RN{|M5zo_@`p z<$j{bmAGZSHk0(7YXbzMh|FFB0;6T3al}KL$}i(}b_Qdq{Zq~`AZ-1A;;^@JQ;+2@TW2BGHf1xO5QTHUt zh_%cji_wx1v)%*LO!j%B)7E~zUVP_R*)2beTal=}Y}GPFXpgmi=}5tY4fpZlm|9~C z{o3hgV#Jq(j!QVR+^2tnxC3{+v&jJeI=SCf?RM=|wTQ)R;YI&QIeBB1cm9)D9||g= zOGXD>GFpP(`zdt}&*A?RHC8qAsaN9;9HjWim*-OgPD-qH?|K zX4sNM>u*3iZ=_`kUs)>Cx7|0uo{HSWC&ZR=CvfUASuN{V0_mzPNg_4I)4YUOrA>Om z$3>_gpU;aq(m*R^2HowPDNY0~chh1Y( z(Y|zhZ5Plm(MD9RvIF6a@rryJ{1ent51;D{E>bKSSS!)`T{I%p-ryB`GB!n-nXOV4 zdmz9pj$@>gHVqELrcC7CdXI(Cji}?nT3BKeA$wAk3ao8G^*J`qna~I5p=F~FKfe1= zPQ8wFH{if6-X)$RI~1STSegiWs%|%9K09%x(tKF$8b_B@hMG?Ju3+zwALa6^_4345R~c3H+$$C9&eeJgY?3N5$Wh8k-8-veN4g_&x%tSg-enndSZblWWEa9d&@Yy} z;Y-|o4nvqHqbsdQU8o$1!;x&-le`^!P6)s7n^chWj0Bkqb>v@cJvdO8pl_;4>wht8 zq6+k5mm>FV=I?)rtafxTms^SCmZ1nj3LiCAfJ$V9>;a)jj8B@%^_*Elp%!MwM@~XQ zA8)AP9+06$m?!?iVv&+~Gz&cWN~x1JTKFP8JE{YObh1mWumNnPgRj5ZI@F_|KhDeU zm2qe3>EWcSFiVAOVKi9!zcW2pJ1Y?yS6r0^e@S2=7)?Y(DLv7}-xcKT$4+Q0-nAKz zRpQjD%D*5xNf{;HMQj9_`{<+6GKaJU2311b%#oqCOzOfPrBF9M{{*3M7A#f{J_*0m z!)Jby5H<1E(lIpRgm$9)m58s{pT>xse`dIH=T zf5)GyyIyVO3`t3i{O5DMPP%}R{Q&7+>mJEJ?jtTAcVzuMeMY?Xj;cNo*|vUz1Bgnp zc8}}}JS6lQ*drm6z^n-uM_W^meh{uLh*lbe{jk+CJx*RocF@8%&8zcM7J8ejJZIfo z=;2YeVA?TGib&tgp+JYR3#AKNu4=rlNA`(%%3G>_$yn+>2(^oLMVZL`A|RLw>f|9D zeJg8dfR=OKNL2_q0SQrDmQDcXg}**|j1s;Z;OR%frIzxHN79vm(~Tno`rLT(IJIi` zoQuv&Y^dYow%F`8LBqBCl)jH*ubd!~xpM5?8Gl$-iAagsrY$R}RqLS} zI_(w*J|7(=$=GqU!%o#L)3$>2ik|g@}k^DWPoLAMIO}LIJ27M^c}QTWC2ygGjU-+ z6O<6|?30~PhVSDzS6(ln0>ht_snGk$57na^45w4O0@qYv0IApTAS{`XX`Rz;` zRO;=EGr)62%?M{oe?RtS&d^)Q=Cu=%n~5ljGRxT0zcUP`o)?i*L+gUq`^(t5SzHE- ztqO(_6-XNE55IM7*JDTDPhg*Jc+12p!{m6?iKudI`Glor;IM5x3GVP`2s0RPWD~!W8>Vi+6k-R7AgZ9n z=C$PB7U40{I*U$^QWJ=Ob-d{S+Y$cYw4>ee;kD!|!aL-f#CYX~~L2iUB0Y5m63lg&2%Ktv(pbwpr70hUtc- z9)X!CKpmMf+^~zjkP#)pH0Fdh=&+r-I9pK{g#U@`FtNK}Pr?Zz`9&UPz2Ld=!C;Ki ztb++f+8Tfa`M3xJNH4JzOaF(hK=6EYVG8mrry1o`oKyCrGAwBpd9B4d5wlP_!;R0Z z>2e$g?0F*_XNos|5?X|h9IP5-Iol7g%ZNMIgbIwZNeYfnCRWJE{&4RnA0UG^+y}@ zzm|r}E$ZI^-$6 z6Gv7FYn??Kz{>CNWvO*l^z@hAE zaKP^gtu?{IoGie7%LYSz27k?y=c^w2ctE6*`onHCo<|XVdkVRcte4NqG|X!jU7S?9 z`Ix#lxu)@vQAO@nvu>jnOzozbz2=&2`n<$NaKd*DTzAXyBRjB0A}#u^Kd1yjQjx|5 zM1sU7FFAI#nZYxYz?i2f#?a3KtjH_IN0DW!aYCW@1at3w^rYEv9+7TbJUQF{Ixj82J>pYht zajObB(M;YTA&fz+{vS+o4W4+CT-s(J7`9w~T`K8vX*7{gLc1*W6ih%mOO|?~?g5*C z?ig~kLzr{RvvW+zOfSiwpcs}1yUZU$)nl4*zpHOj`M5?MWcH*@`#5ClJxOTpykz{H zaWK3(6OUa=MhA7$4b;^Zm|N<$0zHtiJU#=M!)!@hRvyCel!{8pc!rG8{%4F3FTiyW zjPK&at$__>F&jp@8Fq#ouT_X2xO+!Mp`b@n`0+8Tq%_3;t}VE1S+eZ=#M75C7vc{f*d# z+k_H@_JMju7H&a6h@1z*?MvmqSD^om?gUg;TtH=g4yde>fXe#+)C-pBZbc)iu%Zm4 z|JYDUl8>Jdw*h-z@ddF0R_Qtsd8<}@!Rrvde_IZ?(KiUj(DH7G`rC_)Kdh|0Egpb= zPFoHFR)fEUJW{`A?akaFra#VEAnbT+q3LKQI|H2lx(A%3Pp?!7kBWsdB)DCb*LO&_ zdihZ$q29DctY~046d5sYC+D9aY}q)R{jYI)xtI#iG>}SzgKOzF8vY}3#O>Ta>t_kT zlvF?73>pMhE42Tcz-S+IFUXaNh#_t>#<<-`5h`N(55y2@eWuc&%+5Nq%t`|6G=J|E zzYAi2dJp$Px^&Wyq|$+c^C!qt?BDY;StQ^pefygmAu6k(6ieXZjE$z)-M8fKH*{0X zni9kAJPMsID%?E>iQbU0NcMG(gW#la^6X&V8?0}mi2jEc>M9+i7Ol@QE*`?^3qa_F zH4}l5h+NTSu!7Q$9N#9S_78c%z`g#pWV@bS{m)tcNEm(uN?v=~q>oeKUG>^(O|oxx z@2AW{PJaARvzc2;A}!vf7YKQm+34y=&m6AlAh!Q_Q~PYGyLsXKcw43&`blrxnQQ<< zW03SoMq69RoCb6_OE`Fz{*KGU%itNY#V%9Aic(Xq8EJ!M7UMy_eC-Hsgk(YIASKmf zE>|*!5J~b9D={Z&`87$D&xZ%_obQ&*m-RErVk#*))Hb)HpwZyQnW`gTKy)l+k!l^n zF#r;w7O%4Py8kp|S;EwzkbQ<;>!SUammDsq2S8d{6j4h_KaI(|l9KI!P}<#|Z!wms z2EF-wyzR$PNAK>Y0&B4guPwCzLQ}anutK3WnP|;;3{kYF&Dc4)p`E{lA9ru!H+)HdeFNYBjKS*xd40Jn{xf2QUlKtUfwZ3&#rJ5+7tm(Fz5jNsA#L za(kNHQFkCC+41`cV(u(5)#2A9)kxIHf<~h%`xAvV?-)6H@Mtt8_atJUCcN|O zE6`-`c%EM~ui|s6&iR3iOY6=lDic^KcJO*sX+LEQb^8Ss@vB#^m;~~t!km1hJCHYN z$?aji^+GLV#CLaR_;w`jx-K1Llj{gl zSxE-{{~X8k@otXbh7fslIrYbK6RoHNbwhGjknY1KjVU9J#Irs{QxYU*;2U?Q z0ay-LwF{p?8!1Tr5D$Vk%?VI(#A2~MNK-iZ(fwbJQ2>tsIU&dm(KyPv(-z@>V6+wM6Td9SJRg2Cqm{eq1J!E2#8RU47edXNw`}3nk{3WQ#Jc;NACiDBS;3 zokL3pp9&xrOAzQqTE<+CD$~SPS6Ps}*mbRcurbslt5J8~fk=IYGR^WLjsAtR^VgYd zmq4zC33IYXF>exTX)8Y%EQI&9Gug(tJr<(k_9U^TfQ0rVT_iT5uEcrM3$j#jsc)0T zT_*;p?N`XUx>G3WLM%|}>_esbLT#xw0=Q6#S{Xw=A_o>4M&$L#oGkA^{1JsHC#S$^*@50HCF*Ne!=@NhF=xT6^BcBYcA|wt;J#LExY1W|X->2ycz%>X;NZ9m1 z8o^ZiZHI-mn&xaE2fmU(Em~pB&`#ZIznm}W+hLuTAL~jbgC6)O z@dp?Oxp97Iwdv%49Qvm_y5L@{gsV12>hpqA0ha$>KGGgD3$vnQ+vu@bD}Fyz;j$<^ zg6(T6PtaIiICzmy?vo#}H0bxF= zmG=*6!iC3>itkE*7Fn)aueV&Wo>d#a6}H#OAtZC1NrVl>nIoO?aU*75lW;)ZL8Ddz8C%ddgGC3uKRW5Mk_2;twxBOE7f&_l$fe1 zb+&O}Hy<~HeV}xWi`=HG@G@TLp0;Pe*vjY?$a_bhu0M|Zfve7&qNDdvAbU={6Ud(H zF+Q(bBbk+XVd?&n-PltCP;OgS$e;rV?INLa+z(97)_;vT)grqVlK*b!7Z+bwoyT2(hPBn%!0?z_+m_?#T=whg$s_OGDO2M)Vat_3-GSwgA;0d4 z@_>zxt{T?3F)zbq7tUWY`u1dVLCmAsO(d)M-FFOS8)p?VK=m)@t5>NKbTzHNOhw(9 zC%j;Yo?)oF{{($RwGouOfIU^<+0eGN&ivu=O}YI8dV7ca7Z>$_1%Yg505t zYrQ+cH^y4>9_BNBFINy|RbD{w@LQcHHX2^$%P!Irg)uvLYo13N*I0)}oUVsk>BOLF z_%*KPJ|q>Vr+?~%rUtVqG&Y!4i$G#e#JM>6fc3I|f4brEX#V?Q1pz0%n6E0HL_w;P?aPk^$R6nwJB-B+oL&Zm>JOY~q{>>7+ukXq&WqX5$u=;HXzq$7|v3%;6%ggl;xRQNFWmbU}}b$=ZEe!r&lfV<542d8Y}j< zr>Jp*&Yat?&QMSRia=3?Wt>X*O6UlS(oV<{_u)rU0rjSjgqjwovnS|v{>-f@)jXY6 z&#I50A1<=b-DKjw)oD1{9E1Vv*o};MA#g(sEr*H<=%b_j1x-%~YpD(ZHw# zCMAy#Lf?DnQ5bmLqKI+@aSi06HrhFeF8iWIfO|1bwP~ReZ3ep(fXJC)+ESbvpF08g zFrHYc^`MO;_%qS+4poK7(F1v^ITDWg~Uq=S47GQAYZ(k$>d}Wqfri(I3Opp*pqunao8>--HnNl`}>OK zQgJN~E=Hi#^5iI7?3B$t*!X1)dkoNQu1HIL(^-2IHu7i5J`|5QFeFq2nUz~tmZT~X z<`bzXn=HsWkV2vP*&!iLIG^}NP9N^Z#XYqDQXc2Iv88l(AV~@GlHsvJ0iQBQ!Iwq4 zs>d{fGUcDV*Po52yEQG26`-*dIDJJ;_{|P74sjfXq9~mrohO%>a54GUyc!17LN6w%;q97 z?qr^2*pq=}9fH??5YWnApxM?&Fy##(GYVJhTB#eK=ZH}Xe4_jb$_LzceKv#?#t^Z# z!e1$G)kx?3*PXw@VH3{|g2ZGd1EK;8FyGf0zR0I#CP;_g!+m$-_8o+o_|)2=H#opj zC`mmvG!tX&ZP`U@V5YkM`9VT7gjO&L&-TUyw+UO-iOkKDg$#nSVDT(5I^Z7#(|5b+ zj@!-D%db)*uD6>pzIly&#CKMNHN?Icz* zJZ|yiSYkrvR6JBlcg%zkWc4P#prd(bJlJHNy+~e+mPX3PoB|!`llBEWeP#+Cg1x$8 zdHo~`S0yLZtPE{7v#{9K=6L<;dkSY~u$LqhTvGTN!LfFYXnxV;<_-;g(}XBijAd_w zSCm3q=`^ZOOPa7}H zBmi^qdA z;`lVo)p-Ntme*C~7Kix8x#SJ2?9I$sg^NwOT^VB><#XXHZ)i*+=+n*-V&YRIZ5xBF zj2tBj_s@28d7c!~!~)6L68RH@?&KsRDvh03`~!Rr0W*V;Alr%B{*!iKxqAAbCyg7u z6O;5~EfVA)=@+ilBEnb-+_4JmLodygxN~Rf8Sws_R z)o>m%$J0+1+>c-Y5~CQuHzj%XHM8QIVG~LX!i)atfzfo+cId#eTb9my%k?e7{;>Bo zs!{OcXrbYqnvqaHuei8Zr-=FA9%gO$)*L+B1)d)RA09t`j0>Q@c1 z8$e8sOJ0sDJZkIcy7C9d^Ce;D{c9B||9k2*z;-awdK?{Ng?AV17~{#iw>N#lvfESw zMfSZYVG#gC$SBL8*qOq)uNa651_5a2f^Of>Q3@L&QYP=Caj1r1w*A{d9Bm zcu#B2E5>7jy4@vM{AC2)xNW}EW3Is%`@wD0=kcVUCNBHCZ?Dhta!7gB zw)hVLZv>oBAOlvUzz+}X-SJ8s_X3D1$hJTXK@>w^TQ@sDI{0m5f&bwh&0{>HI*fDL zC(`opHBR8;hQ#J63=*UP)_GFDaKvnrPT>fU;Q~cf>ga`n*5scZQaSD-50tK4u32%h zgvm8&#t}>{dkPGWr|#FCKH;IgY&!U?g+O{e(z$Z8U8?R%K{^)q`z(3yJ^BY%G)B9m zNSaibO>~eI%zC+)L>Y8rRk9|e9rn0?;1Xu<4MS#CI&9GQVXrFx@Lf|c50U0th^N%= zRp8Y9QzXEvO7FW1Ms8O#jQWOGG?h=u+i=9V9`!&4!ap6)sOh>p2o}jfYvPza%x-wI z`Aon61o0GxPth%klJa80&8(GJuRG@DuDa!n@HDEQy=shwfH>i!sPD1>9BULF)<*^` ziNFSJ<0+y^1ZZs!jhE9e%L)QpDL7v#NiQ6r&~ragN!=6Ub76EPp5pdE9;TNS^z&2z ze>TN<7xcs5mtMHEAx;39HC(JHi~<3iaU|;2-g;)Yc*naW33*o%K5a>U@s0|A9(6(XA-e+4x--y{#UJkNPD>rnuA*!y;#X6`y_Gxd4J0YTT zCe1*mj*Es{>f*WP`{9mM7kFI&PYl_tY4j=m=Qjm~yt<6DeeRg$* zvh1hokttP-R1$u9Mx6f^CcZmx82=sd*ZSaJmw%Nb_Gb-VAEb&l(H(h%L*>>7iQNwl zm_T5!j>Y{P$8TREA=_^5c0Kj%Ia(da67nB#8eu9a9HCGIz^%mF0JxR@x$7^mGRO?| zGZE!Q%LM%iXDBB0F03JPBi=%lIgHr6+9Mh?D!I#&*2{p~v<^R}={m6zDAC zXpsXV7*#=E{Onp(n`9_%d2jeIt?$)P&-icNk0Z2-zl5%)1z-HC_2e)!Nk0xc4j5{3 zgmypD?tDeQJfE7w?zOP9PJ9b_Kj^}%9G^P~fh3dkWR=hm$dj(dn$+trwgt7Ot?&k~)5dc-&)JAr9EQyd zO7r<0brRJuxR^&+sE=B+7SR9{=8{)=rGDCKQtGDb|CP=_Dh5Ez=Z|w9oCiNQ+ zHa52B>WW>Jjm~TzA2QM86`K0Uyhu%*Gq1w%B!xW>rV)d2!Z?vya?Udy23+50{hbCv zbW(xei)iajafSs&?Z_TAx2~`p`O+P;RFxsU!#j1#f2aG!%6@sakH!jUT`^e@l+YWX z2;WE7dDBV=H<_xS4*(OMJ^GA$Um8)1oRb3%vx&tdym9#4h-X%fh zB^8LBYpNsT>R%B#MZ_L*Eg?wl$TPiCn#RD~hdr5wDOhJFqb3HPqkUo#?F+ zT&nr`Y#fn{HQA|Erb0O%wmp5N}Z zxFzRvfy3NFI7yp5bcZ$Sfqw@XqytB_`&S|G9$2H+1t5HIsbB-1Yb}a7M#uINeD{QD z5J_DaA$zdA$vtd92+uwWit3byqkoI%9eCnVB(m$wa+=*g(!?Lj(xITTv-#M_~U zlEw-8d|xK9&VjyiAR9j2F9h!t4Z! zBprfIdNu_sa>tLKJB}5oxcCZ(O|o#vRjn-;&o9&sfn3YbB$02rb^CDa+VF9ss^dzi zA60%Zdee?VRI$31p>F?bER#=2@V+|>`Lpu?lG_v(0ByLK>h)-QaVEEigFDe4V``n{ zBaG>N89QXRlVe>_^%0a0i%)qXHuNdR@@f$8+|F32l3LXB*$rv;0@N`n;x$rnTto?XdxSw;DOvjW=0yqMHE>}b2RFV8=uh8Z(o{25p+$rvot&)GRCz+?CYB z%;P|eIRa_MMa!xWnKM(E+93sx((U*@buUuqhB=-uw_U^B0l~yy+18<{)@Ib%&3;?|GV4vPt2yVxgC8OMaetzbRU?{P z+`AV<%Qqe$$}`Lm5(vktD`i4sH+IPYY9A>>U=wB~H39SIp0P)%IQ0u-=4T0Z)sOk` z<9laV>@*!lU#Qr0aEBNCC$4hQ$e;ea!2TQccLYv*b|D{q#*L)IK?J#&-iXmQPHMHMX~?65tb zjM|okBItwaJhUSJiq9BRKS4?n#d?Vk;_!56$jedC(f17MXRi<}3w26|oM(0YmKe9r zb|+SEjH3Vg<3Z2SwSZ?P**Mg_1Leknd3O!?Y-3(g`ZfGThgEk1)H>Z$f>1_@PBI;+ z`{AmamhamKUs%sta^98iH#vG&9gW30s_;}LPR)HZaV2{@lDsTa)ke%$_HL{96<_b< z+ia^X?W(tSt{BI6aIjuIHBNmu$+jhD^qqFX#nF_naL zycA+8H`Qk}vPLl!oD24H#bOzZT?!ydjjPo?$Gd6eBk$dJF>xbRUvi1w9RjsB?010e zRIue!zqD|wge`j$M%#0%>;f|Fw-X}wfzEF1zMg0;i~>JM9>VnfDylkyjr^SZc|>O{ zn|%FKB3$l3%{m2p*r`E_%MP^qU6C((3YVrn3(9 zPOL>61N!qO>HJ?1ZYi(sSo1z%okByM=)t_M_YO)@&Rx;^pW-?|{EWPzzH(W4Zx}T8 z7~(_G#_yi&@V37zWN7*j!5GVFd~7sWXdL?{+dZMlgs4c7 z;w;d&fXb6WqaLD7UzMdk7i2yJ3b_x*6#j>5vAI?rxE88B$WZJ4I3i>6S)9kuGT@1okuIzPEdO z|L(uwc?ECq^BK5Y>ssr3p2uP5xrRh9rkT3A{3?7c;9DOi*9 znRj^sp1W84`vzL{PKC198HdYhkMeLM-kp4X;1c>s+VbcX8TBf`#@<#pNX7%sKyAy! z1Dahyk=%jA@w%B$49!m87&lLlU^!Oc9!moJ~d{2=)`Ljopq)29$lga|T z*qcnbxbo6)C*~;$G^}2{*%g{k70n{*NT=Te2^Z}=F3jqH){UB!zEWA?mtlH4Mle05 zr0XXTo?YaDbhR(m+X`Z#f7-qun^lNhCFudzYpYV&eKh%z^2JeeFiTV6{)=1KEz4Rm zrw27bxf+QBQ3$sjpM|%$_axZF!o6|kG(3gnmCVQVxp9rb)eO7F=D06{2_bzN(jhKr zS9DnaH%6b;LoHynZst~#3!VZ-{(RBL?h3q@qClmI0#kOp(pOF%Yxz74#{L#eU3ba5 zrMLl$Y2c2IGPOMf8J3%$6h_s}$q%^j&DaFw*yOgUUWblH8kPg)yj4+&78l2uOH)Nq zUez@ZdctYd@}&Z zrk-nSZ6Vd{Z?M5_IG4z0sBCLAp77byb@Du;tFfDYe;qslr4`tph_d65@+~5oPF$J3 zK`ly`a|C>dz`!%)A;hJM@gVGWb>?rxl;+WIvWvCx@n4t93@);F4-Q@hF-qCzRO=47!?! z{LpA`);W;-FHrX9N*jSbaDv|jx7GiZ=0Sy^VsbgYCu@-dhP36O_p-wNY@1CCc(pM3 zcTVu<8s`lh67zX;GRLlZ`N<9tF$udQoBO^ST<$ z|C|^6y4c!O?PxF)_=Ja0o2D_-S8~a&??D&HL7Q?^h*XYg+jH>Htx8vg1~y9c3I+uA z8#CtqSo7Z%hBvp^7eMr@vA4;soO9~({$;M9yYF|%n%+E#8z`pA^|O^!Vlq^bTErGG zsYv_*t(ma`j(6cS|juXSZbL^f&|c`|e@3|dgp z5)$%|l4bn4d(9F|*<%6Xk0Qtk66Dxs9L?M){7!{j(08zVEix z){p}WSHH0EyeJ}@o=dVlquY6wN``cF=m7G`9VUOyu&5HXAj(ZSl0t$Q!XpMT zDmI*+Hq&uF8LpT1l|#x?1E{-&`fKuU1*~5>J5wY_W1v=WAmGmP5ugLBTExxbA6t># zB2xtU1$;_lik&_7Xy7rW0=XQ_0$DQ1w`sR_Ch!h>>QMtIWf|EL(PxF1YC9SEEuj1% z!&TZ1p)(jy2hZ>#zeW9|X!R$sU8p_!3-H@I9e`6M5{*8{%Y&XlK||xfzNedGJw>Kf z52rZcOmrU>P%u)#vEv3{0 zlW!Jmv{SKWkw?erR*`aYX6VS#w4~vGfH!fn5C7jT3i%7*%tT>aU2S3vb%+e%Lh51# zBW1pQ%Lk#^|HO;*_W8&>B3S=FAEDwN-H8z;NDOzNnm2|6(&bL`b=Wf80LwO_M>NU|*MhIMKEdjqo8Bqy}32+rg zE~0`NyrS!|tZDFdk#iBKugbRB&YLO1Fm-K%SMv1=Qz#?fko4pdWDw`JCF#vt#Qz1* z5(dZQo<|5$QA&t;=6ANd(P2%jdALcnYam7y=Fp=m04lUY^_AMFe{g%l#=|f3?-ItW z9Cy}8zw7wJd-Y8$K|AJJ{QFU5@f2hIf<;hATc|8A^*uY}@B#aMj769NaU?ts70MPj z#VE@v2@-W5aDPv2K4`CE)j?3?fhfCY7ut7@|H*n z{wYG)$O885R<|(YWJCAFY>rDd2{6JIJnOi8A`o(>mY0T-f$DR|Y*|^ZiLRw?tU3U& zI1m!BT()Ws`eG}>Mw{NTc!64rU=II=2L232lf_&e+#Y_<5^@KVJ!$-YJU@vU zOLbWI?i}D9NDLXDkyL&@>z5FG@40jI0#OS1`^#H$3PKJX)cB&I5$cLFL-%lz4Iq;M z&OFE=rcE(Tskg4UK!K&5*uY{WLCD5fvSz=RQi89yA}+lju@Uu6`h7zRdF?{*T4Iki2`jMw8D^2e@%uQbT zlGfW_BY2%~jGFhrzmC2?oxJ}~Qv45c$<;npt7GeQAiS^|N69{rF|luSl5Fx}m5y)S z?0*A5|H+>F%fXi4E$@Ele~+txLqf7-=xzk>vSl#}x(A=_t$Q>zsh`?hZx8|u-hELr zY{Fnr%i&h!I6+{G-X#BG`cwSTxcxs-Lc7`p!_!dCtdr@g9K*p_wK^t9EMH<7O?Q7U z<~zy#6{oEXkvzJ>w|O`M_8EOm#d%AW`g*A~$?0(D?#^S)S%>sc{k%_!}2eBMmRn+PMAz8+#!bcP;iVw0%1NT=Vmb2tm;Ju zZoOyY@|M6nb?j2)tfqaC3Kax$jB1CuZvBij!j#OtU6dKE8ckPJr|SD0St|cj3pMde z6s+9Wi^ial+sFbttg9>7aDxQOeau#>T&f6PP#5=l*HLJ&rjYDMq4+tHke+fdt-~?D zd{uMuy$Z9Zdp5Oi{p{sBOn%!tmQ`Hcb!u<@!zWfjS@Z?D)9-aC6SLdvQnFGXdTl;t zRg|+l?{TrSZK%iaOc7xrC!fB|biDrTmiOsvZnhNGZTT^ibl4qZ{X7n&__Q)EPa?qP z5ixz}!wqwr>8e9km2y*B$a>kB9CkQy5QzdIlpd4E)^{QrX`jHK?%$^7Ux0se(;!^g zdV0MY>TLaV%vUZw9x0;Pcm|m%KOhE!IS)IvD__r3PhP}d(Qgo(Brbn=ygkJ76h2Z! zwtASd`Ir?Z1cddVT*hg?csDlfabq@77it1Gjd(bf=Dp^)AG7z(^G$KCTN?er$Mn`Ivv|Z*-{pC zFAh6`hm8%}wzZWpJG1+#k)LG6a+BbU$i7Hhab##hs?Dco*``OjzbuyT^~MU4R~+`_ zMo{lQNoBcEdCsX`jAP;lj=6VaasYp3;)Qfs#W-CrQ=g34_hifq5x{PtxCh>=vvodP zC5FBlbr_T;e~d$~@jSC@O4Im-a*g?|Y#XeS&|1hX#dA@L;0MD~4XB`wEF0(t$V6ZZpMj z+IEeyuHj_ncJNT`fD;Imv?X{DdTSYD%bkO!+7{ks9h`96tx+Z`M~(?(K*je)YuS;y zAr<%BtF*ydN^|^54Y*#5hIHYdi4K^Mv242AduJ|rq{__g?(Gy-p`hc_Kd>9$)7XH*i+kX#km4Me3R-_Fk@PSU-hHhrXL zL=|O$NB%mwHhS{bswB8Nsx1X`=OLaZUIw(Rn^!RUxfxH2#IY9`^FKd?BQ4fGfV+dI z8H5}Yvub45WT{og!DWzBBJiRx>!?)zM8IXLa67Ypo8P;zVA~`|^!07GZkx#XjfXRl zE)Ki6@6}%bM09urfy(xE^}LnAfwGi>%~NfsN)>jFr*Y1SpVv`TcY zW>do#Ya^D|P-xJTq4eO+u%K@Wmv{NG$;YNbx3rmteE zLm#FCFmLP_(m-WyCxb>)$BevQrDFB5u#V4VE++2iiqpINkfQGj)jrk!=j)d-DDZPh zoo(ESQoZvnB}88y+j^X%>Bb*u zX#4l0CreOFwq`evIQ!6Juid%B7a4wcS-C;*Ww~fVTD#k|EVdjmeC(nB{A%iOk?uVx7@c8U|GMENlfJS4v7*SYd|y&7D@mjdsz`B3ML^iX_}U?O1PMMwh)`0o*GqKh2ramgP;Yh|=9OR=w5}{A zm~ivDW+ER$#Jo4vOo{gQuO}2wYREwf{@eDVU*}NmjVf$}H^7QP5j;?9T)N{Y3ku!@ zklxbMPWYH+7G7)c_t}GekdGXn&8qHrN#5r&hlU?m_FexkK*_tm0I8MUJW`Z3sFIlG zlg54(f;fo@GM;8BPpu+!Fg>p;Hi>Q`)xue#VpmCTfZZ(&#PY3{#8lj$2W1{ei0t}+ z?U3VJ{L%B6SwO*J+Hn+HDH*T0*W7$gieG9BQsHuJA2h_EloBk;-soNqAnpw|kL60u zJ|GBVqKNq{q+^oHE%`o#<@T5IL+rb+DK61&?96{9A~7lFGR^>;hn>dsnZGkKKs0UH z6pF~{n!GReWXbxIGkach9SP^uslE6Tmu9%UO&3Hj3?Se`8;0paFVQ{tz=Z#$`8~P_ z>aPGr<+~1N8VSD?oJjGgit%Lgf;2vwcnz9+BCfZgQasi}`O4st!o z1KLh-tdT-P#o_4(P5OPiRh%EKOo81&B#6(0Ze*zZE%n((fEwa*#02hviYRU{3~?%S z`^>ps-X~{qiBw(a;zk2B%=}~hRrqpxOT%?8&w=nh|LcF*^Ua}(Y)9SkMf$A)LScziomq(KK%Ew~puAe){)ICUN9d9-rMskkiv+vm;P+{}$hf)I%>EIRGKj6DD z|IsNV-EC=aF$Dz2@ys+a6%eLsII>#?xks5)AA+Hr%&%mIILAFViNts@TUH)9YC|%` zeNlr*Tfc7|b&v0y?o7()v{MY~uLEGiC_Sz%<<)W%!cNyUocpmh61+uom$n`zih0XH zp}jM+zyH=X1^W3fnLG=zLql7xCNgZU!d%vc$}9d1N)q!DYXY89L%~5DB_gr*Z{rW2 zr%4bXN=Vm4h+g@v_IoDF&)=L%wPt3n?G2lZz`OgnP34!t8&rlWaIbOzuLbMQI(>}T zWy-knvmGZk4Qg^L_|`CdOPN-7AV)`myJHi&r53dp0eUSnV_YekG{-AztJgL0lm{DK zoVCEO-(C9Y{rL|5;`lB_*8&@*R4so&Hg4I$<=|He;Q`jQ2j24hNpoWD*u_POn>~;Z z9x5RtZQ8=fw^GfxwhGH6T`2TmVmm4S!*)M9WMaVWKwfdVx^B7?PIhN;wxTsF?>Y< z-hUozdkNO|lE7~jS2UIv^i67rm zP8)qkFE8#xsxMX7kBm3mo8x}fS|r#|B$l~RP*CXom-lkam25a1 z-68lhHe%0Bq5J_!jF*xypPQON)4t?=ypn~W)to_zb;8XVJ6)|SZs;Y-T6xnlo!gJV+Az){WCN`EDP ztkTXlibu4B3iogweB~VD1=w7~Y2&AU?YrZ-B66fe$`%k(MEjcl7vQiH+eFkos0IFy zeaTyCIED+@`MNndRO6gU0_pqnVGJ08ccn4nnwm_rm0xh2dB zyW0GPwS8KE*4oNeRqn8Z#6Iz&jI-{*{In!&<5*d@xtUVp2LEtTrzV{*YWhhTfEC~i z0BFa4B(JWs%EAtD?-qUPvPNPXwQZJKldf-^L8Bq7i7!A3LC)ra^J{Zt;A{)1$InU3 z*;=vcRWtRyl&@xzdrrT0k0IdW8rmNjSEJiePm}{fu%IX(CaaKi)9_do5(dpR{n(Ow zS-bKcgaP%YmTA?7YBt*Sr6^AGd*d&g&oOkOD7Q9B8j2h9P|J9&-nOz%u=|>Kkq|}0 z7kc)=t_^&+@6wjr_**w*&jC7syd(~Z`}I+EBftmGe=%5pRSnvUw(Rq(>04mJTB)y;z6Jbi9KSy3VHb1y+JWPB(66#5`u`q>Ph7HHahtdvR zm4vEzP0Aiq7Y@)#k<*Fh2{@FDFKHtCPKO+bc4I95cYE#Cv zBp;o8XphDhEzKLm0<8TDaK2R^njOwfLvk9rT?#&9^oIQaYa64w@l4Q#lZqN`2?yEg zmB93`QcqA0PhEi0*p03v?zL}x*JGInpOxRsITESxXF@;4@T#J16=)719i+Yg6Ivt zW-*w(`>5baeQKlVCb=D4dFY;bq~O&L6B#e26R#4JNh>e*L$9f5dA74 zLAJlW(ktQ3tB57TghJufCYsLYgy~^gBO0Rx-=D8Pq@bMYKrrULKQ}5Kt`qh~5x~a+ z^^Y5P+%VJo6}eg|FDAEt`ie6{>~q#6qgsV2;9xG~!u`m6G*45QhwBZj#5}SxYVBv) zV@A6_dTj=0t1VP-lahZhDBB6c{WYdm6u z%i|vyB__E%U@qshig?TjB~QLwheLNU#UJrHa!$G(OH^(?JCJ1je6B=v0-v;#)5D_Z zW9n3FIZDn950Ddk7B>)>IlM8B2V+mGh)PD{?N7sxQ7vtrc0ZW2h~SwHZW; z2vOZwEBaVjaPe-P{OkK9gEgxr!rWdqJSHmJ1RxG{)c&fbqp?2o*%-8`E@w#YUI zW5R~*`uSqE$@qKNy9CisLoTA4+ zWHubIPL3z4E>?(5pt4??J0jJ<>o2o)s%zr6xAHUwdU;$!Yp!X_@Hw3rRAp{w$!@$c zJ^&*zvFX1_ypd6N)nx31WKdj_{S!MKR8@GKFs~}XWhU%|{&`Pln>nGgUJTzmK~N?q znL5*0iXjNe=~d_QSG4uMV17yU??HLE#Tr3PakNkRERM?qdw#VPQL~VYby90+o!?)| zm7EMC8($()oDO!7fXCmvJAE(q;$$Kv(?Jmg``JE8dbtDBajD6Xm~Pzq^4|NXn4I08 z@}|g8pg7q>q7B?U!L8$;KvA{TBOh{0-eixr{l>D86Z8@c!cVij)>8DaCq9*?Sp*?` zGFoxlCLgT1RsnugJK6p&RFo+#yqoaAD!=yTc-LGGV{Azn=x5BfJxQKUVb;Y=d5L%P zYnVCIcz&#G^~8j+gcowAxVfk!mehNcwN)_V6$Nxk)fgq(WBD zc#(ZcaC0u)w*ujn_!7nc^bfZtb+UQ(ky7L<6TaA85JcsV;k$@fT-KSr`9w%x+ER!#GoDtvx(n>RyE-m5%AqWMV4uqO82RzWBS0Q7?P1;&KpB5 z8qL9V$}yVrvO6Lj7Z%mmj+gV;G+($j1?WEy{J7iycS_rh2SrzS$DzlE?WUV{8^^#M`Ts*Jlu!&h#|s^BBd>-8)HxwK2P6`fO!3w;ZkoV z(w=;Oo9;HMuC6nCL^oxf8Vlm2SXr}U*u(D&(&P^!NE{+&L=Cu3;f8C(r6LU}lZa40 z_&>RpmRcS4oB4I3LpW)Eb+BcYsg&I4ww@&R1{R(gaz+&>Q3YDd_3YRSqmjGNhoQRt zW3IWyL!8NmSfcq!H5KDqsqi`AzSXzPy(iIO$*=EmM4mLO5Xfc`YyYW05GZW7HyiJ0^&$y$%FA--l6r(GGFA6+mD$DkfT|#*ijrHVOi*os=>% zZHtat`%BG}y!?D)N3-^a(&&-hdM{YZnU3B#NR6=w-aTZ=fU@1kkaBoh<^dIpXBg&- zJ5GBpS-}5KH1Su{{qLA_+wF^27PJy4k4Wzxy^SoG5lm%1`E(0j2gd@41-G{rd1O(6 zSVTT|6B`xRAdi87Llwn;ujPC-y0e%=tF5`DP^4s9Ral zOA?Z=6L}UoSsb8VtVR#E=SB3UG24k|Yq{TkQO%`FcIyn4gTy zIw$#xnz>soeLrt}hvjujZ2i!u4t(EmmN@n2poPTpaT52Ux!+LfHv??#L%lF3x3S*a zh(+d1TmIyHVv8)CG36>VAs%|&t|1B?=P1OB@hpOn(kEY>ehnarEf@yO|D2nkxiVYl zr)>z7MXTD<*8&GEtW}5LCJBP7h;*Omd)B0CVxSUi(Z|O<52+DAIgdHDC6rf@VStr1 z!2__u3s3ut5|_X@{mcHrcKjAbS)`Aeu}>smNcZ>&yEo|HWb)hcr`X0%75iW>g$w6| za|^|0V8x)PGovaveXk!i-;7DOnZwYAIkKG(ZCuJ+2yiiDH5E#m!6wYX|8ktM>r)^c4UY`BnSIp98WCK6M2Sj0-OVyww^U5bf@fVe5joc z#{v%B4-YNAu{i-~>*0I_BS)F2H8vsKw}(cGZ=7rnwL(v!)nQP zDdHr$LjD5ysjuorZu+6b1k?{{n1$NB51VZCZc{cvH%=Qf<&U_~)%^N>?PM!Nj5B>N2E5Q+-5=x64rx(68S(#a{}R^v&-Et}B{ zp&y(`M$b47EmiZW15=LaLY}mKa*;2FJgrk*_gl`{`to7QmHO9pVOjsD;Wn8d#Tly5 z8mVq7%56hM8jnfL`5Y;_Tb*~s8nWN&-^o#P<~P80@)mz$VK@-Fa#feERr^-sKs3oj zqUp-_5!W+_dme=S7SZnPEO55hH9BlW)dViG1T_DyXj~DtCPBewaE~Pvd;&hzUsND2 zKnk-(hB=6*j=0HT#4O%((Q+BvsmNm_HYo@LDd5ynAS$wm*`J=yf{_s($r4*UQsG-* zI?}0mhjaJ3_)`HsU=%Eh)>Xfo{B(*sZII3t7**tGN3X)FNDfAUJso!si30EOo!2j@yJ>!5Hp9zmqTea9 zBj)-9?0Ozj#fx6pnL-geQzJ4tejh$?XzP%=`lf98ol?u5tHv{d7DH`Q{xJD{^SQ4y z|JNSH)N#7hc9EKZEC$lKBp6|;%6T|kg&|YF5FC^I<6B+WjxZ3q#6F`X_yfZdkm>wX zP{c1=S+nVVk;@3hLi)zEZZo0LAPAM!+N>8l`JIZK52LXk){;V@ndrPp>x0Lq##jOM z=uom}OyTE3g!}tceRmrq_Uvj{yEw%&8`Ly$YqgAoC9AJb%lqZ?yg*|3c9W>?BW~e; z0o3M@pzIthEjW%;p$R*p%fAZVzc)0c+7m&m8-|87$_Y&SDkD@5+^zN~vj@ujCVVNYe zfCsr{!0*2BPc15zfiO7WJpe1N_uMWPV~L3MfxJDU4lH+6^4hC26|Yl?R{za8($_-l~$A z-+Py+@EYo&5RTLX^}+S1LfE@kvv%+y>!dapDdz7N?5j>?vsy z;`6PM^#Cicn44ecFi2AbKGgkVa9gRUESM(mh=h+#?}1XRt9jP!tt^n9kdrkIt=U{Q zQ|1Q9a9!?3Rh($6kjz-V-d**gzi2X97;>eL58_Nf*efb-tXv&!(M%@CH~HyL*j4c5 zOgX_G4g~qAzGs{d^o1m_$wZ)5uZc>X*g^!J)=EqSWD1|u%0t|BUmlI#XNvF@n)u6T zTs~&t`bxl}3}smTu1jXMFUwUcX|qnL239nIf=w%8(4gRBfOhMEUw!LAsHRGxc9CK4 z?%B+tefC@gx$kFwPX=B~8@@J-O(ye)ZXR5yw9hrI;cIo8SJ%)-*mzgwOPq@DjcoF# z@)C_ZMV}UHatVOX7;y_XUOpv6h0{FQ3xeS^PXHb0jqK$(WPE<$M*CScgS3@&rvz=TkADguhlE;2pvnSVaCW+5U7Iwi6q(0>MLEq-U z^YwW}TSGft-kd-xC#5{#5Rl)$W|CDsI5+jcX1TC@${QP0x=8MZlu7un=sB>CvkK4M7 zq%5TB49K*iUe*W=3EbWxDLgOJ#UHm5>W@A6;t8Qlc|r+d7RMHs_{Tc5UfADSng9pN zpg|X$Br9Q*M_+m9r*_t#z#D|UVlhJt8e;0k<>TfNi@b+ds9Ees&u+5|tCC+HA@<3k z_RbBMs@oV$A%1WxBfN(3sI+Zc?><8y;)@z1QaoXMvGb@J-@*WKJ2AUwFTr>+r759q za?X~=TU(xjy}Tbd1xl|22W!fI5`6`{#L-csN@cRlYmw43tviB7jL z2-T|D8EBF-{;Uh|^~D^FQ7pI!pByInw*_#TXW4~HM`|(5L+?}7RKt0KdF_zicsbd_ zo>9>I8HLKtKdZi&Fa#COFKK6;S`n zEl^v)F=9QB^$w}eTadykiEOrdGNCVJiQ4$z$OH2q&c&2hDREmC8kfMb1z|#?(f!Mi z3tA5;XL2~-C=01>Ir;Pz6?%*VI{j$I!gX{>%0+vAclQ#d9E~(nqT9#-@l?>>9X`-R ze(5;R&#oij=nAYhlOVDSvx>+ zhXgx|?Ot0h(b!10o1mS{5GFlYm1J7c9<5d@ZxNPVfvj*8k*f17hsyJ2BqL>|w*ifs z*zEH8((&AMj~ZKF_+q=rYQF~4@@hIv>wPTY>RYi}5g6e()=>KB^C(E+MxezG;^1^b zyy6c8eunNOE5@uT=BW^}QLCrHYo(~GKuV*MRYKuv89#^O)W%}{cAqp12)2+1k z8PLhZEOtElpX8vk`lMYOGc9jVZWq(ogK)X{--O}*cxhWmuI##GUSU~T=Fr}m8N zZFmGca{J=z7&u&U75$*m6+6^+oOw<7=oYZMaBe5HK5-xo! zH)H&=`vIUfUX!MLPh1_O@8iH~yP%%Pd+35T%gS>$imuk;YG*tgxcA1O@jRq_yr z4a^&8zDY8(3`&h#4Xxj}OYF47abb`7kbWmbX!$J5l5&#Cw08$h^`WQhYl3{tvM! zi`*FmIDR_MoH*4T&WhAJ=IeRLcG+I0fk<|ijz`hIhpn{zP!C|#<$6@tOeA+7oLEq# zp!kL7%RXLW*H`1fNfrt49A>w8Sx>3*Z0%xOr=!@(nQ{nI$+=-HK&w zwkEdq$OCA~5h6ozW~RYsSw2XrZimazjn>C>eD@cJUQX5g%*OZr{unEPq!>DXfDlg~ zS@Nn0u3IZ7@I|2dyDQWKXo29>nQ&SnSs5=@QTXwfyQam8f}~e=TsnEnj+zA|n?eXorNFPu1IHNJqMP!?vK1V- zZYPlBt`KZW>Y^bm`x>@E@ zH&rOV$0)@#GyhYlG_3-v#|&Yot6?%8Me=;v5-_U!l%P+=|J38XXNi2%jY9wLQ?s@4 z_XRfK@*6Qv*tyn&d1r34l`fEzbI9>p9%YP*tG?kt0kLqufAwW@?;JOUJ#|v@Shq7l z;#WX&5J$!MY|q$b=g!+NB9cl&tst$eMpp@@Iz=YkclC+0DRjBYKefdana?js1mmju_CNiO=hAzoN7`y zAFHn#-q)yKiH1P0oO8m4vRQsVpGM~Oov0N_e#PYw8RlIsWRF2!D#{2KRn}MvJQTx2 z@yrlxDN--Q@mosTbA`7=DXBN`x24o!$;-S!l6X@taGvq^lh-Uu^B zy3Qm$_U8NshJt!(@+0Ap_SuWPIIry{o4F9Z!ta%>mPZ;jf>9ZaScG>+WGo(=N2NRr z1RNj3nV+?8locomKMQlN+7IloiK}JdT{e0@gM{Rsw82pJmVYiyt3SeKLiVi&QcZg? zcD-uuV1%3iJjXzzJdO&>V4`!FFz|l=Q8(pdjFd4Kh2;%<-W~S zC3LtHW(b@JuS%1igvkvJby49AK^l2{Et5VnTbsE-!GG+3{ut>U4MWd~`07Q#N$e0f zppiSORYVx&c`M5rQf%W@MaJEB#4`Zs^X&y)tYZ_hd0_|VNuuv ztBA)EKE*}Am_o$f;1U=KZT>H`MRmQiC)+$aRuJgrIi?DukFkdm7C{yq6`oj6f7<(B z`tXw}W#=k&^3s&cA!zPQ&1RIQkhf298=A^#99ri?s6l&#k2T$6R4cW^XakuyHd*Wg zw?`(4mrn`ZlRqyrM{Bsr8Ay(i35UNP_JS$W>aw%%={+h)o$XERh;xAgACUeJd4kA5 z&aW)%5^f{C&0fdc^x1g`*JdeC_G=5e^alFl))2oZm6@^ip4K=&A0RDVs&yjC39m@N zpzF2uQ6OA(8*N#Nf=K<0Ld!SiF{bdK0Ywy-TE$=)S}s!NJlv<1xyx*+ALoZBR;7uD z=%Sj|ZQt|<3dgljW%y~*nmlssrn|OdX7}VozmYTD@}|Pe^PEY4DKaAKcaABE5o=WS z9JlbEwNe)puQ-q$!z9~BYin-h4~x4h2Ut3@Ua2!Ey;$I>9F3E(<$M1t*m_5?yn2p$PK}+JZ9NGH^g7@S9_cwbF*WZ&HdP%we zKl=6mUX`n{e-N~6dh4q#L?eQnB9QEf(fq7mvHo)DDYC)jtPB;W3>Yt^uG_wg(>oO}Kj}eFk zgbqF+pY^ItZ2WI?3}TTA}D1_o7AY zbyRtQkLGRI0?D+r4*I=Da;WOE3iptrnRZ#^mx1c&eF*~ohh>w}722N`;vZv3sh|Y# z<6C~E5OWp2;#*;?xZTqja%YuvZMaqeD-n&WV=w`d1QG|loP)cJdK%XvHhR-NZ*&Sp zs1oG3wd0Jj^6jKje3sZ1`hIVX@O+gh1Fv{`;U~23bKahLo_)4t(&#Pg7+cu#g{d`Y z(>Ws3h4L^X58EY$SCU!k)C$JV?|t`_cbc1H2agaa{$td6INjYwX58oG<)m$gTToiE z+b_pRfYJ&GkN3EMJW_-q){d#-QrXrUQWm6$?s+nZ)An>(4PrbS!b_-CDI<&SB~z%N zJ5l*lwl%CP3KVI8j3m=Os2o$U1XegHV`~Bi0Jq6wqjh4LR#0phDO9))HiZ?x5 zHwHVA-OirA6D2THsNXG2S5UK--v%|y+EGuUeQ=V^ z&4+oICh*nOMr+*Nv0MlQLhE2Cq+WA3-e0pHpfS3XZ+|m>S!6)$?!RvLvTJClR4H!H zNLKeHXr;fTrUq3fHUETId4pB4Ti66kXHj5L3W?R7Ri#M07%?qFq~Q@c4fd@m3ddx9 z$c)b?g*PQ}cH{c1>9!}-!&8CQ2ES@7h?`nFpBzrVm2)UX^+$#DQ9VZT( z7img<^&&(ZC#>M!`xGoox3@_2?ce&@&u_x%k1{=eX7iR*SrO`g26w+26e8qN3;*__ z^K&Z%G34!G*I^5yK0saf`TD~LGm_U{?IbVWnZ^#Xlk-J7u9aN)dCNkg0s3)vLvHsP z$sZzf6XRr8Q9^thD%r1Un@@}DTxmLn8wWQ|0HLohl4>4}PW5;o+4Q^M);;hhYdv*G zpFB9VUiGc7OO$!st8-ct3leRhcQ(8e&EW-7^BdEzz;S<73RT*;I+3h;k z1X{K#XX+P)^6dk0hI`)XKOqPC?Nh{|i@NhY2bKTr+A;^KJzfs}y8B7; z*QN*u+dpx7p*j1%PlR}BU+hBqWSE~G2P%d3X{~0-_ynVn1tl2$tKmW9J&ql#U>|ed zYl;9H3{1*9IMDbJs^!^mC)Lr!ePJid3fQts23&%|+yG2t=ji0XB zS=wbZG(NnE2?1iQC)wuJYx!MdgSR-eqK0Ze3cSa7e7+a##kAEv`r)qhQR(?K-4kt) zYN-*=nE-CRA6MaFjrt3~@ zqUP*Lpz<77k9b+sw(_St_Q}AS;1X*reg(!;)VP9WH!1W{njX`HqVS#2RuD=h*djQI zQ@{qpC2k$sJrlI2CYZ-JoB0MQ@XC)$Fjc+Zn37Ts3|e;!L#r$^Fmc>I@`b-#6|%B= z2$pRC^-Q0>L$S_x;>`SUMA+iYLq!ZnB4AV$wb(~nSzx5n95GS-O<>z_?e1g;r!=?yGD&5b@X>9V!5HwJyAg% z`fWyqOU^=l5PIs^pAIM$O(UT;cxw)`F{9G)(nyj3c&!PpYd#^sOl$|>Aq(}}*J{i& z`+pU>(cvZ$atQ1?!&YZV8PG3}he~zfbbeJJ($z%5+LjJs(?%Ysx(?7HB!hFa;ll_x zHyc1~HRU_|}4!q6M*rGyMuo3@j*{tj)&5oHar}-4jv~tco9$4N@@jND3I%d>lqT?X= z{JX&aZYO^M{vG8-r}6Hq9a|+|_5JxWE=M-YRFo~uv~10`J%yGZQC%G8y|}E3az1-k zIsw08B6EeSL-ciuCm#)M`}Wkx5>huCdh8uCtcVPV^`TbW`~_Hm*=N6m--_aTzX@*j^$;Iy1UZkWFh4?Ap|qF*)%GsSX?VO4nN4~bjYR6#(w&TyVq?1KnF zBh=AlDkb|O@^$0f1&&U|3aKec;2`->m+f4NL$@T~+x(I^tioTE+Bl%ScYuA(|(7EnrfvlMH)}; z>!P!5@%&{5ir@vg?(5*o>`J>$^^;X?Mi{F4MHKrErJNeguZ(JeDNdB*^->U=uzQK~ z2_9WiBTe^gf1Gggx$r-XGIT9wMmJM2NK82?b_cQbgknrId<*Ue@8W^rTEMji>_*>V zxzdp2jQjux@m|tzNirXNee(LZdT=?hW?Zi&PlP!)S`wZ6U0w$Zyq!H^%BmOd1qAtX z>!c{l#;vS<%UNS}y%G?Z85--i@UYD=IU_~Uw(c*_Q{WGN*r<}Dlmu#g`7k$^J9aGh z64|7H6a%xrSWE{%G_M8(;uaVmn zS^+1UDo2oN#7ewEI$UR#{bWr*J5y3ed8n5JbiZ_y3)%AVZLJpt<4PmR7jFGeatIc& zkQw~F3D;k@=a)-@LROFKwnD_@`tLDMxL zrfx+k78RLzEV;jO4I3JH@l~;XpFa0yqhforY&;Wf7%~z8igoE_m-c2K^c;HIQGUBgLu&~y%QooMvtc|asj(a z_v?{RgrKgA)dXiloivs-Xw0phF*PhgWC6F^0Jnnta0*$vwpSKfrl=^0lxHfvf4Oee zXk@oy#osWI0N}de&Kx~1@jFaA^ux&&Tu8|&T>A$;5iJPNd%zV0dUjV%Z6pjKzEdKd z#mR)zI1|hWvE5AeNRxPPdrtMszLEax8S(fN@N3m#Iq%oDz~)~<*&4tt*G~LqQkKz` zV#_QSZ1srL6&toBTa#?=(&H)yrH)o}mWuEwmO)mE*v~i~WY^T;8TD%B6)2>F?9cQn z^A2Kar@JEm@~O#J+QYRqrLf6$Gn6mlYBv42dHDjFL^KhU5On>)NFgn2)09V$a&aXN zd5=D-cJoGLbo#yX;0=~8VW6{7n9I&?>K8$lIQn=v)g>vm@dwLTC=jO~P0)j0-<@)U z#HZw$Y#(9On9C<8O)4j`2UED8fCsV@!=baTGllB?2etU`hfDVvMDOCVBI6<^k1h{o z6L*_VeYSTEV`o(3(g)Gr4L%Gxk90qzDP>YvkZn3DUzFFWRBS1KJ3V(fIoa((V<6xa zTDsCX5JGY}H85{pz3KoGQ~O+GseKpNT9PdAR&Z3?*@EYYtdl$k;_Kc4WngL&1X%)$ zePcGij}cKme(r^|ZAC>rcWHi-)yN5w=BQZz3wS-tZHvs15|b0sy{``_%x@DZpX(ZZ zhO_GBKNXD@F62Ia`eVxeB+`sK>wSpqr_U!4Qm>1=3&`8R{E`CNA! zzFj|*1H1Y}sFx>=0OTEhdOqZKnXOSBpVpW&ZpMa6$^ChpH-PqoE!nkl!V3Rb*v`zn zmD_bD`$)B1-gJ7e@gz_4ufSx?I3& zpt$d$ymMOb?#>9f1=q$XD{w%-^TL)u2jBkbxNHRiZ*l7|;{?i0(bLx~C-TWH`g zYVA6ND0e(WR?$ry7YIss{%%OJQG0sO(cT`d!%WHvPY3FoU3!-rHEFlk%D@`8GlIgo zif5>A_PUi)qQX1vEXW@vMJZg>Y=}<&bv^>M}iE*D^s+fd zoZKBNXVe$*$z&UO9Q&UINKwpNkehzUAEyVMt>3rJ_SyI#m-sP_N04f7^5aJfKnLy$ z)>|FN^BSVP78u<=yCul=3Mdze2PcNtP?y&aBPLe4&uzu9cg6m5roR&mA=R}2Zu7AE zGr$L0EMSdWMEb;v=wJK9_ieGFpM1U1yuqSDsq(K}8+1rxJb;kX-m0BP^PyV}P;7Ht zPUlZ|ds(hU-gT?XG!B`*CVvr=ti45cm11OU=)!nLkYReb_bBCZ;A9_IOz2$2f?XUW zf!;`4#u?*QrTt=z`{8;M?M`jO-!`)BaMN4(6N)Sub+augJ~oBfwTGs%d6EDDjG+{Q zDufF8&wfyHlwA(XXJC2!Sz*fzng8XS6i~vo;txmNdRjr2Z-$gM4sZy8sa0L6zqBik zd!I$jvugX~j0kolt(4upMo9W=G#AUWA{+XkH-6$4oKM5(Pa6RGf5s#}zkT%$Hs(kj zAoWK73D{xJRDaR>O{U_!79;W#blbvGdFweA1M!EaXi$8|;sECQZt_wB#Mcj~Q9WQZ ze}9Uk!Z_J&)lY}g=n38-Oe2xNGT=D=r@N0jo-gYK4~cp>p5nr3>@>@t*pc7pxbi6? zK2RpieE#V05o`L%pbeOZr|;CKOi3np;keIZd57D`Y&0R+kbJCCM3$FO|uD= zL-b^_y_N)+uLoK8#1o)4akStQN7ae)`lQ5NtXyd`c8LV^SK*Ss+6lY+XZ_;9-$uPG zcRe2=N7m6`#TBc%k2cts)nLsKiIDoE}l)sw!*+t#R}L}AzZ z9zttDnX2%@*){K;f}H+^^jxL*n)929+!hH&{mBhUJ3`b`pU%`fXozkeKr`teh^k^> zL|r%~jx%Z0ZpQ_ZtA>-&#qiICa4XRKb*qR!OK`U2(%GQzm)QgGqFehXpmK@Br}Jio zD0|QXu_HT)M*ub@9^BEe&OU8Vd2P&@V+RtF()%*(LN@^SyrMLc6y%3q-<)b*pXU}r zCEyc@0#JoMkxl|n8WFW{hOJyuWcHA;Y}^f_jx?}!6MG6F>sn?N@OmY)jx?sYtKvxA5c0%&U|rZVtBMl{>Zu&9)(Uf+gWMhO95&?Q=R7PShEV zxO0@d6>&;MdF117yP6x~|I4sk(2D)?uJ=ax=dI7>+>|^hF4D-f~4LB z@9~(P3*nC{jLj^hK0Pz0bemwOFo4HSz~7tsEXT(K*&c|WkZMuJkVEBbmc@Z$#1@;h zgwL}4*XXa_SO8V*8xAI5=KY6IzmtsCni>$JlF$R!5rzH)u*y(u%k(9vJ3$BApkzBX+`vF+*j^?#@Huxd%_n@t zzbpV!Gx|#KeLXU`;ZPrUyRax&DSqq;p%x?7@M;ghI}jlC@fy_U+ByK z|9@co&#FpepL|&uuMNEJz$f(kRJoPj_Y`)(s^u8z)`5*I+&?AzPrQA`Wv^RXXajS) zkCR}%#geFhn;DZ}+EfG~Tfb?NQAen&Wnr?|)jDTk;vbILh@k&Sr`XhhI(0?FIz?_> zHfI_`E7N^iaun03+)pxaA^I-mf@86JPRGeIV1H%jxl})5dWN#nQ*e`@g9Pd;9aqN@WNqrrA#}K<2fuWT z7X&ODTz&ZM{^&Nsbj0{a(PD8zCjgTO`!O529wra@s9CY~xnFDZ(b#u!3Zmi!ump;g z;LhNaYWp=V6Hrcj(3YqU;jb^~Xb9Pu<`A!fBJ;5Bhpz(2^!(bycy@9}PmLw)SihaH zQD5ZMY8bl7%!{mtCP*n*u^TItcnY?|fc#v)cJWQr_!{eAR;Fpa?69;+=$SJrP4eY_ zfl6Pn(IxdyfUX~*hmsT82o-=OM0aL1^5)${L=+A&CtY*jU;bD`@RKNHTxV2d6AdFG zLEUY69hxA^Yltfm`I?2i4j7N_`byob{o)v*Fg$ll8LjQ{HcxLi5pwR1O8nlpKEysM z^tw`lco!$)j{xdkVtYPjpY<~V0@=M&YY{>;dVSuW)l5w9#9)%4XA(D~EsgCD?~G;) zdv`Mfgf}3~*+VipYTz%+=CODXyFs3X>hoIVJj(H#r^c(pjoPxG0EBiTAnEfC z$?=Qa<$N0`8f?{fQWgdlMnQD&LiDTc-)7l_V`5qN4QbCSG~#J*Rcre2;_+#2kC2p+ zL3Y;^QV1erLA4r+N?-Ad@xdYu1fcUSMg$_W*dz2@zjcyq|4T{I8_X+$dKzXh{=;jX zD6$*%#p<_-@127t&~RFw10;oAM^je}S`4F30Q}X&zE{KVfo*I8O!Fk4&V4*naD|ymsoO~S(7fn&eQ3;f}Z#J`o2gdYm z&V%C)_T<+OdJ^tXZzXo~r|PEX@?x0Z+Z&1lzw2Dv`ljC}&j-k{kZi|E!IEO8l_)T% z$jtYbq?r1`kvDOG+P#dVa=eN$oQBx{-bC}E8+iFus@YBlLJB29oqiu$=Y>&} zI)Wxx^l%D{u_2NFa{&$~F?M=g2-PJ9#%2Bac8T@ zyaMuQb+?Gl8WAO;u+8n-{jPBohN4p(_dsQ8&|Y3HK(6J)_M!QD|0BIcC-Rz1wt*SX zU!OIK3|ZQDZD9lTA5kU@521$_8)dlwaaF8Dj7sQ-9WNfF5H4EsGKEL%an`o!?DRS0 z2;f^kjgW#5#V(n0kP|~v&7|kqg$N?n~CvQglVQCL&XVrcq0 z!6sMAEQW^hlgmZ?KR4sZzl&m@m!ZBp>j~HEtc$%c7Fi+5X`nsU&y7}Q_9m5%-vZvGcGJqPl~jw- zM7O3EhVPe)t#}6oQulP)e$?%=I+=^j+Qe}`p}u#ZzN+V^`_j_2%?6G75BhS{MTy3 z;hM>q*~e6+`y?}-E_-$)2Wi7F!Z6*tvrA+ zIQh?ocvDV!6Uo0ZN6i!NYr8(XYMrlbw&tDVQL2ND0A?e zzEOYmlh#M85)#~eJb9%|3ldh{i)frq&TuMmXg|YPWgDJ9awHy2x&=K`VY4|C z6F!(%F?;d9DRU?Sos?NY;#DRy2|hvc03nPp`rn3|ze>;HhKrZioy#5mw!_Af z2Qsr^a0&dr1W+8mh;Lcd&Z_R>W#=f6E;2u?8!3)Yv9FliH@j#d?-CCTgVlgHT15byR)=Dwac` zH8o{$bhP!7b)BKI#My5{SrIL;Y0=J`1@nV{y=sY(c!P*$Cg;8jk&GQJ3%3I-|D9nZ z^6WcLsEkMlTq<&$VY70v7o=Vem^n<#$7toSoZJ_#low$0d*SFwt&3gMfCT)7zxzyU zX}A(E(3BgQ=pTADMqZ!`d$*xHSz_$%>I`2sGE(U1TBVg+LA3(WxPu&D+_L1qPAAng ziw&ZDUOtl-o&cCQt=-=gjE8L2$z?5!@eP4VEE253f`$>JD!WTb5N-nh;gR$|jWmHN z{tV61gDMgmmfJHShTR1YxYuE*d4D+1?w-V!Gz-nwK(A;W1*+u2e7M{i zv`*s*n!nA(YzbPEF4fV0>0&dJ?bhfL30okkA}!{KG|UqpE_XPRC2bOb7Gel*VSP?b=h zi_snwIA!l&BPYMee%bm&oyHO;Mp_dquvvo>V~r2k4D2TTR{odq?rpkS;Qp#RKdB%ufdZ_%#{ui-g z$gH`M47`hCaCo;{YHtz8G@I_pA*FMUx)HQzh9$YM$h1#FZ z%uwLv5Q0kl_^EiM?+~idW025Qq*Zo`yI}=7LR5)(VvOash-lf`hfSK{o5n!EO2@Hx zo)$`Wu8{Xc#!TL;K66xm4T-8xei=od0jBN#jBgT>iP8>A!8YPB-0MyIbwnv8X=xy- z3~scL9fcFaO6N)GPr%#1y2UIMTOTyPcuLuRPQ+88!atYq*-bo#APc*KOT<4i?Il0G zE%k3(TT*x7Fn}D~KrNMgd0%K}@>J`nzE{)%TVo>mfMsSduXzAHS}AtylI_ zoHjLD60}?o)EQd)9D?%e0;>Egoc8Od{XouFrFz4)BmjbeeL14U)R`~KbDdlJX&9I} z&;W5PHZ6RreZFpA){i9rSG*_>JgFx~C%o+-TG5bqujaUvIwlk2H8<%P_|?8fAP+;q zk$fv;ND2H=EA6}Mnv3T2E8Co*=Z&wPtM|d>Fp;n0tX+7C2Uz+0_DWNP^<3Bj&`(}1 zFF+w%(x|U5Iw?PNG-LZV&;mTAtJ$ntBA*&K67N#K-ouc=@5^KNL@r?`&pwwXiC@zJ zUV#UrXjaJD^IdLAB5lK8X9SuRT_*U ziq^4L*xxpxbdZ^>56{sXNgG6S#t#an2LH9$yc0Erh%UeV4zB$bl(jVhpD^CTaauJQ zYANd06f&&trMx75xrjmXz9cFMpe1Is7C9o!uDZW>f-R|r`c_$E??SRt#J#;JnC7K- zu+RyJT{j^WD>7?kMKq2hBQlgYayx=BVCbyhP000pu1-0`-8ruME4VrS0|LT}oQhQJ z0Y!oFMo9V+P00L`&m32%0ZF9H8Y)k4+$)*oBlqwWWOGY?0^Xc7ZtK%DORtMMby+#bt2@6eP$b%_g~S|7m%q>o;8GGNF*kA@ z6&)uC9PUPp$?E6`Su*49xVTzF3?~zK@^p2H*^y$9MLG#r4uy89bpLJB1cpa3cG(|i zQm{1TjaZ4AA}5(kK7(J1r;?0F)OIq4kj(44jM@C?y!rt07--87XjoQGQ-9ou+-3&? zEp%gxIJE;|F%k!sb`pdt3>+o&4oRuddT-&GZI&LYMPE#xG1jK08Tjxau*gJ9f66<10Tb6Mre0vo+OH3>#hU1 z>$b~o9k9ixFanEyC|>w=3I0xu!G8%M7KGP(!!Hh8NE7)nLHpNePO;g4F~ptWeke!7 zEXhmd;#q3U4X`>Wl`S!ibi46w6k`-;FneNMcwgE?Z^Miwj)Zb7LRpu4nS5&=tIa|+ z#58#+{`JwG>N5$v!77q*WbXS@o2MTi(dfMtfGWxFRbZyRZJdAVyEsV%se1S&LuYNV z9olCSaw+lc9MZ;1rxYgd&c#+*=;cFT;;~THN>WVJP1HNAlg<|()X4j01~qW0Ao0(yQ#7n-@5IVwSk5aZ7bS_gV%n7y4vpoM29W zEk5^0+!6IXDLo6p@SY`Vm5m@7%ow`k@jUgh+jOU$`xK?l2Nz~xgCKM4_eo|l=?02` zn*1Yy=OjE#j-sjgoe&5hqnuJ+Pl=rsSp}dnzSL-+p zNZac=b2KS6tHSGxt+I5_^q8deU}s{UzdlaqO?cU;_(O?!B31Uj?>gh$+ywXW-PD;) zb8_c9v%J~Oz!mJrn|v3~yvzjB=QjYUT+gqCGye;H>!2UVcwd921lyFmRjJn(zwZ{Q zoMBMn;pi7T2)VMOmUri29&gPPa*WI1`b7-M3>J(CHWA9?EFk!9y|_Y9cD;~Y%B(m; z=dy8`Fp^8^8o0cLR{* zoE*M3GR!2cw^EDA{~iL`*NKm#DJKyu!{Z?TYI6T>rLi*p4~hwj-3%$GwNULQ^RwGc zV0Ss=9d=1WBbtCn!e|+jW7(_}iFkO2m^7AIJ8d@F`5A7@z5IPt zY?RTnqZI0*0c6P8I={LCTFCC^a>tf2h6?^QOMr%ET9TLcX7eM(ot!JO=n zyE3LFu^gBSn3Ge80&*%&jN8=}eVIS;are8X4V<&8<1F0gjUt|>ZZW{pkBkzCmv95v z93jFr=A&1F#kC|gt9nVOB-m*0^71@Q@})OEk2yI#F@)G`7w1YByyN5hzEaAUwU_SX zG0+eO-yWAFw<2KtGMhGH1q})fbJeQmq#ym3G~m(6S(A!}RuSTI{k%|_x6NJ-a2X*hG$fL=^yu9KlC#gySNYvP;*?kYIAD|Q>uM>Z%fXrsF~QQpf2KK5Ux(weh8@|D>5`HRlw? zE$8UhxBEXfA`N|>X5J?Pwd}DuMDp5&0nk}-PHD^A{I|kVrWr10Yw?m}YE^xFZXAasTZLm!7@y*Yn49 zcvgV7+Kt)J`&2>GNqBps$`f|pwE<(thK7dl3WhLM>XrfA>hWW@0vFerja-Le#wug(0 zBRr9-T|DW%g2$R8@sYDG3t@I5!*(*rw(@?Eapu9qEY(AM`DmcfixX!K+=j=P>n3^~ z0P9Sxtt)^k*6zccJ&71$Up_lZpzS@)G{%4nKAQ=j4&R25$4thsz_5@kGSpo!a4kuNM;%M*iR;3%G zHC`pDmW$^O^lepZy3xE(+nqG{v?gQ=aDYhW^2$**xsVb1Usv93011H9Lu^Sjy zVPOvM1Eraklg7yfp|=!=W=ZbWdUsg6f;TXN0(_v>;a?$~U$MeU!(ng|r2zY(Y~a`LxY)tTt(9oK`~U~E+cW_y8_gt}oYYwH zkicQiKY@Awi%(p8B=2ORNk$>_k#mpSo_gY}o9{9fLBT~9mc(n%#Y|6P+Zro$zw2$I zejP3zLJA@QJNP}=(sSlgV0S-0Hml4Rh<*5|6XoKhOk{KDRJqh`8{h>UQ1CSmM(jYGf;H|F4!LvifTf7vCk-8SVWZw=hvAu-dZCdnM1XNv2)COu*{zed>!UTP>px#6i1v&y zRgH9h1K!Y|6z)M7%Gr(Z`}aUF??ZdU=)_C+4SKm3Aj#gU(>kp21&?aU;-%=74HB6EF8A2*kf{ z2+Z#fQCm)6y${xIwmK2)0n)TSxkvg&W?VfP=h2O{n9)vwjldSb@Fy9Jxjud+YLnUC zwkq^n9tU|HN|`vi5fg8N-JzzixXCOv=&wavW#tM7D>WcEIe`+(-a$02$8u(tXWBljbMj60NXbY}p?ad28i0ji(MEi-j=hWo#$O+%dLYTuQ!3hCgN8 ziRX9INk;>^$Nb`Ks|5Ek4OiKuk(kdahp7c|d5K^%zg+r)e_1(JF2lV09OEaTw(g`) zq0Yj4lbrB=RqWhB&NEl?Rjf4H^J3We_vY?kO@Ba0h3&P5sgZv2`;anf-@Hb%+1|~L zxZtYeL##l=+V`FdF|FTqPgR#GA;@xsO*KvZ7#4;;9KuG3mghUq#LHZd{kCV_A|Cz- zvwDP*2yQ@R3+($AM22-Pp}mvyxW_Imgq#uAtg7wJQ{HbO)3M0R+*F$VY6Z5nMDSA* zsk3lL4+OV!u31}I!VRzvJw=Fs_kLKiBOmd!PNl;BMHxzzMlR5V;amL8k9{uE!#@Y( zG9QV79|uea_%-*+*8SnUW0y7hvd1s>y(L7}skIxlRZHe`etcYZ<17;HumK;S<6{^O z?U|i~QE$O_yTeETuN0V1qP>)!pEit+P0oIHSH})pfm>q9v-w(f;^j_9EQO!tLpi;O zYO$WW`iZI^nTW!Hqw8HgiVWd~G*ONe&nHmEEZ#Vrz%+aVV}#`NjUs88tPv3&ogd1= z&ce;U?}>>U_#`!w7?`f?FR{R(Rd3%z<^qku0Cfp+Iee^4<5wc?F%6VTF32upCcSQNt&LlR*T9mOS>b zN|=-9C2Mb)2X*%YS;EGqOSr_g+1wct(GRjq8t%K{QUCxNamVm`j_R((`F%E7RzRLAz)*KUW`bq1mYa@T3cX zrNpq40;1chh{38?xdR-F)lnUeA)omeiG-BU80rh`%d>{nH%*JLN>h`iV@T;i?GvX- zYD8^hQ#i>3=9&604n$P=!1ZV%$hTep7Qi36e+b}=(t!6RV#WNm>VDNr8eR;OJ*G*v z`!H5D`ri33FKz@f*=t6fYQs1+ zw&1G#qX=EIz~RcjKkB$PNtP!_51GN&=PYu@B=HM}%(2>hdt!dMX8yHkGxdRK;NZm{9$J91b%2FG8Gc5&6LqN(@yrHlKhp<+@&$RPWX zQ|-hY3PMg%?6EEhp0oUoULqeH23?r!aTw#~-dZ-NZ z8G}!bRQjH!4!Pu3c-TY9_UnvO;rn``Wsjpl(Lf~9(ky;VMja(1h(*(~j1iw2BwDQh{v&;yx%!xS#UFS|b$wC;T1+;S`swH<@z5)@% zRyX$7-4Rd>w~)6lxVgMu+~Ne^0Tfb|lEEmIKy}k}jj>#W0-qvWGOs++Fjvm7M4}I7 z{Af@(oPi}vfei=x1=2OSs<2(jU3OdbCs9VEJpNu!CU{m!r)q`=JQj*SeDxJv{q=|b z(GS4esVYrN{-b{zUOxdJ7^@v@;jC;qgOC(eAdsD0Z{$H-938zP?hwAZ9iAQOo;vWy zB#Ae)>_G*p^cZYDcuyD(Fqoj^BRMndDOL!@dQ0DsrVst9QOJ~ID5qnrUx16NHDwel zu%%&x{m@Sd@003>lNAqxh$rqC+ksFDLZML#io}PPHOBG{3}Uoy{n>zA8jIvv zxGE`@oUOy>a%^(K>T)7Duw)$9Cz;EE(D${wfj9kUpBW|C6GY}UHaEb<(w_y-3Fv6$ z6uDYOwx6tSwGRK-toY7FOG!*=cO=hEUz|@p97-4AB>wae! zGOD6l35F6peu@p+&ZPp~;-3fnlUt(7iopljq!EFBlVG2V*6xYYq>btyg%E^gA~#ak zi`nJjwX_2-wciqea;2Bk)cvAVkYDq!G1pT2?l89zU1VT{KH!#lis|@|J~iun)#Sy9 zx9_}Vg;T$H)F!KrnFKM=`p}y}pXkn0d$5fUE*o-T>W-HVgL`B-1c=xkm*FpYa1GaQlV%_p)!V|NiaIUo!mzYj z=W*$O7`e)j2hH$1S6M;J6I2cHlF7&m`W!Lj8#mc2(8vn3n3uN~M@3oSSuSby(cU%U zT9Mrp=^u}7h~|G%Yn>ui2;9MWPiRFOy>DPl?v2~eN*vkKumZus%QHjof?QY*fiamF zL$dxt*K5bKsTQTltwcm_=e~btcr?if;Gf>%10?nbkOeGH#L6HZsKMUsb2Mc}uXM6E? zV+UrZGL06!mpq++_;-=)=FKNgp3l_ZYyD*3tRKZ1gqg1crc)^NizA0~%vH%Pe581$ z!HL^JI;wRnS(nj=WBhYLGU#GS8x3V0NitRUF_Zql0(G8aPL1t}#DvAe@604zsb3HS zlb#T8U)okifnhcjIU3DcNub~%u2gavrw*!leYEbt6cx80|DQ`fRaN0OjRo4e;Zq?f zx}rtxb?igr7IAdLw})JQns!EU+(Ae}v9!@*mD0Wux`ZsqEajk4nQ4x|AwPvJ;IdC% z&1dLo$z7&ypg3!YmmG=>i_~mV-$rUg3UF{U=Hz)g$>;TBJ2aAxxE3W6kdv&Ry0iqq zn~VwV&SJ8|^o|R)^f@`IGLr{c+y;g}>Dqr)fP~fY|L~f$=CADY!;c>1+ zJ%2T=Xm@vC?1MchCB5nF_~Lc#^VfwbQ)&J-$fHrcAS*C$`%A4Xj+ytqYXt36rRYoK3e1SOVwbpBDq|fSq)CRuow_!zc8;aU~g$!#2_?Cfu0Lj{XneowT^n> z1>R%9cAG!&i~Y!9Hw~|lxEKjmtk%mH^zSl;FbQWXL9pO$eM`(`0dK4f7=$Z5N;tsX zf~D4GBrb6tlL&hQ4650aLsQJOC*8OW33k-^w0o8cQ@+Oi0@MH4EN2a+T< zNior_P3+js2I~c8Xr#@T5<3&*ubeBIwdRrg4LWUns&_~j_|s^1C-mo=qLnsTe9V|! z>&Rm|{N&EOy;4wG=xgX-U9q$K#@acd$*&XC-LT)n=>PT<{Ig^tc;q@{m3nK=TJd8{ ztwK{0W{3r#+~FdOjke1HFRFC3W+h_0o{|*0 zvy4(J6#|@H-NMFi;+?m#!0G`*TXW4bS>xTw`2!`9k5SumC2&nBBS0LbSoT=-S zBrNj`1V%(m)ypSv=f?j$8|nTkIAvrw5pM*VRQ8R_M`s4>e5`tQYkJ|10E*$Qi+QU) zI9!=DnY)5;<*Pbw$;zrJbMW|uZsjp?3O|qzAyf9``RCSxGy~FpC0JMCm9-RNtC{HM z?8shjogd88{z8U1b0lZWsYT7B|;Q*0u}E1V{s z;cP{ud@I&N_?-%drz?Ma7P$TsP`uvhVz#_hCx+s@ZH@Kr7!ITaLZEhLqsC>(LyA+O z%CF_eaGxTO>ydftNuPAMG7{o(Y-!S(mkUZ8X=6@OpBqr?260Kk$45bq3x;VV_&RP8MNys#rltJjZn2rK5&x`l!oe-z*ykdp! zHh)#wzrta*we!EFUKgRIJB$wSYlc=V!n5NU%;=rwQ5i)0Bne+`5`N$a|p- z2((B^119Cs&)CWh$cgbg@toL_`G(o{6Hvfk#}Cjs7pM~?6N1Rv4>^BKhiOlCf9_7Otbr^QuiMu0tN4l*j<1#S5G&Ze{eQ9@>^(YbZ+wxI5NJ@W6#v$FApZO^- zJRXPa=6inKB{=X8Lm9-y-~*tE8ct)Gm68o=FE&j$Ahdfu4pFQ6bBr>Tj(aytU-7Kk z^8i~SCtu}vGbpk}>nfy;G5m@#DO1Je>IF#xAX8X$PXeAlL|FLG_6`f<@|pcSrQ^1I zx~KVD$y}$sN-3FkZl{YbgVv)Lktd#xju2tBN534|uLXTu^$G#rnb+amb!eca&AkDVur{{S4<6;!fc87#1Ad18a zKa+n}orbBS75}wBp!N{F%zV~Z^Oi%cve=Z5u{w9S*!z_2)W#c7LFY)*S>Q3(B$v7c zY_yFhVJ6oSda6FlM3|+A_Ze@wMhXT|pkf${S?{G1pC|Epu+~T<5rhW4 ziZ#i272MfktD(D)f|&byTV2nJ_wusPp)DGy}MJM4X2^W<@7L&U(jl^u%Y%r?0 zTq*_;asjWrfp+dGn03??nRnko1sZrjB^Mz?aCtYIr8pzIw387W1FO`7gV6Y?kqlLA z*)pe-;vYh^s}ZNY*b+xoobIEFACx~3Vz(r*TKKIUcqg z5EtSL!}*`Kb1-4gy)9?Bg6hT@iku73Loeg=t9uvxs*IDA8GW_3a%?o9;y|s z+aiGslDMT3aK00py37^NajIR%wLe1gf4-ojXrV*&nkGqTD^%yPrf`Y1?tx6AOxI)} zwj*L)*emIC`VHj0@-Sk_aRp9J}w zlzO75v9~Mxsga|;ufsL~B_Gm(Cy=TP7@oUj^Op!P2<$Z`T<3*U7!T{P=I@st} zIjBZ^WwbR5&XoGlXRTMQS%=J1oE#+c8sRZm)|Akb+&)h) z?Txdy5m3z^eG9*G_$vf0aVNHP*q4k@4VeowVmpI4Uq~FsYqBB4V8EsQjGWDr_eZc@ z?ToJ4_&8WU7=Wlm%uq?3a4p-b0f1vU)swa{QMS>>iPYlb^hY73f=x68PJ-c zDjKcZm4H>9?ERZ*%t|uJL!4>jRG!`AXKw?zf>;#yv(ONVP1o0B-isV+3 zH>mMww|FS$IedXQIeXPpn-T|VYF8!A33~|Dm9?0$JqttjC52g!8rU}lYVYv-OtoXU}nxsuxm;DEnU_VF3TbE_v{6*6;27Z;TtHk zhDy(d1I*B)fX(t5M6>><6Z|T^t@4XfXRBm`!nV;%v%^g_!VeW0v;j>bpIGD~Ll#;y zBfJD@fG1bFq+g$wb43x44#H?#`%ZEQ{}*>}8Poi6;_d_p?i6~yiE(~9ZP(SyAI_(GPWEiN|@hE^wr@A zIul|(4QRL%29fN~Fg-!0CBVi9A<(bn&q0AGr{h&#}ZSp~#$-dATzH8X4 z{~OTWjts+%{$%=MRExEIXP{&xC|9L+_;XJ73sKucjmh<&DH)gVLyws7HE(DDikpY7rHP~eLtIs zIl(ZFc|OO20V2@_(0#!%&AbJD?iJXhq96C{Yn z-X+HwcSXcf`v!D}*+zgD-{{h(X*|Nj)*Xa2jh5@}|LL8fL{_i3c~O4yjg`{|)bUID zO0)YV@r_-CHq=9`2u5K074`f49^9 z`uwk3_WIuo`b!QfKeB)hBhFYc?}-`M79FqI#t_(PaHPKn{dhja)cKA&W+x85rCAkq`N^QD;deS{eeM0~hT!4DZ?8%mn2p z%6B+5gx-_giHAo1v=w{a$X-aDP62ttTdJKSQ=LufDix)@h_TF*ZjZyiA>rjY#G&it zZc(I>;v|i96J$I+dA2SjSJO^zFe(iz?XPaswXQH`oKDh!Ca zO>5l9C&7rB!@1VU4}uTF)1H@Fo{v>AC0vjBu6Schq3WF6bo0oA zxHd`OkO-5_?fb`@GuIs!+brSi${nVNz4O63mLjvpBT!IT7v6|deOfCFK`3wGc$`yVmtnT8%dbKK3+Vp&NHSHIU~7dGu(i3SS{A$3r8+~D2uM+2 zf#Tk>COP?wXqC>e;NtEbIOt;5<5hY+&PXmIfdQr^wXC3w-h8#q-u`UGIptB5!k>zV z=NE-Gy$3nUE?maM6DJ4aLMZ1t|5E&i<@k^LuU8N8s%C{_Chz+Q@QDJlyGGus9S2mBy0Q_ZNK3`}fV9}dI9A1Go zIF$Q(MQrYlE`Sv=ztex1OO+6E<}sddU3N2yuuUUl;ucR-YmxTc7Uk3j zY2Zq`ADpNZjuB6m%ez@|EG#u20(cVVC*?b*wYDsjbG$@xUy?SK1jqSRp$MS`9}sW8 z=Y`){U-x%J_98&lX)r&yI}ZLpvFt(O*WnWq`eGTV!5MQ}(?kB;>TTHr_upB7OQO<8 z*b!fIQfMI!Fed1v;%eSFXP*>dr8J)Gi8A}wS^vc-^G3b)@HfqOr%03Inzm2Wy_{s? zZO8a_rID1yV(Qa7fuS6r_-tV`p9Sn&;wKo+w~>oG6CqcGbTqXRPeW63YB4P#?G))J zHtpohpoevMw1%51X-=i1BV`s&GJFive14=BzRj8C|D{dOWFGi0TokYK=nBzcf6K~p z3zSxxNDsFwp{_rryhqk<#8*#BP7e93gfaA`{)cFd;IQmk@u{_DXXqaP^hLUfhU=41 z^s@N$zPnix%bxcYaAxKE|IX~W2*{A&_9QBz=b;!CLl+A_Fx~%vMJUbU%3|$zQ0yh5 zCNvEUTZO?6Ky3_XwyjldawL(ftM!L%{n%*0j>YM_zEZEi><2lnwj#m!jBgR_`nrr9 z(&U{Xt$?dWkN686=kLVT3rCIGLE2D4_908*mtRyZ2L9wVu@QmE-_!z`A>A&RG5;_? zFcavzfSfe7sWUBlyHfbJ+EgbCax!d>jK zG3&nyw?L&0O|>cOVwrOJU@K~tMK^6pF}OGpZt(Nar~1KrQ}v2X`AbLNs4VsDao4@* z{&u&qh`5*HD$dlD#v}Y34(3Xfp+Xn0ub`i`SzQcg(2bOi_k7-!7_mR1swG{{YD((M zG;z{6$b(g~M@i9o7@)Oe2UMUW+Rd`;-5fjqQB!t5=B_)v$+ukCV87on_mBDxX z003dA!^pCj?>t;dtbmEpPPzJgYW}ugRQ6Z*14e%1*Y3%}w$MCKW+XwEM0}GqK_G_q zdFngc@a8N{oxe!XO(g5{(?wZh;hj}Cm^)U6Sz&{6pFU+*e1Zl_z!VvqGvN6k!q{5M zRf;iko(OdK;BBg8PR9CEFeNY};I(n&ufxfw+2V8;F;ivvMnjRa>{ZHF<-)Na&4Z2l z3qaWNKTv&`irj(GD_Wr(S-dfga@23Mdj+FT-mfnnK-H*07hHksZgM4(I6Y_(>HxRP zhX*gV6`9iX0$gEX@x)fQvq=52G0~hDA@Ho0!k0R)+0p(ay^|4jKVTiVS^I8i^OyB? zIe0nc$$d^0#W&Iiz+9abCvQuO9x?go$D3t9b|bv=uDm?OtE_|QK{5k<`uylC^$-bY zXSc^TG*t7vN_gm8*?3c7j(9Qhv$F+KfpOh8(QC*NM?qT0T#T~QPrK6gJ$>B{t;@j08 zN4vGi+h&y4@{({lEUlxS!&X&Q(K9P6r2spM|7>*%R0Ie8VyfIRF^gxpW2yXB3SP8d zPT9$iox5$H58ptOGGI?y8RAEWJ@l}CTa2{5RBm$!O0GW)gcRSYFvzBKj z+F1S9QkPFKZbk3ncsA0-3AAn zkRX8UkCNbn3MCIODtO?|3YEbr>`_)#tt@w-2Y-b>qQC#Y+2H^8o=}z!f+z*Sbu_{N zKp?#q^I^hP2_tNX%_@Uj+u7|`t%YCp!CePcfLn{KLNi^^rFO zY%2vMq%ZT73{EqnV?JvX;a<|BPsu@|#SKstJxz=PCKVa&ZP7f+e<|<|xJrS4PN6}g zr>V=RSnz{M8C)nKm`@nYf9iLsEc0&0T4#+Q#=HpuYRQnF;p@{D&a~Z|3ZISB7KCUj z4=bwDr#JPl(U=e+q*%x)0mp0lum{ThhChN)MQ-11lnjOF7GwexG3IlCd#kSCD?;C8 zn^H#M8=SlPdtqDk)(u@GB~NEkm+L4uiydM%G(~FjJLmAO9yauW&OtP_oMIlycf?ER zie=pj-`tg;Io?Ogyv>cU_Pt0zKFjp^SCGkS*iJ3W&npYbEHB5UCs7s&pgo1eU_Qr| z+u1fZp@6GQfrHtNDUIqNSDYjw)22n1LK*DgvT@n~oD%G_o~LK<&uf<#+S6jx=G()DAJZchFI>ys-vC&AC~y2q{av=C)#O;^g-6y@^5 z^i_jf0|BpZa=5USABjhB0w5BHj~IZZR>MyRpBUoY zpS#Cw@Gul|lJzb9viC*DtGrYJT#cK3pp<;}r#}@;&&+LA_Cd+PfMR21j60c287Xczst=HjB1O zOQ9WJci&kM4b$K%cs}R+23Wgw>L-H9hv(4|frBH1TEAlYo!S?Z_Yz-Q#3h47ZJ~k^W!I&J|hs2WjVnWvx3~`eZt%~pI7%1bjviApy9_s zr+=TIe{P4a z*_*V_AhN-wPZ6TYTM7k>uJAG@j6T0fPil&sYx`F^hC$Q^f>R?6cBn=6vK^SwHZ>k5on)!M5 zvyzfuP$}ZXtYjTEL2>P6&PELvtP^g-_jKSuKT5AVh6y%3K4nlW+}1Y$$_C{`(s*jV zq*F4ErQ%t10++dE-&%OgNAxgk+tV-*eXL&e#QYB*a0Fuh;zepdMKt;VF)f#7l3N&BBTvqI%F!pUJ0^M^08% z_@!od9tB!2D;PG7R|1iN6Cr}g$sKm^z)=y)-6aN7DP+c8tubcVwCF+f(Y;O|S{u#x zj)D3qwGY9~;qua|EO~DY-!=0GUcJQ?u@$?YaTK+29Fnh6_`b8#}qg5WQe^yV|sArQ8jwM1Y?n4P^{6IHk6SyQQ|{vvEW#n zoDf$u8KLc#*l8Z5Jd(m75vQLqrf*71L}@GBJ3SXmMpc^Mb_yaNWA+v2#Qz5PU47T; z1G%$UdoiGZ#bt$DqjPWZQCZ(UhL4VY;H3v`|X#y z8i$Z9*ycOlq^duUHP?U0r~m0J9*G)%_DWwF4$C3D<%L!4e*OO5AO&ieux1aNCJp(K zRT8bM5Avy8yw6w8WfSs|r-f9m{KwJSMtkkIb;ZUMD>)4{k+&)jBX8)LU#;6t?@TNK zR;YvU-1v=rS_HhbU3h4J5?CZz}|{2X|S=Xep{sd5N8DrHUyKjSxeklMdtZ+3qxmQKH@ zVq^!mDKPxA>$Dj%WfeR1m0Cf1ED+>%9nkr{CtOp*tfZgiuz40ap(VxzITXJ%j<08$ z4IXyZ2?SoF?@M7S7cv})l(~GC@3t^=(LfLLNxUY~S~TJ?Cwg#}PSyZ#7kvgku-KKl z|C&5N&@@FS@@(qA_vTpJ8hN;*}eA~ z7VOgTG}{%}V#@7|oX6cz<#xZ`L%BM7ELU z#NiZ<0eq+8|WM3>C`(CJVX<5Su4wG<>JFPJZbF` z7?g4kY`s;>hpHJCZx}Q@NRA*r)dFx0BUkL%=fwq?Doz^Egi8<+{`6;-NVUAs_vui1mPXp$jx}P= z$R!D>=d_(VAO=1^t2#73Bk8IzDsIP=$sh}yq+xz%$p#AXtX=1GN2nx6WY)90`#wkU zvPUy9A)IejXjszFZk(}^p@=CdM2#%laTEvo3|)(7W!Me!E4fQYsr0v_Q#xINvZ(A|p~R9i&xjY^e;oGH3v%DpaL zPT~VKne`%~1LIyzxTxk#fd7;VdtN_H00k0G|4F#z_RtJ$d;OU1A$W}1C%m*u8EnG; zz^V6|)f$aif8-gL;BP?3uwrnogxoiW2f>-x1@?FYOZIa=Y@esi5yN+51NFE)N^!2E zuP8(>4ly2&UeBDg(tj3v-A1WA@{0ZyfZs&Du5`|4J(rK%Gar7WDD2UCJwBACPfzHX zi*HIiI*I>FS)8n;XZf+#8OUm8(eTUb7iEy`A76Nu{E3I{+f!vRn) z;Q%P1N^Rfc(O00T+ptFFwLfaEz~kiY5%raOwe3>n-gjSfF0OGAzVpiqp0rIYq?vfT zsp{noKl~b^7};-IAIbCOnPOMODYVM5@#!1kmkx86VxYtsw>DV^g5Y;oNC1Qy0D|6F z!5j|LGOfV_2bN;VFW52Bj!MB{ML@_0-Dw8J5LH-ma=cjbgEYbm=#CyZ6v12s#Yl)x z|AZk*3aIdc$iAAx_s87iia`kBi^8U)tlgeSnQ{0c5fiPlzU?+M#fLR zTj^iC(Qgi#3U2vlbsL0WbZjx;0vK2ynhHdN&7R>XtOx&SQ_ib{BoGl!q3{lPFDeEs zW@>nO`SoCjsjPWiX7;Hm?(c70rBG0Mz$}^f_VWd;MW}M!ic^xvllw&0f2uS}zXyoc zYPSht`L&NcO_Pv@d^bs_XFl%5DEgih0c90P%am5VNaWQ^_TZKOxYM&x5YG^2P*v)6 zVpkSHr5XqF!*N(7Ctw*NiW}e`_lV5}AXt8A^h=8#QWiroWbmwyM2MX5olRTU!d-RL zl~ua0C+Y&?hZ*`rw~tQXVEd8ivPk~yahn8gZ_@h1FK=|Dq5>l+1H76Y)AUyJtF~qc zfx9wrEi`#&Fx!ZADjyg-o^1}e$M8b5L%_4>o#CD}Fj0o)1$uRc-PIe{4WY6R#T)ik zunGJUWWtS)*BNnt+=(beTz)4=9YBuy`kFYmeCr$DJ&?ItZCj4Gf}J1@h_xoY0tjIF zLx%m9YRBKWaQwUjX}+{z~9m z-4Kder8Cd?oQu;x)}6kl#NWS>aba{Gp>@Zw)LHcT5`W2)0wQ2DlJg4LE zVNd(Wp`3uwys?8dMw8a@E)bVxLX{q(6hYP2QFofXwz^@GG_Vv^af#yN zM}pKdSi>b!D!q-&7SLHoV|yzBYl^etVUnl3gmpQ>Cb2DbpP|`jBwBOqjh?}_)^C7q z-n7>fMnCL{n0@>~%3BJLjVh?p#%FZ0p1Z60&o*wX-!fay1(D$y@s70U2`fk`>nY2D z0DWSuEu+l3{zWEydIA?1;DB>u$u)|5UWbsh<(Vn}n#3k?Zk^X)V9WnK~ zgLryjFt0|jg7BDFpiZ}@u7VV3i;44{{*jlZEi7&IF^Tl(1%UY1L6E(fOT({J8r~H> zna}XiZB=XQOZZ#qe`6~3{tb}*Pmaua*r$*ct**K{628d)e~1ye$(WlEX!piK%Ku&= z`b&`b>mb3jsQ1;L`ly59S4!M+)40g#Vh_5Q8RBSFJXF`*m%)-cG=t?|2JgXPm8HOl zW#lz1X(*|Lt-Er$58?!=M)+cO{+$)NtkK8Sqc3>N0Zh|&ay3bq1b5GZY~WkOM%@!l zGz#PbZgeluP^hKdKZ3&6BMJJ5M4QIcaZ1-6_IIeYn?E5p1>Odq7NE+ z&ig``GKMA}DQY+P2){buSFk5;X1B&GSZ!p|>s(&Ja~ z;VGC0Mdfo#s$VaVV?Z-OE(H<@->sSP3u>C_=^+iAq4yJ=?DuJ{phgrFAj2lJV|o$F zER+&e-tYJQ#H0jB>is?2eo#?Y#7L@x%d2DI`%YoCz-PaXUQ!Vl0s5bm@v^S=BGt4mt5=>GyPsKlk{^*i`3)b~#I zrn7miRtxPMc{c6vh0`K3wn-t&oJ{RDEPWHmd`}QijbrJZqzO=qh*#E7LYbXIgMzt9_AC4o0?;?GcqyG#>BFGxHY0iR&CFFLsB12Y{hrF76iLct? z$~xG00KeTlt8yF1l0pLWJfTW946|s-PccU!187lW=-C=FWAG*HDnUw%cIacN;*{d2 zkj=a9gP35HeQG>2zlNL;4WFUq#-UvnBjsZ8YxB7@aP;%W0$#i*`}A z4_vFy`J(Q|q&v|TI<_|4jRtxzDVpw%kgxb=S2P?O4%HdoO|!_PZ1X6QfXlc7f0m)C z%$wHE33cQhePY4sRbYA8Yk0d1u@UE6a`7{6}>XjVm zgF)gEp(#75PoJ`ibb;Ob)&>F-Kb?W^k*FdH4qtsE{JO4@4(073sdOP5wqkr{z$ci@ z(e4?YHs;nn|7vF|q4HwsK*eOOMW?&!pQ-l#q>frka%)kCAV9 zd+08U*&t_9Fh+ok%2H`n?bfbTo}E}eMx0~JMh@GGYu_7N&PU6|=-onQtI zqHN$S;Honj{(VWf7X~2`o{Ld)rp>TNBkaBoXPu|(DHom)f-fm{gP(o`0OkvfX_Cl6 zSKogF?nlkC`LtOeN>R3 zu~-7E{rGu0%Imf3U8R%f%(Puw1&#FivOfYki<^!H0=C|x<1S)sHXpw3=3&Yec&aE( z&cA4zeM%pFNyljzoRqZXjr0xkvC6)z(&v|t+|{m>H<$DA_z|kNP$l6Xhls?O;VjrAXS7t7AgrZ{ zAh+JU=R{Zlz$)OX2|U@JVp?Bjg`V6O>;rUZ+a%wx+tiss?8Fid4dSx^`8yQcdC!?3lIpcs%u}+Cf|=TIsi@E%)!fLEPV&)ZZw{qnEG(A%`*&OwQw$RlCMy*uF>588XFOt(2!{+Tv!`rOj5^P9M7yZF>sX=W zMO)h)Tz@X~*ZAmuTpXKx6sG5Ps76?A8frhqmoy{t!g{FsC!(~-rmeM2s@K?RZK;+d znrU99Iz$!Z0N||eJ0W(qAcD)40uv>J!F`Fx0#ioT&=zQSrSeS8E{=F#1q5zuC6-|3 zZ(EaXWrN&@3Qx3>AvKbpx>lq$ilC!#!u){13+3|Lv9eFH^KThlTp zupi)643D0i(m2oN=N?b1T!6%=7d0e4dzEg2s~qSKJ7mEPN8j_Ci7J;X*^}$6cg%ke z^HLPwoJfWWJ2H^bSW~{)drMOgA}L^J-vWv=aFuTTNBO3R-o%t}o!6hUj#CY z4m;yD#~@{(uls4(L9swy*`Q;pqvBTS5q1@?xJd3sEjjp2P~eW4NCxC8QcOOWN_%3k z*#B+%j)f$XxS#n2dKJF|PnqM>JMGv{BJD(?`QN1|#Oxa8?tg;4(q3o3O#GYs8w726 zwAveQ7N~{8IcQ$-U#X8A$CrOqdOZXi*iC=ngL$3){oH_f-Em}$jlpFZd54D2qq~&~ z8dnB|WHSL>rS8Vu7qoba$o-;naL6Al5e+Zfv#d8)!Bx%0_yWKp*k6)R;n-vQ0xK?T zI;pl|M;Ohl!hwIBhSF8M`(jLjIz$hY?KRE* z4UndDIMv~=?GUw_@lC44HdrxQ=(Spxm0^P$!n5iG9^F*s9R%KE(|;gK>!U3qB;#@XNT0xk`bf^VZ$`+e#$aGcxPRnIiY7bts#Kw?Qb>{9SGX)< zaXp-v*+>vj5gbfarLG)83HOH|Q&QO!ppb8ocfj2c2P4Woir?)$lgdW|QpNe`a;gnb z<4@$em4=+26m=U@A$08VM*mDlOz2{l3*TfR=5OO8r@D(+1mx|K1PZRv#N-?qtEk2y}*<(=y#Z=GBc2J?$rAnws*h!Z=mUQ@9M zNe&hoB~bSp2)fft&TM};FYx10=}Yvf20@UkIg+&wd@phi;||CBKy2Nk5#n$;g065cb_9Y6!N#92wDBmWOB5;fCO3QVHl+6W zm*gilU~YZV%{murxJRTaA9$dmhF>$i_EbU0^!e@T)D>(YL%PI*& z%Qp$r5cu)M(?(W&NEJRdC#7b-ZGN};PbPV@>Ojo2gY~rOTlA&SIjgP~BW%pX6y%)V zo9O@iZ>YYcrwqyum!GpA!-oDoeVwxO>5;;ND{J7-4b1e*qBgTwxVM3d4qm&7;yP0f zPm98pfR;+@R8-eWu;&X8;WsJS$XZ!jx9$0^lo~RUZt!%Re&9n69u)gbM6TVv=&W<8%*7|qw7+vjR>U+N){HT?zfSY4Mpj;sGv3SmhHb5e-E3aJ zL&JJjR!XP83_>T^R-?(TD!TZEYcku)K_9!T!%^LC^@DHP+Q-?snrt?IS)s!4!Ry7r zsUt~S*2%*^(%;kJ?3b;F+MK?xe_H z|G@N_h*S_Xs)Lx2=nmVXAjQqr2~*rz_L9y|EtVjk4B{cF%rSl{pB<8^Iltw8og|OY~8Ha#CGeHxL|Ei5z zBAdzef!<{Dooahd;WJ5bZPpl>^VI%_)UAeWA=;_3>JMgyEuZ)y3Ef})uzI&;E}7Uw z5Xd6Ym(4@#BE~jQ?5e1^jpCxE+Cs5OUhO65p(c*Yka+`8AngDEVnNpjVV29*qrrpua*qnuy>=V*G&bfF}OybXk?~*Fa zeGG^RKZWFIv?jh|CjJeW0FG|- zR_W)fd{c4gZI9`T+R-Ayi5OE%Z{5OFuKKKA?y7M`j;x0tU#lZ1b4tPBG#xuOc(?D?)OYEnfg)fT| z2E_kHLk^h2Lv-&~18e7$|E(`vYv)@M+M2pQ>ukelznkhu-iD^EhIK!alRG*Q41>i^ z4!*E5!I5miG*RR;-7MlIEa;!a+cDvL%wqpS>T?*e+7X={@1E$ep6fNUMSSh zV8r$#=^M-_aVqj*a`;pj2IOaccjt4R_%(UK@kSz52PP__;+AhAC~b{I8!*_l+1iq; z6wk9p3s>oB*bmnrL^d3lDita}*&>ujs@Sn7O?*c#0Aqo$^pr5-VfB8yI=QV>{JVVo~=C<#jd{JSFtK3^O?>Pge*E7&5dF!k^l^NBrI-?_m`a=;W36h(vT2#LHAGCep_w7Fr& zf3<_YFEn~7+VIj{NCd~w6BI*z9d`+Jqd|J^@7R(F-YeX_N(qYlS4)1W6U$>Ezqznu zDQEfGB1Ou#IwLTG`S!bmIovbb{b3G32*Z4L9$dhJiMo(R-|E$~OLiN~-!xDYD{>YK z^|;c(E^cCk1&Xth6<&7rzN321;-X37v1MuK&hxa9K6|YzZI$*loXGf#DJ4>?a&}8c zCXA$aE1-haqgtc=HHY^;e56-GyFzv zI-hv%v-gGQ26LGEz{b2=g0<*7SH~)83>CLj-_3q_27&0L?jqzoHl|-eD+cgTr?@(` zWdj~XUw9oPJxAeGZn7u3BjNAs={U^5>9_Mzw++?+B%6(`y&dLi&+DDiZ&Ux&bbn1i z3Wc8z@$m* zi=@}1*Z4W-F-Lje(_?``#|g!!S6V9s0)Ec{%$t&QO~@!`yZJKiMs%l+5KM$Usq~=j z!f+52IT5*BnzJN^v3>j&TdTQQc)g+oI90>iobJ>SwM6o%kd$9x=vxa66)lpRy=qJu~$>@;5-Mubt{eWbyRW8MV5xwD;U=q~NNi zboO0f$D$v6b~x#H#@B^nf9A8_Q-t^k-0ZmXcTMgcF=1Fnz|*7v2HT1lFgfc8GR;n4o9N@`o87D+cQ`mQ67{UkZ)n1@PRM zc&X+u{#(}$ve|ZkAdIE|1Df@VB0uL&wYXK^7;Z6nA-d&fUn!4qB zxjFu6d~GHdnm^kIFRHBP5VGcG_r){BH9O4@Ui88=`xPq_<{Ds=66Q z)FShiZ&Yj8#Y#5Cz9?{Z|JN%{m5dCiO;!)r)6Pv2IX5cOw-cFvsGNLZln9 zDR}qQTGF!N@HgO*Z#eV_a}UIQjI^&ti`n^^yK*6_FvM`P9jtIa;=8JFUs-tpMQ_&2 zwBVAY8u%U+T?my7@xL-te$)fcBeCT3(A3t(TmsphUH4%v;H$T+C*>o%LH17@Kpc>t ztD+21KR*pUzFx_DTt6!?UP(3s^uG{L_Rh=KpPtY1a60GFh(NeW_f2L#6H+v*{6K?6 zmSwzX$ea^X5RbpYh-dBh+^r3c$d*=Kq?6?8^HA!JaRZHBHdDq_gz9`J_5*aYg^& zhn@1hwX$dvBf`(hy>-yT^7Z(S_BVav%P zat=)daA26{YZXXvt~tVS`v4rRVs_82Gg==st`@%LH!eGnkY=#>wIxEBo=t@Smz?d_ zvRDcMfQ-G=90y}xV8!=H(p&T7^A)TQN6c>W^lRswk?>53hD`D{*MTx`+I*+fW0shc z$uFy}55P=r3HQN*g6*0tgZKe_ZU9B0@sm;v8)g6|xk6+}(8jRjC{+v&R5U#(HP1w2 zJEDIzR9&NpX8i>pS~{lXIGqnozyuB~@ zFP~^Uo74$t-_SX%ftbcYZZh#YAZ*Z4Se`PcWh#~z^O#y1LAeAr^QA8-5pbHM>q9`P zD^)MZ=)g2FxPa&J)e#g%tE*z4tAcS^WYY;$fIrIx6{jDkO7*`u3Ms_>3prfAP={U+nWXjTWnVkEvy56H z$}ns33!t5_&uJ%eUT3wIo&f|`47;j%<04C5mPW%9t0(j|}mNH)0H^3K# z1h&w`LlY25b;Yj^@@{P;C|ZBOwBoE9G%#2tY*Mzs>+GS6{!>24uKdC{^^(#outH34 z$Qf+1DNPRvPz!Lr!qLEHS)(>gVz2i+UA#cTF;U*y&N+*{=$ISNnrNKI7ukDS%*7lbb5r+JGbk{V`1oH_KY$mQQB z${_v;4Si+`_YJ2o+YY_9?A79>M!CO1|1z@W#|2 zZ;5ViU1R)zm*#xbrY6>kGN)Yxwm~AH8daQ~o&NOAV>P{o1`4Sgyu*3j|3s|_((~iV zPCyT?edf8--+GCBD6GOS=_tOGxKU?KHwJLzjigGs3B0Wy*bE|}+|yUSV$1xzuWZ^rknnPI^{|Q6QBw3&3a~Q+0|l#Z-g9r%YQ05r&hb zUR1>5$RN7{XOdBtsR&1kyJ4=JpEml}|7}wL5|ljFO~+>c`Q1Ji93Z6~+)?q#LJwM@ zoCr3CM>?6o=x*Wlxpt} zZ{i?rVS1*`Pxec*ho8c+K887Xi$?ecz5RL`p&T4u+2qTImGC7ch(%*|)z|c>-bM3q z0&qJhv5_f}g_}abtR}QCcthK7A0fxuFAjCuqen$e!SU9>OsAc5zD!codXbKl7w%|{ ziMshywXuOlY%)(thfK6%9YcT!+DCf&Fl?mC*>wAUjc#}msmJSpU!VN>+H`|{p%_AK zvt$u`_=0dOJrK7=wX+Cw-1&*@HD#HQm3-o`QEVR#Ip;_%EbS+i6n2 zvzWVQ$*!56a@VywN0ju*08)r60fY+Tr)PTY&xM>oeC7RPfBT1F9kvkPSd-!lTFb^s zy;=9gGsDkzGh4NphcDfgo`P7`<#PMT2Do+gCKtLVx5Y?JApNEi%Au5oxlW(YYv#dIrLX3vM zMOunqxO2$YH3`+c5o5W=!2vSBvO`l1XB>UN4R%;YhYu*A-5te#+(Mn}q6zX1oCepy??Gx%oeIoUnf z*d6e;zR`#xLS~{Xj7z#-1hr9FoFOA;NJ}tikr%)QdO_qozDuz~hKoJ=L4y_KZ=>63l{xaYQg}g|_@U@?q3D~oJ8<5@OMvB8^bLG%QvM2cDFY4mQv1AScs++L zR+r6-?UVhUVvyqzFeXDFG6!e4jp~QJk#@Ig3fdr1J^M%s(S_b`fD)_W!;@L!&D8Fk z>HrEOPi9~_NWHw zs|dy*n47;P)OYH1m0So?Xe)fX@7*=H@Wr+Q%k@S`;&~)6KQ_Hrqp)M~8E0ksZ@|73 z4ee*`T;AS$CbCs^@ely`!u(ppVXYmknY*G#bdZq+8eO-FGdX3d@HKsT292 zP;Zq{Vs*dUnWm2*WyRzH-X}c!G>QcS-#$KwJ+m?%+U96SxNZCAY;6{H(`G^aDD|dM zGYM2T98B)Kk+b&_K|`}_tgczO6^*BZBZH&gAj2%Asq|+bH?E6~(^c0v>vuCGRQ^dB zh{*S69T8Zx1F7=ki^a3y%%Zj_)(q01xi`Z33)T9Nr(7zS-#-ltFuA+GP00nu4Bo%b8?ib5^`^`<#n| z#$Jja|6#iVEo0nb{o-Mk=(&jTI^6zhiTzjx9ge%RVg>#>8a`fi{AErnm)ue1N0VfS zM&D;OaoN}xC%5iUz+dhA-u6>Ik7_34V2mNcsra?oJhUPA7rxAl;$61&gLrK~t!bzX7cvh+p z1r`S~=W^H*@E&NNGz;PKlLoqb*Zlh#jg&!%3F<@_)9{`xJdK5YAj2Zoj| z>F$smx`rN*PKOjwx|U{#8 zz;WAg#&BP*N7Rw|U}S?MgX$WlfAm51E?mXFLYLnZ-Jk9E3lp|HYROK91WkV(6ac!y zOrIwH&Pu-4z+|8%8?*QeBfoTyKte~ue;jA~;W?s^#cg-)X8F{xqbokQ9%utq zj5?6L1A>u8*dEF^rNS(8w_~XDcbDUs(Ul=du^%9GB*E5UoAnKGtg>LV8Dz30KhCtx zU@ONYaZ3d__hbV{nLry#>dGVy6 z(fjZh=%%e5gqWBzqdlFyq3rD|6D-BAM_lLCTNWkZbYSHC6ayvyeUVyutUPyFBgybf z{tr^$8NGKmBsApef>f@07X&_wiHKfZ(BLmkd2Kf|DR+Pg=KFSl^{YiO5HNd}coffF z^f{ko@CU!oPP~l+4ml#u7q)v94MA-JD)w!x6Q*_x$=+excV{&;Vt3Q0ET!US@o&h! z;ok3DAT=pFsmwVTFfO|bmDOY}bH3#!lcsmCJ#dUW?(>UT?m%le)LXp=n104+$xY!& zU%c&Cd`1-!C=)CGir7k8P$Pb!ig0P`PNK!_mNeVn_$tfSZ z$|`eKAq@`LGI!XW;BkUqH2Ypc$7`TvK^*Jiu#a~_4e z{ASLa&WL!`T(!VVujAHUNZEhKKSeFhwtU?J<#bq6%%vJ8kQM`NQ~nV71M`J>$2ZD@ zWRV!2@neq}?=L8lmr=4QN5UczJW0tn3vz@16KeGnixPR#x4|wXdTu3g4B>jRHe$9T z*|ajz@^g|eHQsjkswn)VF0k2O5Y{Ubbx3tjj|^tOT`ik{QV&Hsw2HG$~tGYF}FWhedk>8B+~tkt0A>h-1#}z&&a!C)obDC zAxeI~C%h>X11}mgEObl}=xMT#6^0y-xI^<7WEFXL>WNSV938*E;FY++5p5!zTZnd@ zIHOqLJ!%;!JY(^EDvXxVrDfMQ`}8Ps?4Y{j} z%A6GeLeLN4180+ppLp|a;uU)X=2M$=)cO3s7vL(;IE-OU^MqU=wf$|j_GTW{)mHr_ zhd6a`%@>`y+KaJ-^Yu8MNP$<#b@=a-9rStM{Q?n7sbeqv&z+;2t%XMdd*XDd7N$;6 z)IijYi4 z#N_`@=A^Q?iOol0a%xM)9C$ICd&IJ%Aml<%<#^h+tI?0>CWd4~KanE&Qhy{j(($u% zqf8cV3(}RdOqs9X$6RuR&2jgb^*U6jr=)jYfbV}2)VrzHY{pdK^cBofch4?09${o%Mle)_OcKC3FUG`9FVV-2$LP#E1xB z%R`rr5b~~gKdrQWbD#E&bf{kD{spp?`qPg*m_b2dhP^duOTl?ILrMEbTf znLF7$Q5L{T{v!vZr3i}SNuw+6W?AL!19~2)v2KFv4T5Ps=GoE#?9P?~eOiWIIQ!uetlMkLJEtU#n&Ld`fzPA#}* zl^-C{qLj{=zm{RDi-*xa8aMtqT<-Rc1=#GHL*mA!ToC3}VQ$P(HmqVKHRO^S-7P3FDy*MjAM)bqA{ zB0)5}RgozNUiZE7`q@smXn6*n^JW?cRxdT=cL2myz8OoQH6pW%rUJcWDcBg`3WjgA z|06%Slms4`-|6mVn|f7#LtO$CiJAvAJ7(6@8Q=GM&c4H^4V}d?YisV$k$&J%bX0=lz`3yqZql)FVvbKL|1#CwSXvfwe z!`E#OnnfBiC|I5hM)Oe@9r?sFyI0EaYo3$zvpF$PwsFqcD5u4ZT&O!8^vmFNpXgZ^ zYzr}2JbR7wyi1%m$Y$$Y4&Ryi9z@EJ9e|YC>7KSp%ODHdRk(O@@X+7}bT%UG4~a7K zgQ%vW^=WexPta*$?HAe2KlpZ;^(ji#`u&_kEQ-@jC)vU7MCST!x0%NuO6@wq-H-jE zU8ww#*$&8!!ZpBZM{ia)T%c~;0u z=>C^a4*91U{XbU353L3z;RE4Ed+1IGXllnt(7YfOY$&ptK23rR@gh;-(*Xwi3-m6k znGn1OBvhA;=Q8|y4y^gU+?3f@t1#!@b z45Y1|0yD#Z2Yai1p_@ta7-e}DNopWuEcl@%tz`_NAPWxGz{bU2217v704sASz}cor z9Nwb$ABfk&GV8n+?7qeFHbSG02OQvG!aW!<$3qp~T~RWk{6RYQaq*0-Y`Zx6mzsto zh2}T1$pLH<+eMn#LZ*a?cM82(&!@wGphnP@nty5bx;d9jyrO;6QFKjD_Ev|+u$v^# z;%q-3eH!bWPQ}H0g(pxBLR#f81&jtgq2=}Co-6PBYe*&_2sv~G&I~T{{m)1!g3wl> z|4<1S;I0S)r+l|(s!Qnu#8!o6&NZN3F_pKw_-xS zW(IlS2+{0oKZDzosp`x}(e;zCTWkW;(lPgGQvmizrwdl3;|W1Y{bQ#l?zbsAA@B@9i{Jzm3EPI-)a+`R}>Tpz23bFOtxXgfk z)|7HHgPI!B0jrV1>nUoszuO*H45T~u`K=0x+)nN+!X%>9(T=#nqr)wzN|^QL>TB@1 zvAZeLnBFQ}Ml0ka2eizmhlQQL|Pd;+YR-D>ZNyW(z$})Zpo>-J}mbQ*kCJbmIRktG_zC z$?A&EDOJRcDJGo z2&?%*E1~MU_`XbJV{Q*}GUwUX<*$$^`BMe(6X)hRd>m-qKkEzGP~S7tpRZGQ4c?HM zkbTi%rMnwkXB4NAe9=lT73<23mSRVQYJj(>@!kHBv-#QQO{(9NWHSQUV^OqA0=i8l5sP*CJn-)lAI1-n${7q>Nj*#vS*Lo~XFRs{|Nho*jUXQUAc z1uhiwzlBw5*|^ZZ$ltpk=G{vEI~{n~J877(;DPtlvYLS=2(gY)xeA~Euwg)_a4yr4 z0|SILkOV65iFMYHSz{QM=6R9#VYBQ> zN4x?weANHR(z`R=1c%WUS!0|q(!Z7<|1o%CF=f1~6qZJGPGtMTu(7-TO=e5$hxtPN zAvbhrcPbvE{PXjJGF(LS_rxi3x%ogCJ zFUnox&NW;=68Fn)3)3em)o}~a1a}1k*Y)Qqq5DvGFV;X`6j$Y&yw{wUBP4Uyk!~nq z&uo8+&RFEmm2M#YOnR+WD#fnFtymCu&tz%l1Ona46&^HaTIqZu9uk&Tklj)kHv6yt zc=3ejeC(tJS@X_cM;5`K^hB#LxzFmX_N6UG=7hK3AFXXoXIYX(4kBn;$`YTv_UIb! ziJj=m^uv1lt)5l>R9>=vw+h+hiD~#Ag1C<*F9~2@ol*;oLr^Zkn;IZDg@M44)FqZv z90)kSX}6X_=@;lVF=FB`kf@siQ*juhnf$E^6)9O-TaW~nKR%uz8hxlY;dV#VS!Po- zN43Bc5BM+8ZvLZVBjJLjr6kok2&>kDg5GQ+UiNjF`v!kyO%S)x45bJp;3c&XPU_$D zNZ+_u0%-shOFo-{cx6cR5JpsF8myOf#L!Mw5-;lltG`uAjQH@CpD|5Z%fz_Ltsn4~ zn>)>*d2$Xz^ZM#Ts-fL$-H>+Z{c{FHvdYGG0UVS?MKd-xSk1qb5KT-! zDxdTtp#awAq**;xuC4ryzRx0l^r(L^2eSGHj_618bi*u${!Y94}50H8?Wp}-ME`2`p;_db)f9+32XUN#IY{sRyBo89*V!H^ ze-VCD09xQ#ZC;)t?xyAVc0qBW?pmd9_(P_t_mE%~u84+Xtj1a4xT?c$X$Vu_G15J0WXcu8ig5p4m8E zWtt{^)1ul?19)Gs|9I6S@>@`0_(_Jd&Xzedo(%2GZF>CKs2Bm31bqfv?eO4t*X?)H zmzM~CfUpiqZwG)cXOEWB5tceIhDrP&s^_bu+ zCzmy!rNuEjj^KMNY*w0?-XpOrMGBl5c7Tven|jl)LQgWR)mA=WqhLwf!Sp;lP6^XQ zItgapmjq+DeVV?Ac@i$)Jv1ar*~MR8NF4et`8Xm_^<#*lu2tdxLBjwLk0DzjNqWvU>L={j^440q@ej@IDYOfl1HdGCgfw}aMloxBdV8pr{sTiD z@ofw;_15qfui#XBQjNqfkh04V&zRCd5>EPpDlwut(p9Gg&;wW6i~>KZ#!Ck6M=kQW$iLQ12{zqKBOnC_@WGf2)@h?!F9jCYd!0UO!ir1~JezG`4 zhsfZP?YmIP%SD`xAsa;#)Lo<*`A0ZhxX2W+0_Xn)VMs3)iBMTOc?BSSTM^n&-WXXc z(m%LN!MH}PG8qxK5m#q^%W}d;ZNM)Q%5;*z#tNpM@zq*JisMetpe47B`8GH>b53BG z<~Wrj9_Er`)@4I#68gLF?k3KTnj1+p{v;K1x@pINSZeQx7t3g5$O{gRYVvb(rMD8I z6%mt_d1upJE3o)-C?RSh({Qk2LX}UquAP7>?~{=#+R)Mwdpo~n&MU``c0ccpxW7vO z5S2_HJwI~eQv}!52$*Ba=^MJfQ<|oHqA`)7rN2kZs@v3K+hWK0jzVF;x;9rc(=vpD zU^Yom_V!umgFlW!?zhbfL--_e+hfm=qYxZEk5o}xuNZ5#{j~%N3Z46xJ6j|>@=9Ai z4MD~70%Xp=8#YOlxF$4!P6l6XXIT4Ee12NIi*4ljQ#U%A|75-X{+It~8;-yJ>1y?C zrIPR3!0q-^!<$KpcSGSPx=6Y`qGdxn>j;wQte0Y(*{Gns=lupq78H1zU&QLw^3EA# zdvMyt8X^i7`ZswzKex_q%t-fK(YNjtDBuJLG6o-hM5(mLYHYDy;Lo`AQ0>Fnsopbs zs9KXV7<_G9Ti0!bqPka5o=z}!Bdmlyn)6!-Lf3P19}A?!@|0dzexv&sVK^iwY*`xt zkYUM5$J9Q`+fskmEu?E)Am@KVSt`PyFZ|^+5y{02y5Y5n(GX5YZYBEyvrK9Mk|e-& z6ZE1>+;qzE{^E-z^=Q~WUBDgIAX1wN%RLv{EfNWS=*NQ{*Q$N(F7%i56xr~w^$v?{ zNPeqTmYqa!ls{p1upepVPLX`tSJAi*A_8lt*u>NH`tggEI+a2(=Q0W>!hd44LI|#5 zx$HHhknG7*Yt8_VZ!E%iqU~j460t;;bjE^id0~&u_yS&7@DEp#8w^$JQI8XFqpsHd z(f#_Hm}H#vW})~Xhh^LU!-_K54OVA;u?h%2X1{nGuUG?90eHG408dxT=PM$G>xVsu z)7=T@Y?_V0Vik)OY5T>KWW~G;{1u~ot^0*~c$2b$xe)t#Qc8S=G+`L4RY}m3=;inx z&7MEqI8}Er&<6^GoFrClkZC@j46Q50b3$n>#9g?>P~Y5suqBDmK4bGE<&Pp#NWfMj z+FVc2t|~8jIsCG0MPIWA1@=ZZ;MqFuJYikQyfuTs!LP|-O5Sd zx!L$g9TnR!t+@@leyM|sls-X%;g4sSbn1XG70j_TCxr1i{X-(;hsA;HFnpoBn%^_r zpCgZC|DT$RCXOaP=u82*$aP>WZu1B`cNN>3Fnyz?M}f2pRT?`2@P*+yv-_DW=AtCP zU?=|(F-eExc}hsK8n&|+_wu2Q)B2NL_#s7sWl65hRq+m$cGc~ z_P@B!%mx_#^jX|1O@8WP5ZAvw46RlRFw)c-nYhy(hYzgON%ROpgMpzs!Kc(>>0F`X z&Q~3%RyS0WQouKXE22Z_dpBD{iq61>(=}&a5Iy8??-OhCWTxyUUE5stG1$~MU0goj zAuIjlEfE64Y=T%oT<3SWcZpCE6@>`}jFt)MYNb1-$W=6ux{$h8luU4=D!yUhg7u)P z$(s?MdH&{gR!<#|?wfQy1Xkm8>W_PX!;p7G{>Z*g_bRmL)BdrO$(jjk{$=fH@`ATm zv7EPbeB6i7e2*Y4@&Mlu|B1msBm$YA-{|R{_r^$6zm4om9405S0BjBD15uh#?DksK ztpAt8^rclMQnNrJ0H|hGWT2|E5!(&=!X42nECg(fGq0iIqgCfWBhp7i=tlJ=_+Q+o z#{;c9bwD1}Y$mK^6E`D~b$aL=a+XT3(KEMuJY<3RtR!Y1bu6I#l5%ufY+pxT>1tON zx-TS&_n(yb7w8}L?<3puPV@B>9^XS1}1d?fe9MV{f#!)j0(hucFce6uxAWe~%hJ0I`*(lrH|F_}W1T;x$%W6e<^LD7 zo8SW0$;lr4rl<2rp@uKodm)d^SORH!p!etD zYT_~Ioukv`FCA%!#Hwg-CTu3~0UeV#o+9tqXJjf(+rG48JCm{0!FaNSfVU_x;ZG%9 zct7$k0oKoDP^`?$nJYFvEt*6M#rNf;gp$uytY;_Lp4XoKHh$7?y#1c|(Qw$2ULK}7 z)DI&C+eOW=G@8aL>kpI=lEg{}U3O{v%{6(yNIWKzeG6lX+DBP|zqnP$Q)bH6OvK>5 zl4D&u=I6Osz_KNZ>VLV>oSaO27orm>ASqRnfF&l!OFb*RnBD$C2m7^hS^9vva}e6| z4rr-8ud>JCsX%u4)2jeNx3h#DN~4zz0%cL^?z~+`-W55bFlznfTWU;&kIGQ=FBzUp zg~|D(c2RXO#U|b}xn6qagyZ?A-J&CaCChkO5{Ob&?U>+Hn5UX_13NZ2F~LJLz&3*= z8gqFQew`IQ{9q-dvOvC<(tk0t73>Zx z0)+s2C*QmudiZF2J?xe4cN?p?49%AN2|CrHr^4$iVk7fp=jI3C5#OTRzUdTZiimC@ z`ia5HsdRsHsIS(%p$IsXF9eGX7nx;Tl|qGf`S2@x7=O#!4wcNaJ2tBPO@H`n>*o@@ zWM?k4{qw89{j6d}*gDHiV&7c(XchO&1B|Vd?I!6k!^=b=)VsgGi7C)Aobm)lqkM2s zIu&B{#O%qk(?*%Mi3%*607~O#M?ryCyNq{A^54#V(L$TO79Oezdrsk&injhY^F&s| zAcWU*)0(Y7nP>*6mSGGh46{d;A3kbhgP`5VdWfDn#EDNlSR+Xes2gLvFZRmG| zWWPXLH)(CI_wC7=C+`y>q8cJ&a^)yQ+NKCYJBm`PS+|*gl*`HRy~d}ql)lwI@u?8q zJg6+e=tcc?3h4^cX;N*Pu*l;e9PU57Jgmm(yd5Kg6|xG~hN=u0t7@}|u3<{_h~)2c zE%1|r)$9P+^jC)aBm05~%H`SIX%V}s?IMzFBG23~!Tn+o0EY(Oeh|Xt`Z{=RnY3;P zURd)2iA*SK=7fO0GiM)EYEeZH%44Q~6dOHB6qVkN$7tkq_{#Cmz=itZEL7121Lf@7 zhJ~sh>KmH{>g1pIX1*|D#Yh+i=@khQC}nfX<`S z-Yi$C%pJOZ^C5jD>@L)`0*=KN7~o>d%+8EqPa(Kp#i`f)^XCjNE(v>!rkwsKW!Lfj z*&1o$+0558`f&WLb;tVQ{-1VKh4I8`rm!GQd=*qSN-uG!jf32+aLm)U8iMg7%E=1v zc|5dq!>S1D?3^>LqN>xnM0c3NM#@^i_iF!8Ham<4lwaYEY8)PS^yLN=GPu_}AvRAl zN%r{*CSa46?Pw(lh|VZUZpRIH%i)l%OFc@~BR&eC&W?>=wkjv7u${eN#|i5NB;?xP z3-lF`?=cckv0Ik4jmY13-P6a_>mrF2d4@=B^x)`yW5pwi@IfP1GuV%Rqr!l;(!2f_NZlL9Zns-v8fVXynihOnAM0t6G{E_-*s6>R@DHM@8=8IrvNqc9L|ztKp@a?;d+409yOnZWg6 zj>!AkFsni_8uF6Bi+sl)^9?g^cBh{A)+dE_P7%M4sf?#N$T&9iTY{b+6c#KjN{tq6 z1mk)PSjJUX6TO&PduB#H1QmY{CVQtJRxeTO{8m=lf~q7cgBd2>gcL>V(S7AiGE9EY z?}b!dGqaduBk`=F2FfW@trF@@Z)lmOn2r%8=ld34K$1T4(J(^{k%koD768IPQ#8QG zq*=wq>?moQLt_c@e)ZE|GnJpCS&P5&G2mUM`jIJ^PB@58mv<0s-~`>_S6^qKJmYP& zRe<_S$Xa+Ou-N=LN4bdUU`tSY!#uij@kH z4~@em$PT9&6lV9TP-#zU*^?Y7a2-A`CXnUq^Zz%vA@`<45L#MFyiiwh{yy4>BfRRN zGVL>PeGvcZ6I)U5o(iDl{KR(9CP*NANw3Kt68r%VUO~=XsoORU4@Fpa>Zd2g$M4H~ ziGdC-OQ=X*41~ua>dptl`^_3+`yB^5wQu+P0pU2Z{~>!ee0$u=I6+8^U1OssrRHZ9 zr-ot;d11m(*Cwt{1jO}GugD{PDVDAvUi_dK8@Mj5yJOUB-$FiI^ggRx>nDIir3ml{k2;>+R+3hjeX{7XnJRS2@kS2re zTq(qjxz|6JiPKp7a8*YESFM*XXeq_ASC+0j}c=$Lv|qil{Xa5KM6F%MN{o1a1`qD)AC0Gr${!>{;nJzZOj+5M=z$rWq6{%cXza}KjWP9ml@^#rc(n2 zsRq9GOKR1&|5+J+JNMLPkNq8$3spRzs$!fy@?=+8MAGQ_1#&G2Bf|EszG?Axvm_lT zaPD#uqq9h}x=LTc=GOU&VO@Y#0CHedxC*gjWx}s)o=v-nDoJ72pi$h2m43@Y0z&9Q zIF^Y-(o?UDszd;-26v$UDPoHZZ*zw6JZdnPjlP%t&8MZHP^4=M1r&>Ds7RE@D*mUQ zFLH2NFWmFigtwpe>Bp=p@`lWOt0o@EPjGv;I-0MwNV#mU(c)RlN%kToE> z@ckU$_7xh$Zs!VpvvqcIEHU8Bn#4#U+SHCu*C%JhLmV@QrFT0Ejk;Hg8W z7h!CqWoOL5*WLJNowuH|!Bo_y8q}iT%8bYgawxv-$_z}cED0lX^-HIk8yW^y`_^aw z)#|O!dl9y@Av2rc9Wta&sx!`ZJRX|IG`WW*E$E(JRK-w0Sks+47ZZl$jO5Gy{4s=9 z>XJztenUuAY|oi7m6)OKbuem8^=1%{q4iA_`=Po|s{8UKbH*`BsaH3I?Qzfu<)**3 zo+cF6^Je8>vM7rAuQzV!Y+BhOQek96wu}G zv-@9n;zHe~42^Pp)K;C|AWN862aD$AXaX^YS^5~dP55~?)V0V0>!}ypW=wJbOMaiC z==KX6Jr0JW=(Bctp1kL5|DE(pdZ#bRe(MqtfK;4kUTz2WJU)psH~Zp$h7fo{7n8a) zLjhv-6o10MtdP{zZ4zHN+K*dr zOq90f@f253(H-acv{k6sP}ssM?c<0l3QJ?Hg~oyMi;Z2Q5~I7ytQIb30gQ=S6d7bs zL!OW~!26q@Q{v7~KCzY24XsjvC*SA^d?vF_p-|UqJ6D?4c<-RXQOT>y^06h-bOA@a z))*6emG_Fb7m$!q2`b__yd0<@DMQc>!p^>+uww0^C(0w+Q9&Dr8_S59Nhzht&+!Eb z3>6^_ye3ghSOw=lE)dgzKgO|HVMUR7{yG>@YU$9n)pvla_z{Y1<-H`*K2-N2+T~)L zG?pAq9+z@59;&8-jpcw+pO8o4R5Lede=3Qj@LA=dG+o9P)Fom|*y~@bp&@y38pH}i zRns_|+Q)P@)+K>#Nt0;YB{_McRTxBSY57j67%UIcM=VnYgBAQE5+X_lfplmKR)jADVjNJ6fhF&8+P$%sRo{c56UaPa~ zEsh^n9Blv8_VqU9eF}({h~R)7Eij|qJ)uk9MrOle&Tef<{E@hDkWC~YJaOKn*tj7y zk-*n?8@DIj6gD#gMZ)#%0~=~?lg@DUThIjmrhxuK7ykc#X#Sb{e_e!>LxeQtA*bBn z`32#FqL^6pz-z`cn=7P0EIwJJ1W51*0uXq7GFc%_74m(7k4H)GhpP(*TAt9e93&>D zipEAjP^xXdW^)1P{cENXO}SET0!MnuNq&@k$VwAXj5Qd}kJ!c`wHmv{*qn$t$UeeA z4P=a@C0$~f@ygn4RCYRB=I44Vt^l%HqOjJkpcF_@5QC%1Q7^T6QoXF+eQ(lM58ha1 zUXKXh_)S-%^#h!=W`m3dTyp$qY)EXz<4cSwfxK60j0#ms`Wz{>b%pdYayw^8R9GRuF zF(S>|(^GDZt0)k75y2HK?m}YNB-%}3XGoWE)sepk@DISx#yU&f_gD)ZE6xXt59rh+ z0&u6V(v>uHb<77?1Yi%6?+Pr6%0Mb-4@oldg0 z`fyNZSoSG(StH4F2h9D^SId>Ld2ctO(ViH8c+Dc@=ejKvhQ9W=8ve%^!QUqpX_+z- zbzA%NRphB^xF}%soA(QZHK}(MMEg1s@N!Gy!$lN;y9SB$BaI5L@+rBzqh%o2;YR_1 zK{yFU^7T6HZ})xXg0^ls+-ow`s`eOl`=*wIB> z+z(<6SX^Gi4guTk`csg_xABZZvWC0Rvhb+`Nnbs6f>cBnltRjMAL?4N1$Gr{qRIti zM|h}p6Kww6}tA$C>-|Xjj*_{4KH_{B}!_$ zI&Wz>26$j~+yKZ>v@V`@({CO{k`aBQ{x=D02|Xw~Lr`;PeWIZ3nt7@S!8je9rM{}k z^pFhPyo#Nn4yeJGcRsG5dFZtfs0w@d{knd&0ktvauEOR zDq`}y1$dnUDgwW-jk%h4%RZ?OZcH7$&ii`**H;u?C5yP?mr5zH9GC<)aUKZ{!AwOsl>XC z_B5nnwL!}pf-$9>6z0_tpfy*K^El`e>D9P6H8rZx0P7!KJ&3-0=<&bf zzD;jgv2$(${Ep9jmlb`w1!$f?8;Q;5$NwLaEZYtHk$WqJRPk!zrpAz&xk8wiPA#`!m-F=_ zQ%?z3P0FRFE^p8(vNP%k+cEmrf1f_GjJ>hTIVonPIF2P$kVWP}u^};0g^P+=Ewlnw zCH>ADqMHoww}u45$4&K=Z*=qFwu)81Kp!BPP;35;TjDg~nJRsbFoC%uTr~PIC`!;U z&@noIV_Ct!G}ipAw%VcaS`>kta7Gqg?;oOvpe0@;ekmMr;E#%g$kZOz}n)Aiv|fRm?W#Hx+H_A;FV-D|KAp}(d6 zWN*?o5!I`72&UBC9Y9a6+x>I27S!8E*3+ zlA}+>AN0niKJj_*yea!vEp=}91)!cg>OS}x7{|Vuf7smp!=3tnf1%`+owB>t39B7J zDT6P$LCaR!kEOnN5@vY*`V~TQ${A(5Z}yB9*6@@QV+^P>%0p*G*{)9se?Y(U-PFvY ztGYft9bTJ7=j!1)u!A~YT$pW|f>)b7rkzdgL#2iU_h5fIa!rvKMuEl#MU5B|L$6XG zPF_cs8tTGSO)Hp)u#5;zDDR$Hrtt2UjKkexSPCr1)~PL2a(JYKVn)zDB{G}RzgZX8xwC4 z(8#N;epQN!CtJ(mjcX+(MRl%4T^(9ONE(qf`49op`&@NbOvSC{qFnkVLN`91koctq zwajCf|Bt9pV+J62khotYjk$#dchaHGWQ&Sbm>wzUruq#orMJa?_+|VxPmkjFoV3jYy8Bwi$I3< zI|9Z|+#b`en9u{oY)n%>& zlQWJ8{g*|g1S8j1wMlNFfSG^?Ifl1^67nc@p3cWN0=zAW^65pd;(S$K5B@DXeYJj6 zsefiuy<65AETPfoOOGpO>Lg!4oMfCnvAfI{UlhCNHB{+&%O0qTq?e@!=+-vX_fwtx z@l1r=7TU``Zh4Q7eH|&JKD8m$K%FL8_&Of|VEJD?ATv|NT!PW5`eId`DzceU>u40j z_j6_nq!I_oLbcVoLEr%J@3Wrt47y@q1%996M>|BOpc3^MUe^M1V+iA;3!ZrzhY+S) z{NFv_3f0wRbnj+H%mF4|T(#6u7vRl&e5hs6o7V|wuaWf-A9RDt90^7Wh$2M}IAxke z|J`*fqaN^#Y{}~lQH|c zjYO6KAQBYVIWOu9TwubJIdOxNGU5`=5>VxCg<+EC;VC-p zkW+}*v@;W4vc#>SPS_+IB)*9?rysK>Kd(FHyk*yTk|GO4`HsKyCk*zzytHkd84H$v z*V3TaCO9Z4z5FKM9;pW%!!@y?BE`;`8Z2V8-)qTI+I(&j#v2Z@N+3t6p zFKL*5QynqMl&B}Dsm6J?{HZ66%m;7P0kIT+jvlq6b+*^I!%+>}QFM18^L<_BoXICe z-0$d8#%xpU_P;=6VWN?YZ0Kku%!aui0xrM*Q*IhfCMbsJxemRST9-PRDKU}}H&%az zF~C4SMndpZwUo#0#pJ~EmJ)_Sj_W`$$=3?e6T)`7#^mdIZA?6*_m9OCQ93MwNw0Ch zBa+tG?BT*x<1!Jey03pI6J2%r3>2c!088}4qq#SF55xVpe-KKj7(*MnT4_7&@08S* zLV3zofqp~1DQ0rgEA(wqudCmA2-FFV6g!F>+2uwmnuHhX3BkIlXeBQ}e1$z^`+J+r z>tTEJeQIpha1!0YHoRztIdoCmHNZ8D`jlIW>7j54lGZx$`D1mohOfcu>N$yrH4?2MCmH4sVpjOp+5XBQNSXJ2)1s^*0;OKI( z)u&s0CPk66WQQb{7rRe%?;lwh&735}a*a}>6w0?-{XWZ8D#(#q+( z*Q7Of<#l@(RFJdvy_)l7z4TMSbf>$*@C=S3C~i3#lc}?kaw6{kv)VYR?(n!-t9;*v zwM4m9#C7!Dgvo?9CH{v{tN8?D&ZYMplHSQj5)hYfqanr{UJqEQ$%9vprb*sblF#*=|pZ990mC zw2F1i_DACvp{Uo|HAV6$oZsjK(V*=pHx2sha=r zVB*KJlbb8kgPQsz_)ciLmFY0ln`UW;u!yw5c9>V8JlVvoD`xly*p-hjmY$d8;MEx5 z_03r%%s6nnrk-Jq8!7b204SNci`}> z#mRx`J8EX0cd_xHrKOqH9n7lodi`#q-cTwcQiR-U6W%%HVmuVY_~d^u`DiKaNs8S% zgboi1-!Q%075hTbI5FeuBa7A)xdgBWs-$a&1D}bd6D8{teX!8QVQQOVXZn9S zzDl!jIqPb#MV?)pX~B^c-g5>I#t9N~1}2+Q1%q2Gw% z%&_o~7`MR}unj6_YETY7kHW)$R*?t8!*{c`tixnA4p}bDR7bd?|4EYv^3sd=)gXj3 zu@P4#Z`|0^{!)9!22F9Z3z7ia>4ZTGTkp_{R{pR-v-Uu5Ya;e3b&~Kei?$hJ&lre5m@G&6(Yq#9OF=$kTA@Lqvqi%7P{;}jx|3V z2nT{g@^GArdqJHoT?3GRF#$uLPY**M>*O1Z@1d2tfpFVg$e91QYgp6$dc(pm(DFiK zwS7eve8v_fbpV@BUuedIUkD^XNQmv+xvD1wLp6tD4@Bz*%Y909O@z0^#v(IIEiZIl z64F(f9NWHucedrMtFJtz=)WtZe*8DIcMdEZ4+8cZNzS~(_A$0_q9E5Dn!ljhV>jYyG|B_k6h}=IytSL$>;%uo{ zHz%LG9b`hbSV)9d5Jk<|DpuyGKt9-35hXt(Dq2W<28sSZ5&rcrP!w<{Fs6Y!VY7{T zQT4K}6L>@(@{w-CSv?V;my@}JY-J7)wfahdy<*nbEa$UlRxqD8&D7vORON=dP%q8% zOmb-oDtGjkw*=SUjryYLe#6~fPFBFDMknsnQugahL@%G9a&MHn?M1#D|{ zVmhk8F_4CUdt@uDM9z<}o6m@CMekeZ6t1<^H|$?}=il)Tba*RC_6Hy%gr&sags5X* zB#+@lS^F#CkA&cD+2KKzRf}uSLDupmp#vm1VVmz7HS$;`oZ);FxFy$6@Gjv7Tki#T zW5QmX)F7E{2LRbTz)4VQ3#s!;b&j)M4n?@MCJZP%3t3A`7RpgAkjGA(zxTJ#zKmd# zA5}D9OrJR}CzL~YJ~*N<^7p%_19>au=Sc=S2I&SHdZo+D+Rgj2xQbcp zC)`XvPAf=B>j)m%91Cqh-=YA^2Wv<$-1*Mdh=?v4f?TyrTfmg8TuzF`SC{*5?3s{< z#AZhB#uJB+*-%RoZEaVKj!o}NrT7+yUvyPB%&FjfO1|Gv+*-oQ_WHI10iQoYRZfeau-OS!LgW}Db>8) zHkx83Ae?m>MkHNy0KNQw`t`0nCo@c>d+NZ4lLrG02LJoUK--L4g+Ed|YHZ!)yQ>JWD|kF@n;Y0AKB||E>ocGmyORGcdfT#lRTVW$ z`VYX$bp7XAqzN=&Atq_4je3b=Qh^1*+z5M{dYT{qN*Hyj{{xsT+s_DvyF|Z6ywA>b z6YUrJ|G_f8@1By3UzkJ(0uU9EZ`8&$mY4z$fB>_2;0ly-K+Q)-oa1w)dCMQb#4WvW zlI}NtL^uV;M4;K2st%~us~HbN9>Fs;J1rFQWS-F|CJ7#Ru++}8pg z1B07v2nZe0L`d)o@=G@=Jc~;{%z*5zTB(Qm76W=92XB*zd-t z&($8bJOijn%^o|S!={F5goNnJjJ16(oCc3sFbB9D;^vnJ0yzjjs~;ORfiU1NmCU&s zIGG}G34;d9B2`i;v_(f1xmD{Z=kSFR@>$4a1n0{{N`) z1HB7+t4V`lBmyajq-Yr!AS44?*6nKv>woRwjgiVoU8L(iqda zL$v^j(#HTt$@X}ZTx2=ctduv$8eKp@(i$Of}BAAXd+@J;= z^V3o?3Npk2JI8HOZS>Di*L3shpGW);;G-a?D%BW>Ql#)!AO2CE z(blj{k_jIN5Wpzo5Ml&AHk@!RW*2Twwwrsr(Y36b8y{z%g`n}Hz0d}cF%EN9FqEYz zZJ8b0R}5z_LgH0Nb<4!CPW@izgpW3d)?I!7Uaxry{p%Xih6)XFMkJ zuC#n3g{LUN_!!MED4qWCj;$>g4IhMFza~#N=ljJ=$e3WsPeRtnCgZ~=5ppC=mt#R^ z$0@bI!vSf~fCz2_eZ7r1&>)s)RGXfwX;aOE!YzM3Oh7K`4oEe4k@7TB`Oa#xzrf0YV!ol8TIO zfRi+s@^`Njoy19yCVIP`&oP)e-|-8HxBPI!3Ms9xZ@9ig!DVk|;!A--XBKH?f6;AW zGY$}m72S@xyLi_#V+z_q@<|41#d9CNB0vGJKS+dhcS(lvz6>eKR)Xe1+t3yX1 zqcOn}-R;h(oO+&gQW|&A0Mf$5F@j+prY*?v?BebXThfd+cY*2BAHe7CRjAv?b|>hY zx;(OZqx^;TxpqutD#Waapw>VK3+**twniALVZs727-Y2`8)GUiTBZn%Tz>olLL#Sq z{GX%mat{(j!#OyIeI>%|Xb8lOY<`MbS-MrT(<3bmZ$78@G=cznHjp*624bxs=Gs-y24+0I?Dewx@LlVKso@p@(Z-FOVYM)}l z1i4h*--J(2NTJ*tB(N%JW8;s!Wn9gy=RaZ4l}bYS^-%sq*Pd>9;p<7W5*FpeN=!@8 z_vol(fgEAd$`VwTZHIeIiLFiZgG86DHOcldTB}ZfLVh`#-BKuDsP+2HrY2NTyRuU4 zULc_`IbdG?QN9v606X3Ln@x&JAdii){(xxo;8R|0mD)y%I1n3xE53tDsI2f4jOz-L z1{op8jKDf_yqh)+xw5h}I0ccVKbzAG8aqp&g-rW10}*;lG0s_rsZDnS|65Hx#_F zdq&3XV&*#)rY4D~teM=-8C3!x{Q+1eY1SMzM<{!2d204R9&19QDa^-L5lYx_#IgAg zqkswT-*JWIM_U>>CQOuZiy%<_bGG+?@mPo@#s4a}5+(;rlW3QQmijsgN{NtY3XuaK zT(ju4@Z&`)zVMjbCizbjOm}c3H0~Z9)=5RTrMBcBhYTshx+lwR{%UDTBCX|&e9};6 zH0PbSH~9m}@+F+zmWsrxWB@i3Vvne)rduINb%!p3sP&^In_)<73V}S4b2__s^6V|_ zNVED2O+s%LwK#9yjOVWVX86Y%F0;f39-FRk9aAmB%wa|!>JCnYA1H3l&7Y~W=H}>s}G`p-2^#)P8rkyQ`9yDd(t2S z2piO`lz5Vcui!{!93qxTY(V6%rC{C^53Z(OH;OJ3Ejr7uo3G>0ii(2tlB z>R0RpYY{AU+S!WJET=mk61ySqWcN~Sp^ZR3hc2Yh)x%GOdQUuj?j7f>xe9iA(0UC) zNq$-n4!y;)J37RwA>3~X2?Z^v$qAiNWzS2@*`v}f?Yp=kDN0>?z$Ps~QmG_0B|f3m+_iiTAQh=An`1IhG(u|tXH5)$);NK2 zZEH|T4|J3E@MYkT<+Y)5$2g@W_#JJsGEii~;{9-xY)aVD!+@HDA6nA77P50BCl z)t(x$EKYoj-dKsg;jcoaZayYY87?j$`2hK)53mW2vQ0}@U9QX(K*CxoXVme9VCW18 zLZ=Yvxe}&r2xl^A?qn4zU+Cd{win3S+S{Ar(247Hi3y;?Frl7(q2#-h zN98xDwc>iA=(MY)Ju-5uNpH|~u7eTxZXl$_2x_10+d>hv@Of%nJM1TuHuzsAlGiJj zSm`9gk??a9%jo+Qi_CAdc4pMEC@RVW+N2Zm2)uG@EZkmSEFaO{?x<`2)u{nFDUR#+Z{- zFmSviV}Z8vh3J0RIG-S$!%ZF)#+%@2XUiSOZ2~$o1fA7VGV^(+YXj;``UX0`Q?XyO zRj?+^F9F`M?W4?y)>^;7b`YPKeU^+EeHf6L*gDdh#FjxFy6H(D!&sn^w!@e*0>4&D zxN0Z?`o!ZTGIGiFF6=R%UW=3V(J||&PD(CtTFXL^MpZt)01h}0O%f)ZijRpWKb+Oa zFIXPjiTwe%=(Dl(+z z5$l8pNf)+wvIJZ_dPMxxDAxY{hci_r>JBZv=OMY_vT@Ewo-QQ4x2DHui3E|2v&uvb z2Pxh-cIE;|KjHxiF?&8TD}8;6Go<@8-M6tjx^<5EP8CbqQM&0KVp7=6M|bz1nU7yW zsZD+jPYOyZut&`-waRMFH%9(AD)rGmfR%q^_DGl=_I=|k=8ZP{(eqH%kEBg<31fgx z`fIhlFd^mMhb953F&j1|U#wI!3k^Hg_cN`fzd6!{N=hV1dGDmjV>Js16&-3gk>VLI zDj+Ijd?)G|qAjr7FZdtDNK7y;>H znMs?vuHH?MRfc$gDMd&y)Y=b`7}hF$*RW8q#h!MJrBN$t5l)I9hJv?T&=5Cs`PxR;eso$KKG`5f6dY^6fxhG4<@j3pSG94Rs;|x-K9F;FIZ#6N|Fu*a0 zyMe7V1BBPia%_`=M`oO0ArTVl&bX#jTmP+dV>b|eC;25`5qJ8`dHC;ymG^>6(CoE7 zeuBJYCCnKmjuiuh@&Cda3%8hs z+l1S(*uA9O6OYR%N=VY_<>XQjiI;o*%L3v}db^+jmONl-@~Yggv;nN|hKv>yd8)R%x>e5?DpBL_;C$#>CM_f#nFgi&ayHWq4P)80Zku>x2V{XtghEOZojQvaa6wK-_{Zhzq`x zOYWt4um1K?nYJ^yu)i%fw4bwrS!yE4L#z7>`#Z3tHgyCPQ&_|@E$ORic0|6!(_Ia| zf_zCt_gcxjD~<_nMP2)ntPE2;a$%8BtCy7RUyb+weuqDLvzB(RmKz18vp)66;%+Uc ztHslZFH-&i2*NfBd{9zqU>ToN!@1-3Q$%>?Ms@)h#LpicfqV)~;y8kcbgocOnVC;# zOplGzkD`i}2bL?YbXMz`sG+8r&>H~&094DS(QhH><{47`0Or$L#X5 z;7jZ1ta25LkL3wgmE^$B=>$i;eKAiOj<4T7^rJ*(efOdK7*e?)K+ao{omn*JH!1S3 zk{n>CzDQL68aS0-+iHY5kv)|NdgMJIsT8>4$rlYad!eP|QitZ3z-@wSaq{_kW^%Q0 zB?xc!)m9%$emPq8c=a=}H6%i(j*NvR z<;;1EP76pl$soek&&H0c{WP;edE{>2p_(mCo6M)8f`2Dc`E5Bm3qPDoPSSegbx9ZX zdz!G|#z0Sz7UfxfU3VdgGxyNgc{1KU_eOt)4 z+Gq>$B)A?`by^2e`9q=S?=TeJE|T;{5|To`c2-{>?bWnsZCYhPh;*A!+WopXVnDWz z&`qmBbl4^c8X+FCqvq6e(~k#;FGXUW_M%!R$dyr@)#x&R{RbgA>5K!tI1rU(Xll|R zGLj6`xqRgj2}wKJ&S!|m?RdE>z$EYj09-9J#o0~qoP$3goI>F7$DHmI`v~ztULFT0 z!na5t7q6t!f5AT>`kYVRA#Cf@#vM0i5=mi$7V7DO1iCeyxME=a+J(E?!@ewQ%?O3# zL{TJ3`APN~6eFWk^0p)uy0BAO4CHa(FDMmi+#)ox#^Z}#GS6Zmt&uil!8ZJ1d9#NZ z8NJM?ukS2q^))%U_*fN_%0QqN+e`}obca6!2)%br?y2U0KVIyn6G8v#Tihb@!cEqn z{{cW(cLYQ4l70RFetb2}YAUD6Le0NK+#su_cB)8(&D@nLj)Kx52bvYl``tgt^9g}j z6S{S8WkLk>9hYa*1MIVq-zKFn1eE3DcqeVXIsSEyR+v7@?5V)zNFc#|4HRJLUDP14 zKveYdq+eqb$x8hLn~Dz*O8Xb}^a|V}kyjoF{{U_R>alS8t^P~(-!@=IMp&W9b73O< zGeG(vDO8_YY+!J30$15z4&Q2lC3-PS*Ha=qwKL3o({R+`~kQPeegY4ewr0 z3PpFegk9oGdml~T^0AnnUFARvKa2`O;zDJ15owBrxdGWi;nxdp&vZ@_yux}%*_w>8 z#x(h1Aj5{KGsj907e`?r*GJNa|LUO(up+2j-BMtm}+Ia~N09jkI* z*LNI>z18T_G$J5dnCbSUjp60(WfYOwNcjxk^Lw^E7gxGbctXQZV9Yl;+nVPwq#}=w zZeAo&?#IXHTFgs4JU5xL9LB}n{l0%LQxxBnW4VfBrd7~%eEahj2#`UZ?&nu01(q6G zxJYJ1tpOHy?17<2Al}jb{=2BKotdkta5R(o?FAW_pxJqtwK6aHgug#Rf%P9Fx>Lh! zpPRjs7V_y5ZU7xI1~&Ztpm_0;buum24b+Ed|K|Cue9;o2X7o+MMTGgu<6b#@8ukfR zS#$aYaO<+q2t78Hu65VF>b-v`{Mm%R5J--xg+K$A+GIfEGOIo`Cyw9-Fy?Gz9GXGfYUYKCauYGrS8_Y$^ z0(auMc>^!uHLHp%)5eyY_7v^nvtqJ~x;qu=h<6ZFI6jqcP#w=kL6ibA8UFX*fvZZ` z^Vb5G!u}#2HN9r6^uU$7ai#J)*hY%{{hIr zOrBG0>x3Io=nVxwf7;oPImoBglL%aU)h*~!GYT+lVgu;s? z$;xmdhfy=N*_o$GE-WrF!r?N>Iv8{-wf-XEdta3ZMBmpu1LF_iWx;5`2ESau!^wr+ zLTFMl_iwejysCG90Q20}+kY>J(cd0>b37TVdTo^%IX2kGH5gXh9NZucMbe%93=VAE zRD_i*nG91Tvx8c1oxhV`^RN^MvWXNOYH|4{z}p1LgM%aant7~n$_3oH6QUbn7_HiV zgE3_U>jH^-Kmrv9{CS?(nQx^ryqM0a*l$OyQF_ErJe7C- zC4VRwJB`pwsq#oJ@sPuqIG?u6MW%;&XVX=h6*I~;Ql3Fb61_}idjqSYElOP@Gl4$Z z1_s~vi~|>kr7$EH8BP{02J$Z1iK_ZlIBcI{rDPP}$P{)`q}XeIu{*5yf_I1XEY&W9_;<)zGkeUSB26}4F)ZHFv^I7;=jq__@P3HFl*3v%w zMgh*{g{TxPSP0L2P% z8*39?@&5fNa-5;%OqTU@6i-&wB-dSs^8#+SI#R1oz7vx8pQrXoUu<1^1$c!w#xQEO zH%>{c?e)Chn60PSno(WqZ3NxxhklZwz)#U)7-oKp59@ybeXt*SjX?6Rtf6SRWWW3r z*Bf)aaq?AX^gXC!XFT<+rQV(twFg!n`tC?oHq~}Y8cYnYlHIapn7@lKPN!iyU(ael z3uJBMe5uAKS7St0}p zP@m6e^c-6nvv!afyjsBM{#l-06f*9G4s#yW9a*QGmwW+O5LXeogYPw{`%CUo9TBzH z#|3T&(t66@oA-`2Z)o4q{a9}(+$orzm$551I z{+f%Pn&hT9VQYJ2FfdKF+t@+7ZTg8LCaDfv71`O}dqq%w7Ylk>&)z+rf2yfV%>Mis zzk=u-IT(@@V@#}cEl^Z>Tqghg`KL;yN@DPC0vkyw4O^140@ijFm??jXMdJ7fEC_#T zpfkt6lX&B=GjMOey=9YbxlD>#P!>b^X1jOE{RZXv!)N?dn%6X>kJ^U?=bqU9^Z52| zq}0Gx3L__X80BOW;I7i&!Qi>Kn_FVMwo={{r*{nY>ee|wPlHq@^w-s=$Kzukqzb=w z|JO8wUW=qT`7$EI7w0P05+%`(n;0QqaIWu`sy>KnzFy%nn?UcAjG4CM`aZ{9>|)eF zy&x(SjzA<7LAT}-FuByDMQCq*BZKTD6g8Rk6tOH83OJh_EYt#M*y4u|Bon4|LeDnj zA@{WDBuZ=hMW}>GgH9lCixt~-kMDb=O(;HS!!C&ylsWxBH)$7A>F6jowIzZYgFi_i z{>AfD#KgV|R1k~UCqRJ+$8rR8B&6>S(=~J*F{fIOdqiQwv&yt)V2lzeN^{vXDHy1R z(S4odr=(~zXJLhMcx1G3sa&-S6$fF@b(zdi8qrftVEM}rua&+&6kFgZj}rW%Ug1_) zSLwrHe@!sUoQIB)#) zrm;6b0q&p8hq?MhR`2%HE1!hCw@<1M>d%!aenQiI)4cbViV}Sf&5PsmN83o_?%hg8 zZS-ltG_`m06K9(Iv8E7V^{MI2B!lqXp{8c0%Ay9l@E<_rB8`YeGqODA;JB%|upi;RR zu$*||CC*vlL-z*|l7G!M;;l;{d0J|yh8d5tB!uo;ZLDStpUG10eMgeBS;eXS9m(*lQYy1a5yjhWkb6TbnLx_@A zt8cBDwz{8rIuQd1is`wu@fINW7-&Idv?=l5I^&LXa|))idfjk6P#ytd#AY4o--p3N z^OP`&0E33~l_EVfHRTcpxixF($CjVYr8AC;yJ9{Og9W{O#i=A%M94n%^mZq{wFJ7I z%bJBP>X>B`iVQWyys?TQNkGPJcfXhXsyC1wgQ{SYV^yC$6xypZo#^P!uH~-_2cb+M zryKQ_^S@L2y_6zhRRoLhk-bPgpuX`Opya!HVKkbFK< zirEWKLSBJ=P=r`LY10Xen_P1Zeci@9V(FJS>0A&8FZ}wTee9BHG0dN;K(xGKLWa{M z0t@zy7;~xaHM*vd1}d&lgytEodG>A1CS&_IJtjg*vjXh6XgKY&SLf0=lzEdaR2eN- z+kaUsL||5C34@s>J=fC#>PIX@aV&zoZ73y`lM>PdxW&n)M|aOiF=Ih(&d=|~C5uxlqxsq(*}^b+1GPe5;-iaA_xhtYl=qVL8oAw)f8Wj zTlkZD#tTo8o*oy~fZ-D<^g2vF=GFu$9p0oSh1pp&R5{YcFs?~zbA_bDXv?G&C>Wn| zwP?f`{Yu_`VVe;R{dinB`*g<`K1=I0nX@L5Ew6fUw@)9^9Gxx1h*4l~f+S`qo&C)O!)7i}=5d+ohcbMlM5R14V8CoBsm=LjN= zq2OpCxxH`VHhWu$Xz~fmfC%m$K4L*_*vyCW6?vCiF#G!~7fNM1w?ms__I(1X1SiNJ zK!b-%EdxoVFXrLVyQ?5tTYlnqai9A-ZregP7QW0!6(D9uyug=Bk~iZ{Wb^{U6^OAK z!PX|4&*VBV474MEF|L2qpl^9A_s_&q~70A9~Bn94-2u+43>GzLi4xCU~{46qvhvqr@C+;H1nU~?@ zLHySxgNQ3G%GMt*{n({GT&gSu)F1ami3zY&p`b+QzhQTF8i~PqI>m`j7IODI&x9a?E0h_Eq>3jrqPOORM2WpgLgg+A>*?@(EEAlQ=JgcGk=Ii%vve7Sv-M zVZO>sj=Lp{q{8M}vP_#xrvUqsOUhmk33YkgVs4BH zN7sE^$;U)`CfWqj?HX4SGl8D(8K*xa+o-5S08s4LjaquA(WWIw*;HmbUqKy}-SAEl zUfPVIPD`5@}O)%P_INn!U(01G6XLt{tu=;#p6nnbbnB?Zq~mSJ!r zum-pPOphNMBe46DYxP}lU0*F{zLWO8O3spYjy#qEs3twYO$y4KO~t%5LhzwKXo`VI z#KtViakJNU=w@To)0LTh_4zTZlYz_mj*gktR()uDh zOKHUS(V-P5I>7)17d2;Kkgg=ynXev~|9L&Q)@Rq!mKEJL1uk1ioB`qApQ$(%cQr!D zf`$@y@jsBwb&Q1}l0=nHm>NQ_IC#^(e)!KOTBgS(+jzGu-Hp1Ed7J%takclW=IspN zQ{}T15{J}B$d{aO1T2}#-)lt#iuW8~(*s+#F$;eWQdbyG!)o}kr1Qt`8AEeOz8{4+ zi~nP31h+Y7CI%GA1{KW;F@j4n&5;hDY0l&?5XI1f5X;Z-L0ZI8t6f@RJ+=Ctf4dK| z)gMTI7W;I!(k8CPtMhUHhW^+hyzzm)Ts|!@>D`0UBaZK^Yl_P>>J4ik6fug4TSsF?c@a9J&OaXLz`BBYGg!}^ zME6Y$pEkQ_zS!}Vnj2qpIzFC1?U(`NX3JU~Zr)VBp#kO2wGieE^VA}!CkA~Hx(J|r zmZY$DPNAqH?+cH7ufX;81hERjQR|KhnNm=QVn)V-$l9TdlzIZEn0RcWwIwm1FPMdG z&6>e(KMzqET!7F-YUv>BDx^q5xAJ+AunpslKS_ar?}sHl+@lhQ~mCz|uEkj42%Z7;DyAFSdrsF6A7=)mR|1ln;d#T>2iD zG=mWt-njI%6jRJT1Gmhpuu0_6;F5|Zk}P=!d)K7!e+9y*FXVuHP&EiCv*`IcWu$2t z=)@>LKUOS6SP@6d%h=Vffxk9Zbfl9LdB&xK!Lm_x1ruNVn!vc%Y?oP!U0b9&(Tz}t zaS7m-Fkbh$$e&}DyYA7Y zUrz{vKC}lun~fq?_mRX{xrkAG24TNoQ;j?De^pdqv5;XypG3-WG7;p8$JZum|JJwR zU`3@g zaCMA~-J`Ps?Zve(bFlmHp8NAiWTSWdMk10$HRG@diT7+EUVd3~s094>E%%p&b$uz@ zi_3{@s;-L-Km_=?PCHe1c;IXXgGAEF>ah3@>5>qDW6UJ{+g>}IfXEb&3eS4R@8dt0 z{?FniJ)SR`;m?evVa?(sL#Y+!ifQjzjMK36J=6mY_E~hKh>GImj`a3$)GFq3GXDT} z(VhR5RqwSec7}F9&3knJ?(ko2i#0{*L$G9Kj(+cEo2du0Iu%#o={bH?T}`&*E3k#* zFyk&QS)&A^EW>W{<+C5?j<>oC9Yvo)!&s%59$NjQ!t>7 zN6AXdBjairXqY;JzQ_VAzIX%M4adbKLYsGENdsZ~9A6d;H!pc+8_HAP17*M#SBdOG zfPAIIkSy)iB9`!t{B)8X05siSoHZ!7Dm{>gSjs85)+#_Oc|i>;ZX|%BTH*WhbN7~A zdhs<$sU)K2i5gPrwA^jBz)MYWU^MyP#F|@xN_^{ zi(TTsRh_~d@Hq<6n$;@uXOY&P8T76+d6dWSK9s1)x;TbA#ivQGX}Oa3+=_RfHbJ_O>6BH58hKauyV_gSsP;T4JphlKtMuaA^dw{aQEC;WyIFx8(M-wP zE~?QJLZo!c+})6qI8`BquMGp(FVs%Xox8GKq^7qW-f?-8WN`X2y6|Pf`GSjB&SMSY z4r%=oEvDZoSH@*ygqIM^eYwI1`DaJf34&2h17N6~;Nbo8v$+-Dz?}z)d%}%^}7oBLzM3U-4Fzm$k}$^-6B8 z_;GD2D&qlXnC*%#?+~e(-YJqQ$CP9)0xiM9%>j=;eTO4@=0MZa`ljAaw!fG2KOLvx zv}P$?|G;e{$|&;x&DTtn^C|;m`f(cc`iDab*uhWRe`X|`%)9(WSlGTs>;^=YtOm{o z4qSx7-AlgKVNRT(Z_u|dk&tZ`zL@up@njHwa2y1(sV=Zo{U-IV5gBAVMwQEqW(N;e z`BG0-Q7(xmtY{O^i+G1*_ic-NgX?bp>-HDg=f)3bCZjqbT!dCoNkzOXZm+}_xqZCRcTZg9FXZ_hI z&OdR10on5Cwi_w*x?NDtElzXw@EEZ;{D?2hb3+ZE#WXV0mILN= zAQkAsY$?HYCQOWTXODb9V`|FP?U+_IsMI+TlZV}D7eMZCNr5?>u_Yb+Dj(9#$s7<{ z#jQ?hVeTz2fn>`r1B3;%Z%HALHmkP1gr0nfD!nh;ka~Rkpf?r{4|^lHPMNE4|I8Z9 z1D4eTiv&CIh&KB2bv49q$#43uk&LZ*w4-fz@%*d|a#+vY)^ci`0o;Dvv2nu{qu@8M zufL$6-of=Ssg;Ikkup293n%S<=RDL3#^rP@Wfee}wX#CppRqHXJ3q_*y+F zaH~X06qw%)4ejq9oVyKNZd9d{*pwEUMErhApaL4bpA6wvkavE{qIE#dV2fNE!rdO-HiE5%U4k5L$7Da6pFn>ch%F#*ZM_ky5K*6 zt<~u~I=a;z zTkwWC2T(Mg@RZUsw*0kMa1rn(9vA;~L1|rgYj}4fxK;S-c6lmPTLDAGp0nf+psZRU zE-KN)5M)Itf80Pwq^~?b%RAOQ_w7CzbN7v>`d%>Db}lnB^nkdHcWXEPI7TNU=XszJ zOgh^+VuC<8$ z$nZe=ICy@a{mI}O!!-gQjna2^#^iopit)|jLzaakmlP3$xAHdv>?t+B<%bHx9nV2K znbGhBW9y_B!p!S_KA8C%Wa|yMHIkuUSh1@7+Tr0Gz#WzHa-;K--}6SWA#-!@Uo-a{ zk+_N(trWu#cUDfcVzfgp1*JkgX`&$>Q1tihS=%OjFV;8(McsOSds|E;kfmS9ruTq{=wt&1{c;;u!#e`#v>I|33M(5bTa8XV|ObtRsVha=-MMRpb)H05@ zUdK-i7SwNMS0eRT4vcXPgOe+8Y27gAy@M_F#Zp5RjXH-cb1N%2{oO$L6A6x>${sJg$xEkRW8K3 zID+#*Ncd8~5aq>jVd(brf3UtAiI#9acp*Vh8~xbIsHOP6D?so{4U?UEtimmGC3hWf z#A>n0OAvqD1JCv59{YNFkm-EM{MrrcJfZW%eB5_2{9QaJJDzM4pdXBR>4#TwO@-8x zTUCMw+OlNn>MgPpEz^nNS7R?i+sHv(O>}87%wKg>6n<4k~Eb)9_9-X%)m;wUSA+jTH8>sMF~3?>SvEqYDGDC=8OH(L>q##fpl zPn3+N_LwCrQ4k2#1!l0LsFP%*3mCm;(SB$n63Ag6u|=}r$A5lfu#l7e_C9@|;2nvQ zty5j~+FpRtlw8^?CX76JXz;sB_nXxG^(2?YB z;Vg_F_8}s$=H``gK~)@gcLS6rOkW)fEGb9$RhKF7|K%G2GX{_pO)V766J4`TRIvj= z3y$ioK!|Kk^0>**c$$RvaRE1BWCO*+VTa1@$vv-sl`pXMmetHD;oH57ICMFn9* zqx+&mtD z`3P(3*RZ}8_>7-gMg#1QqfR_Z_W)ovH4ea2f@_Ph|C)lbw`FUdf>obD-2Z9>zWLO7 zhO|%3p5yWAH^X7=zf>{YLL258HChx_M0h_LNM;A4vTd+5>dAE-w<{9sKA z$|ObEqVZX!E%pcfOPtIZqVQ8XbZQ^B4`Dp^=X>>|3+aDXhy`3Q}@sY;g zXBsHI5-T??L(_Y!Z3MbIgR7!hRaK+d1>bou+9qGpg%xwCsUpdd&+Wg!+Or9cjS`xM z{pQf8Dr~EcEL{_ICC=L7vywVdIkFjiygOTnZGAItEP0|s&ANK%7K=u}A4ZW&Pv1Ehy02>UwFp9TL0J48oK<%;mJlAor4kY>WIUXt6#Scf zK%Ro99Iwew2O&KpZ!onXgcl8$WasRr|mRwVx2b=!);>3$|FxT6#fAK z4K7~(;uzTY{q6+1uTFo2e}+diI~PHkjCOB<0T1eIOW=-g&p8GfAQkAs4kBE-MVDW` z%mQ#X1~;jFIScAA5tfZgh7`R~%e>X{$c|xJNPj8uws|=y>j0v%d<0DU?$40uMW|f* zAxRNeA042QQHUjolMhes>-hD%@cp9^Zjxb)GG_AX^3<0D+juN&0MgqxCR(I!Q1=jU zqohE1Z7S$Hj{cdzbZLeWW$mXhX;9tviE97FT)ZG)lMZk}Sqe->E{Q7X?aV2R`<4o# zY0w|}L7sm6@vyst);XPuvjlUeOSq#0NO}tC6Jc7q8l%C&X-$st~%>lyEkQcX8{Vg|K_C0(z2>U;Mns#S=Off}*+zRvpubO68u5SsmeI=5yH zzZ5fhU_e+MKk>RnVO+DGTD(&r_8O1p8OfIW{*&TW#;bZi;! z&TLCu_q$D-TM@u?tLg-iHgTYGC`iVDmwSvobC7SSG@H9I%$FxuehXEgEc|?zjd9Ef zFM?o+HUaeh0HkqwJ!5-~G=7*6`Tz>%f@sa^zil@h9ofYk%V)Y`x^mM#d+&_KNgJUW z-}Z>5AOVcFj=-|&bPHTz_{H_F%x>h~0*5k@_6&Qi5OXpqw(6jWuU~V`jukH&Aq05E z(G@MyulYVWlg&i4KzDmES)Bs6-bp@(8P?v?RrampV1&$pII(+Osp1BpvB3ds1miEe zoi~+^Xf9NaANCgx-){*k6MN`R2a3sviAp29?>Gm#VS=8#mlBH=MIWL|GNjH>bgi?BVfU z$K~v&t}*>8+JZi1cX9G`#5Gq)TXS-t zm<2>MlnUIk(FX|~qv$NHGPA%yE*?eK)Um1<;5m#$y=plQpoVmr2v8*qjm+|zaIGZl z>_@+P`{EDp;Bupy;j2XpSOBvak-x<>aL7GOA@rtLqRxf~@O%p^j4wK|HlVfU;b%VF z|F3aDTJ^n2zx!I=y~rTeV-uVO>(SG=4Q=;P7k~^Vl3#qZS$SpzbY<9Elsd3GyzJ6JR&oDYscNlmP)6Yg5X2F7bzL=R)g%)6l)ZJWce8lruLWTmtb!kAO zd^vY*a-08+I5(3xNHZT?+sNt@vD3Y%LQWx`;ByqVYUFq_oG-+E#uBy$s1B(Kp6sDP z3Xd)I=0bv<916}|&zGXpYvHu2IsX`aX5FJP=jaaa@hrLGH0G%z)sxda1EMnq)Ha_M z@&cCz`0$g_)!Or9FIY{Gs9M|c?ZfX5wCH4dWNNaQQ#}3vltNcz6c9d<7tN&UY!e4> zruFZq+K_+6*@y3Qq+#aNW01i{%vKW4Tt&tRKT2Y&@W%zS)mW57v*gZvtzh{OK}cr@ zMsAQK84`)=gOsDaVp=RR&;GyWgLD&j`WYqsT4oe&hT0%3qZ^p=GoR{SOp-iR2kYD~ znZgd4=A+O6sIVj*k)$9z?7Ml3xw-kMWA+bWD(}%2@35n?6#*MbaP7ccn6DGwa6GN^ zY>ArPnkBw1v0IM!DxIvWO;7%Kafqa>%_s1Zv4tvz4D3E(gDru%iFpv&BWOOnMR=faFq?ZsG9=Mp`u;l{H66zZ-6jK> zRp+;(M}FVjUiG|;CteFM-S*(jL(oelknhkpJvhsoHh_k2u4QFn8hWa%<=}~=iR%oe}@CF{Ko3-4{i&WoMEJwlDv3zn(|IxV~cxi zI@?18BKfh-CysZDU9F-$-U9(UwIUgcqmZ$wqsxMqZruLq|4VE0jC2jJCOGY3gi=oc*(e(2GopZb5Q zUDO_os+Zu&8_IWvub7#?3Joh^3AlM-W_!h+af)TvM#wxCZ6-nqmE4Tb=0 zyNsnl)mOhhBI+^KTI}k-<+PvNn92N{7z}bWHtYnL^Y{9OU!d)W=)O_ZFPc7mRyUdc=uPi2@C$y-V859})ztCt3{%KyGmBpP$h0GU%4~Yg9!iOOi zHlv(lk_rhieC8sk)|u@V=;g$uE(r;6vZFBhV-n-#Z9qDoNIEO^$LeOhp>jq3~gvA+>=A!$2rwbD@|R zVCbQULInn-o0A?;=|}A_vRAZ+)W|13O210xq|~Tjd_KGF!^CqHr6WG&qXV-#sllfN zEnT(|KEZeeF1T!Q2v1A+LfW8l#Pb}QzI`NZoC{X7G)QdD!v(#4V;>%0&Hbm5+)WG{px*FBl||HHcFWQE)c& zy!S)o1a!6e0?n?JX=hptz zDu{d~h^i;3!z%b=`_wz?Simj_%c_h>vU$3(=zTLBAYESNvT_U66dH$OoY-e5L>SO) zgL&*wFseA9>XO8Ly12o)NdvD+V93!4RUPtfZzh6Y?hS(M1P4QGa3yxR^W_v3vPq(| z%cuTB;M<{npadte2twXkS0gWM&q~Gc|DdP4QQqG?dB=jYwq&4>J&+1 zgP**gKpfK~teWKg`4{GNexMK1#XvX^HHa2zSCwIP)jWpx2vB6vBh29_V8%H1wo(JY zzk)Dy)qQ%24T4y24Lsh0GoKL^q?5dZL+7@u%?ZzCgI~`R;w6g7);6?5{c$ymgI!Xy z6Q$dnE%Bz*ZC_6$??>9Yor@FWhPY+Owl%!mCPgDCtU5)jzz^3?zbu=B&4Bxr+V>tT zF5S;Z$+ru-r8_x9fx2OAJ0a?um6RU<0tTzUDD1v_9l)L0DT_P^WGU4-FV>3t#^}u_ zhZ}kzQ?)(u&ZH(tybQ>okH5iyV}ci;7_On(%l8fkQ~HRxkYglCVi^7_wKFl^5WW(t-=@3Y%`q#laJLDZyi-*gyaB*hjm)A8|a*`jH(%fftCjw|qI zlT3vr3>#0GQc;snX*VT(-gVLH=-zL)z$clVE9n;w!vC3lA2EU^N zMZ;E7Jue#BY6fDrb~cxp^PM#(wAsfLaXBkq9kY+nf}5uP7Y~Bp5sxSRQx{PUBDdodUZ%!0qPkl$pZ#akX9Fa@rm85!}`RmdO!o09Dk zG$F__VYhO~_=G-z|5{!BarIr=Egoj2n?f>1@2_JVb>o^8R*!1}aR9Wj|8dab>rIIBe^LLwm+Ym0(RKV}uGhK(O4!Os3Bw`Jb|vCMRtmV z9}AY{NT-RI!#gaYKj32lfHLn;V&jB)kAA@tuA1q?*?-z#doL>h&~nrDCWiIQVI)8{p4@-aoeVO&>S`I=-F(fL-f|u=E7GMlEC6JZZjRm`E?rWy?%_S3qkW93-T&m7#;#es; zC(UCHi`*tUJRb3{;YqoI^sq6+sR?KdF`bo`N_=vpG7c=Xh$MF+!d{B1tU%y%c|J(s z*6P6e=s#(T>*I1P7BO>YWFedY`2%J5>^hHxE@RqkP`olgh${$WHC*O&(3;-&%}pqO zW4%DJ5ub+gM;`_D*B`Q(-bZnMw-3y^YxQdeJw*)=Iq#!4ryt+Bm43>ig4my9YfHfG zS+Oi#=E8-%Kp(Y##PC3mj7e(PwgN0!cu6o#B!dP*Q z8cl%_)e3bDRTr54 zrNE{nMGjngmg`wxsFK7GJVuvFDPbSC;uy;U!Vcruqq`^7k{D-qG|S1$kS9`M%!$ij zmQuY;6IwUMO+VCw63wWD)nT6`-d33>%i-4xVkOH7$q6M>Fs_4U9%HM2gIJAPIZ+RM zzy~YHrjwh;T{0YNe)-}a0IH;nC45|czB z_a}dw<$t(4nP(>~-h3SYM}@4EAANmfCz}9HI*$mX7>{N!IXHQ2G$ak{F^rnrf;d=T zXsltNYj6_O4|YeENi!F5BO644#^rf=@rBOjLGPYOe0Sh(`f7Q`P9GW~`JqiP;nc8X z>Bo(bckH^n^XVXuQr7S8$E+mi$qpskPx5#40iI;? zdaf7RkaP8;TRUpI*3ZX3#y#t%GT&#pEO<03M#wtE(#=?dv2*m1$K-Zg{L!1O$)e_p zlFx3EHFODafhQGUIhUQJ+cZmLQN<&*L>{Qbp!B^9{&I^2WV3v5(=0DZlT((4lY&3) z*1S5$y4>W0(zLLl)PbdkSsn$;;szg!DM5gX81PVS7b^NHJFhl_t$?}>KO*DjkpjDV zqL^S|sm7cN)jc<&_e1#T(o;Y5b7sxzBW*Um(yl;*w1pTUByx~>mv&!%itZ?fgvQuC9ThM@MBuahlL`0`|IktM3v8sMz;95 z=^>r~zhH_3=7ecv38btZJ&mVZRW21<8*4EnDllbx2abP;?Vq^Zb8`ylWlrIS6c+tq zJUG)&wS%`au5ez@MVUH6SM;QBJ+@w?-8GJF{EEF-U8i8{;I!@>lVDo?lCT;Vw};M; z5G|$5d#`4XNcFr~%)?NyN=_1wH(+6WTX;2`&naCpIx`{dahZ+nr`PDb#(Xl=V!;sUc5bPwJe=u>7|5K z2o@qIhj^u;&GSnHxdZOZYjt~tBC}F2ipAXLO@g*Jm$#D@RxtRWE1|Rys|E zJPI@-Z)I(=ns7%j1;Uk zQW5f(KL_(GSH3D@^0J4Jyj-&(<}_LB<1hC2^j=Mj=dzxDt^N)x*bkBQP04$|z!0W0 zufmTGWg`~RRN%!K%1U2Skej+A&JMd237D@OE*KX*tX;t)d2Zg^gwe|c4568wfrjLI zt4XP^H$8~}%Bp*X(sF}O-W@^yaKM&eSnYz#Y(!}qIy{>{sXvI#Gq0l)|Nc9%ovMQI zr9l9vIH}tUOQt{rSO8^treMk{cmEnm3$xFZj)dA7sTdkkCJvF2hnF1FnR7AaHe1=} z49F8EU2FjWx><|SG5FAC^E>#QMD1;sR-!;38DSMl+~VP0ZV)*@gZ7ztU9|8DFrbT& zL=Ev!_u#4rKWoMRQ1Z+gg+Fv|dy&YAX>872ns38g&$BsqxS>;`HBZpDkWsv4SUO{| ztZ#`eJb@R>QoRT&bvwqak)m2VfySQ59+&qBF7>Q}BzLjFgyaGQp=p)a{{dr!Bs^E)%|;g#uwEwA=ma1u=vg|za_h48nC$#mY;6DCWe$9#ygl6(C8b5k@%^( zai}aH@XD3+mo0^n8gFC8+6r?qJ#uS*3yEuBvW2t)k|{Sq@f`$tZAH1E&nH;}T0dl{BAF_DKd}9|1!o8wF;;?vp~v8 zLIaly`P+*{O?*{PaOk#kM1C&oqpD-j><;;4+H{DEVTj0@(L%)YMTPk^+MxG^%dVu( z>GvuW(DD)~)xNd0P3QJ<_9b$Uso`e)K_PA2A&aibf*&4Dn=A=Oi5z;7Jut=c9ZFee z2;HD0;a$UffruY-IKSSo;>ODM`m)Gvh;sh}9kgGiml^UpoWO5SH#;o$I~=)+#Wa4W z1@IyF5IJP(0{1$^Y+1D?eX}KCDu9kGm;>VkYo3o@?isy=n;4=z0oNWP*;R#k9KUkQ zYo%GQSw~DcVi*6+p$)?)F_b2zCTgO|S)Nj%cd=BBno-UA>>xHySeQ%iS^nHCD=(f+ zL4n|_Bw3Kt?b}i6e7_q0N7L76St={CbkYxQ$($nwMJclC2UFtl_+-?7)tFwV-FTYc zDte{VUcnP%rEk=Fcs;s28vc%M$g=3~=Zj^J5bGTZM9WK3bHsN{F4f3C(HQ5FV*WzH z+axi#23{z;Q~MIwsSO0*2c3IZfnm^<=yRrkF;$%IAqzqSjT_^|ORSnsOU%q_z>ssw%?fU_$`vZ{7 zg&Tt|mhQ^lV6)_fjV|E?=^Q~Whm>323S1z&Jz_=5>fVDpPxxz3Oq4*ERhjfM4!(yb zp{~~=2#IO-HIFwUvX)J%8z~Cx8ku*B{da zKf*_qI#yHUOjGLhMgoWm$UZMB)PFPYoCLoOOA24%YM_3}V~xWl6iW=L|Hh*N6QVDrC#$ z9o|+6xvd{buSK@NiZ6~uo*bKvZG~xkhp06mjB%7}uZ{o?a4VKk6MYzG?@8V)>8DA$ zxMFzphnRPH$zP9eWE1o!qPr4AxTy^#sg-)^_cUVTL{FtX$>%2?o5Iroat@Dk0uf=f zmnx}$nLE5cd{2o`94@>ojmW@*3Z20z@VfO|QUdn~dMFwP!9m+<4C+B|#bOvaw%nb3 z_OeP_HWi>Ar62eMkm9rzu}#hw4o~?~Z!p!Ky&_zBGK%@rX}B8$dam!2D-{e55gepK z7U=z@;cq@hyS&S;>o>ZM)=PV}*$wCZ=o8tYHXgB%93o@OEE#eYd?~t+=fYXs*E;I} zlSU6!N|PDEA>VPeSz_rGh^djl*bp9o!;9&! z@~@E*8o2%vx%v(?rY{Z5r7X&ac20OnDDH{ifu$oRHg!@jUVUqyM5|7ItfnU1A8J^0 zY()7RcH#ZuU(5PGj6D^z1VLZg{AHD0v`GMm0aBiuqga`-RQ>tFsYHVYv(3!w z-=QLVOd1ZNW(~e|#Y`=X@EqE$C-n#TyTsuzAW$XqAXgQcvr$D+w&w-s5sz~uPf>}= zUgtbUgeLP$1Aj9T-7=x&NiM{y#HQ#J%hLeUpM8er!2SZNEvO)Kmr>o{`lMR^$CCSu zKBhBR?4gMkD2Zv`%~;u|`)S#2%>><_h*}mk)0dXL#F=3s=oMv?tpjqy)bxP0YeJq= z6l?nR8b5OxNe}EY1|&cbwHX1CPnhi>1Rs-Tfx39lXpB1oK1_(|=$nRpzm~I7&NU*x z{HevbqUJxnYbYG}D~MV!P0;b|$y1D!cs3eK;Af>s9I29_z?y|+)B@1}LeOaXHQ(eA zH6i93>#adtIJnZ5+=GtXHD?QHxDvFq$=?=9;nYV)Bt|VCe8ny6ed(119j6jt-Vn`F zHlYVGHT^U8Wt4j_W7NRm-jmtDT?1jOO-dUpbpv7DFdJm%S{`A+p`n-Mz4wwK-v{Ao zJ}|Z6gIk>!7%f+_uM}-gjD1W1=e0Tfz^Ongb=$`WS`7VsF6uBJ?xj#-rtRG`fjmnK zK>Rdb(enjnH-j#SAG&amf^SiyTd;~YR7RUX?nS0NY3QvT250WalYrG%t4Ec;&NQ!E z>3H>7S2Ieqx&a6JjZE}Dh*o*o%8}1gE#1y*Uq#qy!028oMZG|N-H!HndY|A7?NP#& z0Hl9D7S~LiAslXsN>|Zvp)=$GP=&ta)wGA9yaT~zY zr)YxRZbPu(Mj)yuf6W9UIe*n};Xa>8MKH)l5PVmmD;lesWwLseIai%P?WO zm8mlTDw?LiRjXA{;4wDgx9Y@m>0hj!T?yq6hXAlaB`7qh->tTI2l}3z>Qw-pTaQ9d zCNytpgM><^qV1G^;EM~sY4)1v4jSO;szr#Z>N{r~rU|k*+I!pCX%RP$llZ-kXm#;w z?ruKdzJ6@#0*^gO9lueGV(W~vbg|I88fExi9CnU%FQhgOSOY6#GukD%JYHXv{Pv8% zR8wUx8%rdR?l7$zjqDfmrl=!6@hcmDa^`AQtsj(U)P5;Y6ibJyad5%$1ub?y#x~sF zgWxFIewe6QbGIFbqre<`g$9ef4!shO~>rN`GROW4e-~6{P8;1j0-IoN-m){7}y9AT>~4GsBhW`9>gO zjJG>kTIy{gIR~bUB)~%piyprr8bV;yRivz!h8XgtGlg(6-MGQW2c^EO+RUYJ7p|HO6#N6zaPcgc|SZA zLN3yeud`XU`;IqBCc+{DTy#zhk#vF1n;Thr(j!*`yeRh_mhCBy+8i~10B}WBQI}t; zeK4YbK$j*(xN<|a@T~-^@v|u&foWwaC2FJ2-%IOqK(td~-qp&zFlkrlWBSS1sHIQn z*=;SBA9P_Xq8#waJ;D$f{`0)yp4oHRPy2>J_?d%7TTSdk{1NY7X|>{B`xJokLlil> zkTV;5W%h56X*^Npj_c0#VM!Lt?$I<$KYt*61s0-x~glSoE6ake# z;&~r-SEmn|YEY8}*ph}l9wZap12sg^o>T6%;d4=dND^W7Q3p(wR%7cTe_sEH5RGMg z_;!mnkSVSU%!@l;S(8Nin8Ljp1{+ts{ei_U@^ z6_(Q;Z`%&SRB;P5v5em2AlSIeP@<%->4!rDL0^BR9I2Hf5=dLhA4L@F5g+VS8U`r0dyAipnc$Y5oh!Fod1BJt}54epy4RW;I{>E?7lp;{zsVYw#+?Em# zwf8sH@IK_2Cc=CH+%fMZ0HdeVwz9Zk=Z>Ah)GQaRCKs^77dSfzuFXMPCz)uF1(6LL z7;#{ByU7^Lw+m1&gPezJUWg}uYS%CP(5O8$zmg{7+ENvxi6jpxtwfgacBec}n-hv_6S}AVx zZe~Lwmt9i$P_#H+ffO-M&Wezvbc!8ZVP%O@j^-{^c9Cm2B5#H+ZmGT0>31V^Tv!EZ z>Z)motc-g?hz=slEmKFG?9Wm~M6#*!+G}Q<;fHY37P(t!nY;m?5zGwMj@G6v<$;f` zlfWcn=#*zmu`wdud-Z<0ft-_t&tQw7?98Yy&+Y4n{VesZm=MRIGlFmQ_}SL)g^dwU z-ZI6*|5S=XW^C&m%^sp--gP5LdJx?8UE{CX5>#;^uEk*+XBm|-*KQNxC>6MLR|9mK!4V#RvEfSMG( zmqJLnu}9_46E<#hn3VlVA2&nlNqvkcZ=i`Q(hwoUL(84o3%$>Kuvr8*xG>m0@2C8E zV;d2fzgVvNN1WZ`Fm7OyA2KdjdJQ5R;O PlfBI1Wa%)DGbYlJ) z0_GNeksPW@ZihIaIDShvBxtSHjh;rEfP7yko6sT{;)BE8pjp#UiAQdQh`LHyVo$&d zlvVWGN*DK-xe{E$`?Na$0J?XVPWaLAcI7~DZk2L5c1J*T8tb|LuMA-iLqK20EgAc$ z`lo8!V#P;Ozfv+msBPsCS)zg22M7}CKI*+#4WjTBi$!X*<(UcuNsTlD*>z$i!MF~^ zL(=OnUuG%mV)U6XVqq|4UBza#T#In$fa_0qj)gUhqn_DkXM3rPvfR)BtIFCQVr3$N z-htne;=rrQhp+mdj`1Ki%i{5o^d);N=iZufp>H*paS^shP6FMecP=f+U!e(?3&vX$ zlK`p5<41F)07&iZn)Y;z31tN6Fd!rtC7@oZi-gPT(hy9Jkw|ijv4r_WE3+$k>MNsy z3BTv&K?}ysTO$oG^*;bC&t}qz13QFp^d7OCHL5z93~^86=ztTTmXhuZRsEfHY90yv zokRCD^ieMimws_@L(6bF~{k zB>Oh?TciBG95CqvXDvT4Wgum&dNRwwf%F~9u(D`bZSJ$0!`HM)=#li}GsI6n8ndA+ z8)ZPFPw?_<*%z|vXf{&U)NSp~{jXmjzpUwN$U%-X@VKJ!JqCXJI~LQQfC%y}w*;i% zS!L)FFi&y_l&?XAa>nhD5L5^nE1jq8Cq%kMz6(}Fcz1M0q-K*YI~~O$OAYs9(KJD{ z){r8bdAK+n+zXo58T1bJSq>)bO;sPy2CS?0YFc7wQYcAAo5NhYv9sLrw!n+H!Z-&b zgs#@&9L+s`)~C?azv^s|5Ba3RCgua`Ar^Er%h)?0v{jKyp{e{snqxMl!duEEl(7@9 z?S8`$z2Ie#2b5jRAWuWW(pFed`ET4EZkl{#_A0QJuN9)m?iQr9lCJ(Z@)!4G$j^YM z(Vx=L3-+p+XC)rbQS$X)l{k*$@-ql6bYu3-JNj%U+B&o1+w+~z-RS38I`_i=0F=w0 zXA_aLm=aSHq9(@6`JTsxDS4HamTF(s#0~LFl+KXd|J}TK-Si1#c$pu~AWvk=%SE(4 ziE}y+l2oB8(763}ELOZ{5Kn2uCn)kkbC!v1xC{he2rxenbQVr+Yw+sHK?yAvq%XI` zoVH=ev}$&RHM)?`T9LBzfJF*dlHB8F?Mb_pZ~~w(bs3Onn}_tdt> z{K=P$M2TH43Rv`&+0gp$m;cKl&`hTEVI2<_b}9I)>Rw&;@$2$G>-4{tYJlXorGMVA z;4|&}HDdYadD}BecYSru+Oxp_dVy9+q?$hYFo3=MSMqg4-)Z}6dHc#c>HcO_{Sf}% ze%#Lby3A3)73MF8c(GdyclFh71o`Y=Hu5DqLib77Dy;~AI?R)iY9ptJtcPoMl3dtH zkJ{Oji$t^js{0g8A04zO3cd=!W9LBMC~yQEp1%DvcKx#*Bl7-lU|)5+iyRV26zGy0 zZ^6G1vr7KP0FP2olG^-Qp~ehpvB2$Stv?A{m4zF?eZb<*EPv&;G=m;G3Qg<`*Ip1b z%4JQus*=Uns^8PV+8!1VfR<-nzGCNdwl}{Yhh@bo1t*Zy>Y+Kb#STUF#+yuZm(blv z6ml9L`jj}H2oy(qDxSIE3|k_kQv)kE`dcL&beR!>;wp?lE6J6;82m|ZS_o)Kn-b7K zH5>I!Uw2KiR(z{l;;AwMyuEFHjPydg8MBg7m>x)!BUK|?X|v<@?ZW~N9IPRPx0 zoBP{JbguMy%7l($IS`f@xw}0vF-Gk=#+ZgSPyV^g4!Vg- z&opvP>9_NIso&59;N~w3+C=@nrMgR6tVIHotf3sx7|b-116~5uUDza;M!{Mm8YIK8`Fr@rK0WY} zWBdohJNxOeGcCaX+gMkZ6S%bcFKCr$x73oz*gaU;no+;6l09azA)Bzk_GkKkzX)T%yJIf4V^ukVZCA@9C2PNaK7Re-;&rb2%fP+o+|Uc+QOs)ZO&7xa;PKL# z;9{Sf?2Y$DDCw0o41Axu@>pz%&?qhh^dYr(vM}u%#ss?FUqT zg(H%nd(06OI9CubSf$)ydWYN#X9P{Ji5@17vCsSM`b$o^&otSL8$RpoV9!ah=COKG8cM?5a+9_4l9@X`R|Tj2x?MFD+RKv z3Uu-Vs67giLql82^OrX$bKFTW-e!UIhb%T~IGhXJYG^(|Sgh_$Js4QaA0L7~>ok5_ zDG~6qS;*SjjQB!MsvtS*YwYiKoir~lwgKQ{RO*V-5|9>M7!IkD9p!`kG{C}zOv z!?3cz;K>f{DViR?>wfJ`TQ&SrYkLTs2*Gb?gB!73A~8AlI^;qZ_C9(+LU7lk^iFPB zEiSqmLk9X`a`X39xn~>PDz+?efGfHLuBh-MT$Hq}^ZWusaTDB_cwkH%LqRYY69>S- zs?*j>Dw4vh@?^5%AT&r8I!jyHWvNR1S~%3gLPd9yl$0hI7sYLYo=h;EAS8s^EpW>) zMa7g!j(bfv3Z*6p0UG_crPNz_{V{;*i@)Lp#mZ@#4R0>LNfO$2C4ANXjhqVy0CShe zy*sN7?j>FquMfa$trlH4{o~pn>5J*oH;kP$5{Cs|-355M5TExy0@c&Fn3^@XD)GRE z49crC2_kEwqk$O7HbWl0Xb^={!v?=imr79G>D7ThOT(YG5sVB*YY=}D+NqTcBen`7IXV3n~QJ)!3x!iUtAf(7)!{#@Y(V+GfEqZl4; zBPmAAzu4gb_anI#amSf%UDjb@ZU%}jz3X5-sE(L1l^Hx_qq_s=*PyEuiK05UUrt+ zci%JqeUd-Qd*I)h0ztUoKEfa@DFF@cnWoOozyd``d2j>pn{Ep{hvZ3!Nt8PR*Lkqa zAjx>(i(u+3ki#S4fqW}egQK6nDT)M&Dy#K9pQ7A70-bP^`@#n*+r?swW&DC~92++%xepdJ0Be-;k%#t#YU0i74Hi~9u-+%md5K$#^^m}? ziN8lI`0xQ9wZ0sT$4*l+V;n^GS-8$yCIxJJe7`c94#;wqKST&{cX+2VZi4O(;Wi`-ct&BreD8{SyR|>gEmI<5mJu`srMy<96$Q zqs?-DzZus|k%+t;1JzHugXFOd%B7^J{u&b6o-OU&?0@5Z8t%*OB|`g*W_fSjv;t;h z5F&)!=Pq7nZGUVFT2F+9BcEbp1$mBESf}HgEr4Caf;ham15FcvYlrFP)M#5F4Ba7i zK62aG6dBjxraDbSuC*oY$X4Q(IoY9lwNa*=gSzSw{S^ZfP&E?KGVxOF)4*de_b*6K zyBl?f=g3i%Ks4Htm#_!pPjQ8Mhf>YT8*-^n-BMhvymQI&=bvKu9?%H}2j=9X5>MFG zBtE|1uih6a9|4Q%D@*VB`ncpg=)6PDDSaA!J-BKXCST^^{$m{0oJ#Uj0{Z zV;!NamxCwT#FRZv{V||YNb8n$_rwJp5n2Bqk-TKUk z+YK81h3u&K_0e+p`Lkv9uVpp%Yjh>RQBW&{qRE$c2+#yC7Xr7z{*qn-&`RoK^t zN4GvG58C2_eRt?+IHxJEl{WYaQ=#hPFiDM&WmYB)@fyz3OVfRdl!Oc*Va`Z9ewCnT zSh{JtwNHT+BpRy%pDi}wZY6UOU($IV+pbmIdd8d90mt}DcUI9CdI}~fBHtnTz;i*N z^Lx{$y9K^Pj^jrDEN(Rcb2$2+kF*H#&1*+a?yoReYxlU`g`ZLzneykT{5b@dBJSNC zFOi?lb_*vwudem)F~1R{s1eTeKwu|SEoqT$_xMZnnBS4{*>;O2^1FO^2fXQlETtGU zkWUoP4mtMZg94u_%H|CgqC^IB&JXwqt|7hV@V4&dC+t!TJtj$qFC|d4H=?x+50l3D zXurk3XZ(EMneyq%{o!G8`|J;ZYsdezyY3$Q8|B{O&rWNGMz!$~r0epN4RhywS-bJ& zT+Xl5^=ceUht^<37yENI{}uax-AjM)?8A=+-n0zi+fVgUdT~K9i=YY1kyC=zHHFge z>E!-X3bMM}V{ixsI&UnlddT+voR6`l?VZx4T7j|6Sv1-ZWm!_tfX0f2iY+hsXaBFS+;%QHb5HKoRZRaA5gE!94MIa=QHhXsysw^DYa?3o(p%LasMe1JeR3H@!y11pmjYN zHN8v)l`?PIUcAAQ@5?{q6_6yTiv(13X0EL!1XaS<*J`T_yl0U=k_`^L+feYK@W4dR z%j1ZAK~J~?E2^pdwaTs&{@Rbu$^P7XHWa+~rP&kn@-VPp(8=zW-M?etkz30JAL6}H zXkVa{WEVW*91ks_7~Mc9>PWJ@0l~{;7En}t4E4i~BMmxXRe8eHY%jXvj^TgB6XJls z5rjbGZAS(=s=C4>gkhfvKFYzbM&#L-s~6NmC0Aw>fsmT-BE~w1=%a|HhLTGN>jV;tczM zV^ZhllzH&6O84BLrL~0u|GP){F{$h3SiJA&DT_1?S(JE&74jo0Q-NOY-*zpLv0VIw z+K=f!hWxz0s*8tQrQu*@?#4@jBj8pD8YGGr3yZCG4$K7kHiyt>Jo!0&r147OOB86z z*Qev-@0tdvIO!A}VOUG(>?NU~IMb++so5lQQK3DqYrVcCFDVjnfyuZv*);_%SLlLm zb4M(Gf`s!~&3UigIQT36{4WYV*ezlPldTGU(WISb?jk|1i*^huNJl8e3%kT5@!Q3R zbxqSq9))1lQ6l$xg{VzRdtBE*Jj(Vg>+8bO=&3F$h@bn(`QjAOn{v7OB|`VF<`~BbDv*mA?9$8?G}#@o%qI{{W+)5M~Ltd zro6iJVXC!{@sWVKcKPnvLF(ITY>XfrO1CN@h#qT;a!1VV5qWo^^9LE_srF(t-(h=w zJd6>1u5b=i5XCT%hu*=BP#RgiDOT25`YGD>w??QYC+QDyQC^I$R^fDGkHy={ zlat+GIs!D17lTIkAHZbzeK&*K+W0Dmt^WY#NhwE&NSJ&cI{)Q^0rDm0;rs*OA@sis zSJd?cl?Uc4ypXZphqi&}En{*uv|j@xQ>uAv5_a0AxU(7Tf8>t8___dUnXn?i5Bmth7h zNL)EMN?mGUi(QCahKjRRasYsBxe7-RC^iU>NqXvTgUg%gHgskSm_i;WAhz44!Rl_7 z2q&E^3PpvyS$3KigD`d zw}^(w=#ve4M?B|o?mF)W35l-7LaAXbVmt+=})xOxutcW1PR(0w#QP) zi~uYaZseqL6XqBq-}ihEZ>iG^!^D= z`*i$UV9Q>edlnlOzOJGc2!fkHBcZS%GpMW*84P-e3>rNac3yNYv4e4Ia7EdG>#OU^ z{l@z%2#$r=8t&`KG1b*tda~04KRuWJ%8))^$h>)i-(4)^yIOcu3W(TTU0!i`1^xHM z|IU5v!?jt*$`Qcec}+r z<^QT)^-tvIe_7D_?;8TZbzEU^9rxc5*}n&h@g#fOl~Bh&JBsW+ILk;PnXNwO2=F^-3``1kbS!cX zF=H4?Hc@d^Y&B;pPW2!h6NzA#yq-V40^lJaAs|Eme*kW+m{cawPocn~Iup0-LWMu0 zvkpytWL~j2X9lhlo@h+|^^Wb&&tga;wD!num4A>2Q5;%G;*f1EeAyfmqKYg;cnNq^ zv|SZQ2qbWWH7P%|kca%)qKPJfqS&=w3c1FAA|41CBZE`wdRp@=x!VPB_rg#1!pZU_ z(3CS&=%vR#cOS`7s!BAaQkm3dlvEd1cEP5lJ1&_<4;%#&_{?#MNYA({ zb0~T0M>Ll;vOF=Mb}eyYxG`a%9WnESOgkFYzS+Xi zCT2eL)en2guF`7`iVFu+$-4xI`~kpn*4|vNX88J2LOW>xGPJW1?ZrdL(Uad0X|{UD zfOP|sNNq$Vge?^0U&BA^DUL0;>*QNLBJ=MIhMmBx^y|dMD9&DGXQWkQMB2i|SfUO( zhN|UjP~1ianBX?5H72NEl=9ux-8}~(2w+x{pbEx^wNo}e+Mu_Z)$`tIlelI!>ZsfH z*Pl59j&9}AWW$oCH=z$5--J)lW`+7;*aB^tjXj=_OfZc6f^M+p;9y$E>Cm*lvtK>P ztZ8C5PtGBKJ|Zmk8E5uGUB9Sjq<86IqO39LE-}8xC%g<&k(22^t^eqXd0P#SZLfFRYYw4R$_;teG&E? z`YC)RxP})R%0F!QLC2&WS<%;;2-3pp%0F$2Lpq@$fiD;9$3QSsee99qQZI%b@ErV& zpJ8g^YxPOQeeh8;MGy3M-j=2p%)VwG^?5vzl8`*iHMtdIc1Iq%=(|&QKy=R^owhk} z^P;D%NrQcXKDTj9hZVY2jtdj{x)X)VgGh%RF*=cNtK~?TQjlSL!bMKy3f#= zVp3uqzca0@XaC~#vB;$Gv~M>~F)&I;i)No% zXQAbUW9dWi_hoE+O&sR3#kM;#1tQGxX_n+z+pFbN|1j2X{JR1OX+CXJtTyn{9gw8{ zr6u`$E1IZArsvq=Dw&zE@dcW)3pl~|;JMVtf|x-+OkoD+LMLW#)0;qzOb;6I9-wi$ zx^A{-3f&NGDQU+P+%IdT7zW}OMWYWP!XwBl{lYIGv9!^HXh)<>b3`DHl`DP z&?fV4!ockDRnXgmI+;&jAU|l8e&>a%c3D>cc_JYkhv+j0w!oX%uo{OSsPn6Z-#?c$ zT$ZK2uwy&U(@CCa&yCj&jmT=}b}gay=cnzigm9`KYsZm+Ee^iZrVS1UH{14!Co)Z}9g9cwRTiEKQ@S;7&EJ4t-s=+z0;{E|Fno zxSHw~^&HE0t}8q=`!5iU1gl^+|ICtVzx2BV1Hmm4KW^^T^6IA_1~M8bhqTw~fz+mZ zOB>{!1IM2p>(rwDr`KK zG^B;eMkXhV8_~T}?Im$mM@R^IZQa?-?NXwuh)NrAc?-VN|<<2 z{%M3Z4|G;K$Ll?SNu$L0KZ<(GfVR3|T^QHm#T|+iiWesYhXTc&qABj~P^7pPcbDL< z#UVg&ifeIq*M51=`R=_xlf8e;S~F|*teI!#u_DszWDq>Ge3bIv+xX1yK@qWq*I@0o zAjvAj3i;J>KhjxR0}-l-MYl(PQ9P@zyo&IP%G+Wq(-wOOoZS`tiYMsZ*M5g?{Cmtc znUcxJ<|cbEW{>N+akn#F6Dg*3_6(oF+Ln&OHKo+uD^}HJi(Im;LycYeB}AXFo!WZM z3e=PMB{s|MlTD4tBf1t4hnrpqIT>JgIDror^D8KT1#|k5#BOlFNiDX%SBGLth}56E zZ5drN6-50i{qa|p)yKx*p7ojS-Rhp}5UPYEf=^&&fYNSQa)HyEL5+^5-tyBmp1llt zxWFXyX#-+_qw}7StO4}~J}M72(=_cC(_WN3lg?eaM5_Lt2%YvgdV0dc%ZTM#BP-C?}Qrbv91hlMkQ7P{>-a!@b z6}~O2njQ|9i=2fa3?ZK#`fVss?COvymWQRljGC4#AlWB1qC6(Q5+QyEo@H(8@hG!0 zL8I@rgI`GEHxS>%ul&23gMhXev7q_{|GeNBY)<488-i}YIxzE62=Yx}Z9Xf}jJB~0 z=Cx7Yt~)Y@P?ZFbT3n_CkVwY*y_>5*>_9+EQFV?1hq0{3aaES@EL2)AH`K8-0vnwt zzrg5XgEV!-mz6@`v(9+QRjX?Yu^Uuv%n#_d4~<7K9n0ABPMf>9uySc7xs*pw&J;*& z2HsH$_VyS{2$6g_FgYgln17F8qXs1!d<<#X+;LIo5+3wNoPjIMVzRgo`N3zxxF6`# z_$XE1VQ;s@3ZaUp*Bp~=&HYqC6RRwcs=w-+CsJ2W(d+YZml&3wXNz2W=c6gqA3reh z4-O>elCtIGVuH;BUM7ujS;Wv2jIc9rUQE`7blioior)*THX{yV8bo?s>uMfaF5lsr z^1Cl{Wx=;%4^(1b^tlQuaaE$kQX9R+?wS;U)73!KHWHX&b>@KAoTduF>U7h)QD&x z{GVF;Wo2w6`-JTA3Mc4@5AmA}hl=>+s^=(4#OlnjdR|1Qx`)jHSxg~)@MPSpN{H(k zZYXB@aA}ViLN3v|k70it03_Ntolj_`rpCMX!#XhvXO5n%gvXT@kx2=rgeYk|qKJHEs($|lf*@F^7mej8!(n1ake78*_{;=Rh8AjTgzI^`X;eQ}e47lMNJ_6)+WOP9Pbw$GQ^V}#%!!~B@;SaElWaO| zylEkDiZi(l+z86Ocr)n9(lCo4&UcfLeKfdBkX4KZzK zhD^6D-L74PmBpg@>{u;Bxa62LC??&kq`$8&Q4v?{Gw;d3E#6-jzS7Fgx8f#L{3B9x zQH7alyDfu=0rP#_n=GF!&Z~4{a_o@7ia>YoT$DD4`-K=?{6b?Pp@@{*7UVwGikKRk zY%q$73^aYll3&+Op4e1VzW$N~p>loTH#0>E^UQg#y{6l!EE(#29=Ri+(3rOyHpaAHpYc(@n?G6 zn8{|bms{Gwmu=CB>v5a9_lX#?^kJc*be}abK8vudq`M=NQJS;S#^GI{z4G3t=B9lb zG8L!JhZ=^0Y=R8r^*&E6xPRO-GzIOj_1BKdU;5U5r?iAZ1Dvm~NR{Jd&2D+Rr>4RM zR?>sLXL@))HL;R|sOgR;u_Tj*`t{z-_soirgwu{&HeeVTEK)l&b1sQ?yaTN;%CHot z)x<}RBl_=`2)rzv(N(dP^$Kf@%FBM|8ZU5qV@}R1>Hw zIyj73nCLf=?a`loJ@nVA_eLqxqYUF6da^;3xxc$#d%0jCdGZvge#XQrELf~t0%fFS zq-b9f8!GV&Uk7~2qnjs@jC++-|D=}{6Y=6K1W_UY*Br5{C@BMT4YyRuL*wEPw2o1W|zjSW#9#i$z?AGsK7Dyr0!H%D(fnl zrLzuOYsVc;VfiSSqi|+F5TcXg1_^VoIP`Osu^YpEt(@t}JS0IPyM12y2e(Q zzPyc<;=;EiGaIU&XdF|`Hy+3;odWO7S*$!xWyID%AjBCDK8`Pg);g_V7y#5^EmWg=QJS*G5PTN`sM`Fmec`> zB}C$P^pLdqK3THm!_Z7XS^W3bBN`}G!Mh~x{dYYPFOi!ga?aXixI1kJOoVa7lyN#v zje_nxykTk?t*9*Q|$dbDE)0 z#qzc%eKC6NjRdxGrC_Ldi@_bDBc`W(4;(S27fhbT^$BKWZ@0%#|Na~n5D<{1Xk;|g zi7^d!-J@GSo@bZ4#r+nFiaO8#++ga2W+#4(EgzduPjVCZsdfN@I1Yzc+UinoRXpUG z$w?U#7og)>)H_QW+e7J}RnVe}EtKXIm!CW2wW=!|mOJFh6$cI`^;6WFb*0*H9F$Xs zh5x&#opujA)dktS6|EuMK>%=7+LY_*dYG(t-*^-6$6(2*9ZVjA1QMn|x})YwqI3OQt; zs6q?F^)COEk;F8jpCslwiVx?DO$c%{aiJ@hOxW5E7or5UDnRP3ggj#-!aMw1S45^z zmVpIEjvAEGPguAV)|t{%G{HV&OquSf5U)`;U)-i+Urcd=E-tCVdvgbAJFhdpMSHge zhqjOCEdz@=14z+-*ql|nBQfV>hJiEo=(LmyXmpwr=1~@NLcIsw;UxQ3K1doFNW{D$ z9l=7=SMk3iH7Kcc(_>KKt`iS`BU^qsI!W}oQ20)0LUP+3GNtV5{l0G)vjflfctzDZ zqWUjUI#h6O$X%hRC^%mZ%x|V_Bn%XAGS6Gi)Q8XP9cn2bcoK=l>luM?WgdQjYGE83 z8n#y6dkwbImU`3NO;}9jT{m;)wjn> zGBw!7^I25N2)%I@%y*)_6}%y)L*~BJtPwsbuP{C>1YgO6<6|CVa?bVkU4f12z4kLY zg0iN-yB`TNZ0*M|!nCp%zAO8BsHaTtbA4%9CeK1$;1OM}b9#E5W)CL0s&)t*(BM+0 z`M42&>L;mEcrx3ZfSY<9tNmxJCxH9;5jDzNatiS-xazZB1fC7z8Gl(S-aLIM{&HNJ z-xAUdCzjg@#eiy!i@B+Gymm}e&7yu{EVr~$roB-KP{l9IS(dpe@cu^vFkU%BXS3_T zY2gI{cVA5jICYnZc*X8CbmV zu>KNxKwf)<6JeS=!DxmxJ+QU$B_T?^wS5u-GFym8S4LrENb2C>yMKDAsLPp_E;OeL zQ7O!O6+<*K1rFFoZY%OrZ?;Z8Kpxmo^XWMH^>VCC!n)=I2_BY`Kk79V5;O4=2Fw{m zC=YrYbqf<=kV-q+)m>hHMO^| z*SLk|0lQoQyQl+o%KOADsaLg`Z+RPS!cC}t(fN=xTg5sz%Zh0FicSV^E&_~9tIDdX z2IMlGJdvSe7jAW`&ela9tdD=sKN>js=iv)R#HBYf#Bq@`FQPRZ=We81^k1IrX#sn! zMb&Y7hOZiHHXq%*K1J9;aeT)5las48&-e#9lzCPCKX?DaV|}RRxfM!YO>vRzwwcQz zr!6z7DQ-o{9~}F%1Jn&q(N@t{8hZ$)ur2On(89zOx&c-;uxHl1@sw2~S&;8;qtme8tq=gErFI}R%eJPkeRgN?zuh=#$@FiQDReAFC*qW%I>k$qH z%bDnf9WOR|c!dreNFm|XJyl%WDJIAn1QSZcFfW{FNBI_PV(%=z`UW7E>GXjXH zBY_1&4>9APnofj4&$$ubSEP?Lu9B9U^W2`iGZ%tgwr&Y)zoC?%=nR(;%=#$yJ2*LD z{NTrH4g2Aq=7mN=n$z})xHX~+ud6eikPF3R?H?Ru13Y4(7g1?DhRN34#To{j3wU=g ze@o>It)v!qhg|^SH_V?!DQvd4tWuLY7ci*0`X1KwF|Pl%p=L83JGAgn7=8J2QGunM zF)EQQRy$W8ZWtp zgL!&SAl3)B5B5esC4z`67s4=h>Z@^7xg-Cm z^o+?K`&Q6EI8F+eODf9qcXEi=u!Sblo&OXVSxWN2%yT+3XB8m@(h< z$QJ-@Pzz8_>mHUVFWKh=dxJ4emR_+0OqU`U-Y!dLCi}_(kOYh}{}LQnx-1_Mtx{0C(aLt}vyla$PBi<}Q0_ zWZG;JkQHi*<5-furSdfxdDU{qGMRem#?#3FqX$?V~eYmnd z$Jewf`MVyLka<_tSRAax&-Nfh&>kE8-eP*!F2ZPl%~1OTQIM;TOFerLhik{GntV`z zS{o@_>RSCvefxY}5gB#EDj6f$kM%L3oNjwqJ{@|7?Y8NYj9uz`m5J#LEHtSDTPHOI z-1vfO2aL`S_EqOnjP=*m(2oFh&Q93B#tgYJ&ZzDR3*?gbb-JADxOpCIu;iAK+PwQY zr-7yB7<}e-TD!=;?z^m7n((ocCm#HN$=kEx$Bos7B*=2T5l^pt>$~rf77xh=4NDNa z;%ikKNG`eP0@Pvj3cqDlre8^*8VBQ^c$i9?adI+key|C0U5mk`!3&MlB~TJeDA!DO z$lXLfTnx!WGF7lTD0g(rC_r`B6Oi=GndyM;IJ;U9`b15fF%PKXKXG31sP zB0XS84sNCnsBvqf{X&4sRuBKFec@1dPG<4wyM79{#Js3ZQURA4#bhIUUD6>)NB8re z*{{A0U`E7Y36ECq-b28J4 zs-elHj&7~+>v>h))|}G|YgAdqZAknFn``0x01)-l|lW7#AW_A(*tn}7eS!l#Q3n$9cK-;^no4S?oU|`!L`a}P`H~QBT^mMgx^IWa|U$ zH~MSDqxh7vB>XgU$v7pX^oSxZ@pFRq&;e%4q3E2W}s=BLGg zF9rwCb0%XbxAw`(;zF$4MCQuD!05}4>=8|#&A^hxDKUv(l#2hr}U(E=g(>RDQ52XYbF)-VTK%F^LY?fgxLmYGlL!Tsw(C|}&v z$|XWNT`Z|`e@ex8&)ZOd&a1Q79>~R1DnF=XjK8`~=EF53HCIlMcjK*&Z;AJ$II!&) zRUAi>tCRK?rhAw?(Eo}$R0ZD3IwA!qw9Pak#$TYzgK662wi+67_ZW;nIN5;bBRPTmHiJ6O>gU{=)2}lsGSu&j?brqb0nifq3 z-v(kR45c!*dgrHN*0A8ZHUuN-HUm0Pi3-Ve>GHSvoSl z3Cj-~2QcjdkZw6$@j^#9ZwRi!HttR5Y*3uWB<;1Y5sr7FlGSx=P}5G0<>RrV`>Ri! zVGY)KG%;}vN*Q}oV2iQ`{M?5_+9U0VE9T>C5#J{9mUJ}KCJ9~jVGH*yv6*t?sX zmK*X?x(TEQmU)vN1MzUQatg46924uf-VE#=5@5Td{N?{h^PeaLvyvLC@S=3DPF9z4pN%X>EqD^Y!4bi6i(%_Tm|T6q3A zb{@ZZtp-d5=zgGz$aO*qLteo%)~JTTX9f zIp051lCzUX)ViX4^>A40+#0k)T=9zWmk@1$1X7qe^@JC2_F3m!%WKM`*j_fb* za3RviPd7YQ1eduQUJPD67EaZx|S_Wb1hiUdIOQd&MK ziK>d4Gzq0<&Jt#1FyKcByh$GZk8UvOmIt;9fYkr2m6I=1^>^3{z6R%X7+DuWY9*E|?6v8U_*;J*CKaYn>%pM{Lq(3=4mba@SSgd?nh@xd^TG#(e1 za0mS;H?vkrtijRZ%Co@7g8jnp9%RB%=}x0(@-KB(P*UITFA4rsg)|$j%#}c@wrBHm z+TgsLDx7WLE~;j5exSdx>7Tj@mcZNO;V5HH$|I^!e+jDi$I@+}z?@E&R~Z?&_-kBk6vclxU9(72vY{=?EzM%unWKaxD-*Si<#*&qsgCMzyOcB}|x zE6~cQH>YK+p;t*tTi+*0-j;TcTRkZ6-QTxqzZ=*Z%_+a_yzQ|;&F^pY8_G&IEPZ5N zerc1s0=;4@%LG=!pJFM|SllJLzh{$+4#atDUymYgemtvBZ2$Q6v z7AJ<5d8mngyUpMXll}BSL15_IwNPiOmoBQm;&OVHBwpQP094hO-%dyNh7M(4T(T6a zHhM-Q$_1>wi~{bTarXXaSCyt7CIu;_Ke(WHY|OA$xISTP$qgxeOvp`eP|xRlW;+*g zcTEN@s5#Qis^-^x!y3JupJ?D9g2s_OOJFE0tZ#E6dCGSf9!*q{r@azQ4%VO~z84{Ox=JP%vlph5vmFiQ!GV^K53Dgu9-&id*%=!5DcRQaPI~@RI)tp;FO6b7IVIoC zJAa3j*`NTvD}_452R44eOKZ_-=8Q15&*g-L*P|WEc5Bj zSxs}9OIK|lZeM=L3FA5E7G4w366#w`J#ON5AQKSdImQ22VWbOcf(==HWBBR$3IAoc z>P|VNg?AC|cgXsydnL(S0?c!7!|&oAMnpL=N%=Mv_no4Q321-kJGVEgO`0~K*NpLI zt^92)K7E7b)s$AZbgO{8XRd5Lr_Hcu&bqU!3mNYd`I{YIQmcCdQC}KSB@$M8@F)#v zY~fOCeCHM6@3Pb>IeE2Q3!+7J(Lp5M;?6CXFh{4v*>YMM?{+udA3RL< zltI-74ye=?(wRZl`PmgUvkhJajkV`Q6i_vCS6#BQ9I}DwhXzLU&usWux^9)Qf^=0T zKl8FMTi7rYLIE(%j$=fEOXTigspu@)0sS@7oz@L?$Pc~mCl|`=HC>E3%Y{NGDkywp zvxY}oK6Zi)h#WDFC??gpxCRLwbGp>2%3w%>+4Dc$zaWtMy*rHrLe@p_dn~khBC(+| z9(rEYqfHPpMejHm3Hw1L!&zy%Dl`GnRqu=rJ*CGWm^Q)LYa?< zlk<#bcNJV`bpsXk&g}NAUW)!>1v%bJ!Kq-dCR|J+PGZxwC;!FPMgBhfxO`Tf$nH{{ z1ufL=vH3sq1gkwuz4^-^>1y0cIBfCV9FyBymvhDZJ{tI&EikYS z>=`ZJ30tT8#SQDNSjo^%u?c9nUe#6Um!)iKT16O2vlA-g!;XTkRh51?^D4cQ1_$lY z8IjQZ%PdI^*DZ=lzapb7h@OfiHt)noso2`2d5&(*>+VLzeS)*< z@Dy7YKp@*^Py0+NYgI^v>6ZwPng;8}mN_Q*qe7>;xFDL*4~|=UxVa%0?c}{oPv{|6 z*qIr)y*6y&-AVcHQxId26>Y1}ydSH)(x*MxC-C&NirINQ-P5sA)z*DFd`0;M;zrd) zEz>DUh;Z`{E-)|NonG%7T)+;Rnl~DY%cgK>ZkXj_Gl!0~(IRFl-l6;zttKe4&*d@^~m=eEtU+pWypO}i0CZ5FqUSYh8~o{oif)8OsH z?^t|?M00eucy&88{P=N1k?(QL$qgo8yiq4_L6}Yl_o#TO-&dUOqW@a0wVYBayCeOz z8k28W`9>5=OHNi1Mg(IOsLN6cQ|l0TB)LJH;ZEN1Emphy+_md{3? z5b4fGSB6>&)+VPqRchhp8prCVI!6xq<$=E?NNSyliYuJNf5^4)vuQWxsYQ*#Inu83 zNIM>f@yCg+pPxqERG?OV1HajLUy$ivjD;7ay3?Vd-C>3LnVmoA?I|8dLg*Xm524x5 zN-q;Ho)PUCELtQk$=|oRSpG@|O1jh}jSjU?-g!&A)mo0SvhGqikoE{fDNxki#5yJ` zsoLMQ_4JHG+zjhDR%9S-UmBZVOAuvFgBHE02JO*%Q|YPk^6(W-C~$?i|~k`U9xuC>2Oxt*sp;+wm=RCM99GcQP$U z6uka7cGDYDmpPS^d`yZQY>J>-JUWnNs8YItzq8Ru19QVN9xzxnWB`!uAB7wx>9D*@ zC~-v)ZCSlptSm{^Sw?mgOQ5D2we}#wg zwp*eB0F+*RVtdAo1mH;@{M$d?;k$}%L>#!0fEX`v>@slHB{AtiNDyD;t{;il0)t?SWk$; za+3^ew`BkfX7(fSs976TcE4pM)UxPvv(+gT5?a!Fb-*JT~p?)6W&}H^%bVe_5nDd!lOahm3 z(H+!+w@8*WbI*@~mX`KVG32$BZjg8HgFa$roI;jL$&@5cb0VMhxjQb($=(DR>ODc0 z;eq))SopPblx5rQ%%A$HS0c7S^V0yjTlV@bH)Ta*o=AxL06*n?U2({H`qf-qPe+Io zWxD)D>68!aOL1b0cj=VVQv#)AjEq{T?6juDj%H`^T729@L)qd+*iN5=Q&uqYluilx zdn)HJ^cxnRedi{q+pzm<2h@+Cc7WipXC_ zVyS+si!{%Y-XY_uoN=3H^u%R`*oxF;+sL2oQdKIp1O9w(LErgS3^m@#%C#iSdz7tN zV9BsqV-Hv-$Bvz;D3OJn$Ge8!U8J{$CTp{GKDxz!Ml|}r@<_;Fw{sV>3{cC`L-lm9 z;JL2ZhD3YAgvnWcHDB@gN3Q)@*7?FTz4TC~-PKam-8k)~JvIbw?r-L#@i%qEvh0D| zq36+A&MKEvnwU(j>iHPWv9)oBSlPiRO*`rIC@hEa+;pJYHF?5l999p(h|ePGmjst6!pJud#`E7YZ>pB=Gi6q_Mm|9w^rOu$T5IEfy_CZucK-h94rIqR5^x`8RZZ z+4yiiPZ9W+cG%JuH2dg>_6`#(!e@5CL!m|;CG%`~b~zf&6epPvE~>h8R&z@zx>zYL zPezGaPMC~y{AIaL6%+pva9ZoWqg9+?x2qZVqdw!KvPHy6UN5HCU)j~CM#MB{{P^{>{I+o?Om&N zw)Jpropn-TLs=2W0!)S%Dx#7e#s?Ddm$51zDek%Ij)t28g>Yv*)0j9J$qdh=QL~zK zzl9y|@*FV-Cn=tQiOkW|)Q&F%>eAjgLA)*gwv)E#NnHlPV+Ec*w)o$tu}gHt~h zc1f$|Iuu@SKFOxLVC-P2(f%m3 zhMMG%)m4hGW zX8E?LPYN!oc;WztrDokDyjJT=+cXU z6mGeMv67>GQ%<%hr+h+J6b z(y)6KDBE;^YFJH~s%=3?Z~krUj>x}TdElh$Dd==KCm{*U;vYJ!T?unPL;i`6n%(fL zw91lKpYQyo!H^0l$lXHw_W_#Srg3+v+UjhT0QxFysr-LM#bWx6PBE;hNf#tkw?v)K zB7J#xFN&UmD_uXNEZ$z6wWqMDos5!nq}Z1pF6s=?{msD>gM$|a5&!Jiy?i2D#_1-P zEiLmm&#-N4WhLkC8t#bGa>fOLYX9o>%o15?2Nw;GRtbdOvyavHkH$Yr@RN1IOhrnI zbxf+oLU!+{&aKx%?%;>BXhyc!Uni)puFOKZ%x`nXuZ_Rv*taQvDgWu$T~^~TQM_+^UEjq^gCe1)T#vzt&~1co?G_jlIX8FgOkK};RPBdb~F z_9QjPxKkdVKgbI;7-|TqKoD@|B!>SrmtxQ1cg(l%R(eV%^mETNJt#}q$tzVtu- zJvgKKqjk4Z*}*-E(vFjDy=$qxm#)<%n|`guu3M6#gmr#|5}h=-y>%yYgffwj!t!?t~$PomM;&Xbt;a($m1F8 z2dpC%45=Ln;%L3>Hc(n&{yBVb)wlTv_j6XUg3X85X%ED?6k>J{P~x=%0lL>QS3o=)o=kJbM$@LeI;O~u@9PT$x%Re~&ALy#iw zkK<)7?M;}JVoOIzmnVLlKfIqRp~1H1y?X$| z*@*@`cs&7ZrZ8P*Zm; z3l|GSSDxnb%~pZSmppTZMlCnb)kbh_(&2&4^D3?WEou@h>2p)gS?&vR^1~yIqRcJp z#_p{CHSq@+_04;z;pi@u-b@RZr1QuAdVRpnsqDI!w((Z}(mwN0`OnQVOFxVHOY7kw zm z(U|^pqOEZ_$}()nb;1(CT{nJAq&7BUwFin%MAQ%>s@0dM{y69-rjIb z@gX(|H?TgZl?dm#oVObnncru!2{R^3 ztnb~$8ZCLf6xSQ2=v?Xg-M5^lyg;HyrCBj(3&->&323o-@pp+G*lw_bj9MIe8VYHh zbI!q=8e?CqVO&4g%PzH7#;^WNnVuf+c{;yK898Fw(Nd|YUzSBbdkP&jWF$i2*@i$-0e=w%sB;(%kzh-LE$IIz^JKU`epP;O;< zMnjwI8rz?208;d_QzpWhHzsqjN09BpqfCk#lt({uYNFMcdr;Bvq(_m8w%!xrthV#T zA|IXUOwLg_93_x%)%%RBRvs)L8gJ=E4)<(~-H~2s1@Wb~{3W{+3{|NxdKiNtl(j14 zuT~+A`rpPNXGW=#yVjSdwRR}mb7sD2U!Phvrj6|%o67tXHO&{$M9ezx&08?|dP7o# zftt9Fn53=t>KsZe)K_9cs|!0O8*93g`RVVY4p_GY<5)G_k}30(-TPy;Vj?!&{bhf* zb3OBw>?=UZe#q^imZC)3v#mE5!jS~tqzpkwvi~|*17b{8D09oXSol!3c6g3M{9y1y z!AYFdp&_4*Kt>~T-Pqq!L4a?D<1MtFL$tudwC$3KQY({U3N|Cj8%|dbyq`&l&vDuz z$Ns?w60TCfKUa?IG)OKJ?mq!@J2=?ZED4}h1&3{BrggEzYHB)EW0oCSMxZ=^m?4Z z5a3XUSr1I%-OC^6d$k-WF$8GSx7gz#!$kP0%$H<$t#^zv3hUwlpDwB5VQ4o)yV2P* zka^WS#-b%@x}LU^#^H@Sqy>##jLyuA?`xLbEp|f)c2~1KXIDWNC&>L5wiHyDm2nRT zMkm6tn7d~dH7FSjt5osiJlFgI>zo}KQhnRgwpg$Wg@|;Ua4`>7PmoQFE!5+@)$H-> zi~ebJsvH4hfr?sji%3LhUN?n53<#OP`VG=jSZ`8q2?n4i^z#0GIq*iTF;J~!uNRj5kctP`mazug%**_8(rIC9uZ64iYQ zzo}{Xdz+(qkHLi0Qw%P=P&4o!T*YI|x$a${EIzEdB`hu1^mj+#QD+LM!4Z)L~4OdU^X2F7``UQIxLyGXoi!GG$!6}9$dfiSo70}DV?_uUBc zt9Ndd)%>6A`Pgm==VLd4@uK>~4RsxPc1Vd_%q z{_~}~9NylufU`G{&%9rO&wn+%Q=6YDxTs&Ym_h)Guh9V7Ba84H6zl@aBPt6S|Fllj z@gP~QkEg6h2WEaPo5nHr*vcyW+?OmB(&+o2hFqr?==c052W#m4wq0X?f0CU_ssB8I zrp_ZAsjE+NouYSF=OGMKJ|^_C=W7|gn#|YY`wbK(uCMU^nbOt5T{i*9LV6M=YGTM0 zOTb>Gr_$%@WmqUF{V5A8h)P~m1#fdK=atpYQ zUErxqfT}7&dt`jX6d1god1oT>mt4nAbH}Wvi7eUK4=0@}S%?ODV*L5{z>Db>kuz6C zb#FazsaT^$E#hvDhw^Ke#b^Azl(=-ByPz7+F8ivX< z0ZOYprv~hY7)8R0r^>LL^L+s4i|jL+kS1y?Od*i_jZ=bk)#`$5K&Gy zf;mji?1r2Ea}vPPY`n?6lzQpvxlv6B#T%%mSSNgZkfjUS*-y|od5p)yLSH#r zLzx(Z1LT0R)q zCXPbDbsxuoawG8FKe&#^+@tQr04{G$p!h#Hk8ARcfJS96(V>Uz{7dTd|CDl>!_y{BTI@ZpafX1FqF4c5+qTNyt$vXI{sPWBG#a_r zyj+B>I@|}qC|2J3AG4ppG8ePsBJP5^)ux`3+aeY}!XVfMIPRY5e_=*;0b2zcP~(Dn zk(H;aK0(1XT_OCV;eMuK7P-?b&%?N)NHe4%9F5CvVynA|etxv?MW_O0Q8X5X-aC2r zt_1@t?V$w}KhIujwGCLH%R44$5UAvJy2j6$S@M=p01VS<3#rj zfNh&wRNOdoDl^9e-TD}@ZN8^!iQX;+ny~zFjntz#F z`_>yw%`z$=9cHXJ)_&DWC{yCjz)Sc(`%=MXq@M!m;4^E~1K_RoVZH#>WcaChJ$Y-v zriS=S>Q}|4oq}5cgM)=P;sN55uNmR}*8o&i0#=q~QnW3q4}^l>gi|0*6>aYZ*7TwWE`Ss^6m-~?}(+PgUGi2I!7%FG}c)srpHQh(a%^r z{{HTqPC_}z>Oi#Tu1Qo-rBJ}I#J6^d{qm#GLT%MedK=vOBjhC&lx>FQH;NPxp__ZC zNBhw98Vy8#yX+EpR=z=f?oR8*dz
    AvpM9r^S;%7Jb{99rC&moE|PowB2A@!QW_ z45THs07JUL>^lq`+~~Rpp1z6yL-{hvK$$y^*Q8D|-RqY)O z85S5VJD8HqNd&Wv)k)^d*HHqP|8fEWUR zM-NLtBZfT0-44Mww3$$?aA@cG!|_K@tXBBOAqik5?9DZ|y49aD*K>nZ^v^3I%)KHY zSKVblXjH!ap>HI%C4lJrEV~a~MIuraf~#G6V6Hag0_LJ_(w{=84x`TFPUJpNhI89) z>yw;BxI1;t`N-1pI3Gdl;C2}8NM5%XsCf8MF9yZz&c1K1#EJ!w+5?(=wpEW@?|X5B zgq~d8TCM7|!@;w*3MpMTH4WtO3)J0sy_IGTdv_dRu0aWIxNZGFFJVTS~sUGUpuEbwKM1P(KHWI85>{2CV5W!Bvr8$;OCU)4{w$l=sKB^-+BFdTgn0r4TGIqs}<@TGZbW)-@Cy42lsF3{{xy8 B*UA6@ literal 0 HcmV?d00001 diff --git a/docs/assets/advanced/neural_networks/raptor/results_figure_eight.svg b/docs/assets/advanced/neural_networks/raptor/results_figure_eight.svg new file mode 100644 index 0000000000..81d3a51286 --- /dev/null +++ b/docs/assets/advanced/neural_networks/raptor/results_figure_eight.svg @@ -0,0 +1 @@ + diff --git a/docs/assets/advanced/neural_networks/raptor/results_line.svg b/docs/assets/advanced/neural_networks/raptor/results_line.svg new file mode 100644 index 0000000000..0d7d142013 --- /dev/null +++ b/docs/assets/advanced/neural_networks/raptor/results_line.svg @@ -0,0 +1 @@ + diff --git a/docs/assets/advanced/neural_networks/raptor/visual_abstract.jpg b/docs/assets/advanced/neural_networks/raptor/visual_abstract.jpg new file mode 100644 index 0000000000000000000000000000000000000000..40ba52877aedf8d273e74368d7c2dcfb5e18ceb6 GIT binary patch literal 208973 zcmd?RbzGEP^DurbODQFybSV-_gMjqjqM(9+sC1{abS$wdqDV?NScG&pEFj(8A+%2000F12mBrZ zya0S$Ts&MHd^|k73m5P&5?&!9Bp@K9x=coLg^rqmo{pN9mhlD`E8}$zCR$oHp_?2$ zyti-PW?&T-zr!cS#ebU*a^b=SLIOfcA|gt@YqZz+{y)R-8h{iZd+3586mlKFB85On zA-{hBv=|j}Fsl9mTqrgU9zGW2_b`BeN|>1ZL;UxJUA69tl>PrryQo-V`7eF(E6Z}$ zQ4^^w-6>-8aqk4E>EDc*{@CYDeHAw5$+Q2I$lWAwTfjK{hxkE=C4=r6$M;KgyRW2n zUYu5mMcWnQt$B*(Dr50@Om?)NfoMpkBd;H-G6Ddozh`!ywCffTHPSk8{g(CBT~R=i z@4$BZDmg_o1anQ{~Rd8G;lK5vOvn$Wle_ zX9;ZY)il{WGt;QI&^`Ll*|5w21Dg@^F0aLY>dY;E>|K389)7RfK#Nu%WQ4Z=FhS83%Uz}al&BliaGJh-uc?9}lShd%LUuz^^H<_wiRBVnbn7+s?A5foyr|)OIb=p*a%0A~27oS60*Y922 zOT+zStLnx|3ih!=^Fg6nJG|$yeg4Ib%8z3rqUl@x1%ro2gG1S%>=&Fq0;wHTS~GgP zo~2pQF?Y8EGEwb4+mpu)p+UqZE4Daoaf#}734hH9TftL!s8;gIiw{00&Bz3l)ed5m z2jQ+uk;&)1v5L>7*3b3$@`WfwmWS4uwoLqu-VV6iHPXEz>~*KdH2j%*s9_}o}sJB{+v zeMggPj<;py?2~D?dEd`*6uxU(tHlO}&9vwP_eg;-W)UDm-E`Z1YI=w+f%38=BZ>qbSyRv8p!Rry4LFsmMn@TZDtOYdSi;5FA-a<;Ly@neDd`= zSkQQ1UolaxX6HHmL&M$r5=L_n?mDnOD444pDdkTp0H;&R#;(0Bc0)zkHfgKFPEymB zM5i`?=OL!$orb&uKa$VId0&r{&xWbR(4z?s^9yNNdWlS;gVTLNA{>7QF7KK5rqIaCB{E#qlz|C18>+D;u7Q+2+5c?(*Fj!FVk|)x>=!6 z8G)ZgBCfU2QN@5lvF{4y4{JjUOzi^d7p9fw13J1RQ-~P~+<$qrG`k*%4>ReYJvDWC z1_y~Kq|9QyNBXaBN03_zzfBOdw%o+14FWc+lD)6C`O11D9nrVsA$1zxct;CVaA{uf z4u=xXz~P&LUn}C>FtFuG^u6ubH_KlnsoZ18bVlWTE|p9wM&;y;CR7z@&OJ;k<+}Q* z$m-p~xNEG5L7t^Xm%3;FIEttY&v%8+p|jj+Fh`uX+s&xQj)f^$Xj+tJK;w;?JuCGl zOG@)f#^bJG%yfFaBXH57DcM^xsQ)y=5M9O~2+Ag*4$$E-$YpC_us-TReb^^3o@aWt zwo-zLORNqR^lv~;e?2n&S+{o6hK`;sg}SkG(O1XI1Wj7^^Dw%D0P#b%s=66wGGC0) z8TiKJGshPsT;ZJ;slR=N*gXK*f&|-8qxHU2-f*2J&9lAqaJzC)khjSX%cFM55)Eu%NSt3R~H)t z;rTH&`=soHcEyvAKhVNN4o1l$F*iUtxRRlQ`P0&y85``);$$j!w<$iQ*$3*ZOR6^k zu-kY#Pik~+)IU@%wrqsC{|54D-*npL>Db{tZ-arI|2U1l2=QZ@Np&b-H0a;=JHcXgH}GK!5-;4>&m99(-#y=DNF+TFfE#)lgFJ=xrFj6_ zk$7GOAgE3NfYy;9&M;TMBcQV+f5-sfTD%WjdZL?fuPQY zDKUBkTuDJ-a8J@Pp8!^YA^>Q(oRq;2f~-Uwk&_Dfuk^Qb@YB`lc{;#(g1mH4&as+! zQshDckh2Z#wA)2p3_kCNOY;o9MdfbeRF3V5f#@?~B;=DAnzYr*jP-3XjR~g9?AaIu z1w9hLYXKEF1yFqrjJW|Q#6j*Ta()_blzfMhsR6 z5XyV!V_e>lzip3`6q%D~Nrjo&KQn;EzgX!&{c$pH@?P$cEwf&DR(w&3?&^}hC3-!! zVYIkf?GXa9JrAHQz+S*#t42!%#?r++yQ!u=bwByLA5qAPTHkt>c2qBmd#i;x2*3eN z;Z^`Py(o4RA7fTnJBYwkwg3W8@Cit``)KNDPEcAjl8$D~*X!pBJH=`e<0mr*B;E_Huk-V6$b*Gg=oKUyuo_QJdZPhe2O3lsP?7 zj9lRX#hlp`;+q@fWza6ecBgMee}uX%`Zet?A!@nWkY) z0F*rlGEEgu0NQlV3=~Xs&3`=S$RuKv5v-hz8aiXP$eVq9Pbs>-a*+Mb(J>2}|IxeF zp$$5|h8ZlO8&WsaE&*8L@X)6LO>fS;i8s8 zFj3KF19iQPZ$fE;8+7(_vYUsD{$fC1zp4L{%v0xX&jr8OX1~x(*!PSNn2F5WtJGyUnw*B(9jB;{Sjvuk>c6WQtM;-pylC!we<+k8= z2&4qpB1Fj2g65kUZ3eC|cTV1@`EBE$G+6;zo{?-rH8+~542)v#&o>(g&wH2+tKzb^ z>s(mlIg9`L&V#jEyb(eV8me;qLu>SY<@u#lPo(qvIg(e6sJ+PcF?mV$lRPxtpu}1r zoulGG7Q(lQlb28N&vFN$4H%WnP4GZVM{aeNjovfJ<3OWYIOJ)ljb?-rA=-%$>q#Dg z%p5^7fmqk)7d{RdZY}4^eK^efILo`+vgEc{b1W25@x!R0%_#S~%nS|<+sp{KjO*rZ z+U$KFJaDTf?$~YmYh$?%oE3~kaYY%z4v2$i2dTsRJf8XX$LEl%F6Lo7G5NG>4eI9|+(27pnGi5+_8Q&;6^L<61M(d+5Dq%;X26jB@tGa*j@3j!H`&#(_#Oau8_F#WS z8FZh&U@d#kl@fmF_SS&1U0ta~!_a0RoZ?ROkX%qhck^j9;uo0W6-tss9@qp_)&HE+ zpU||}^jPX>ZF*hPR`+cXKl~|0eASPcqo1obCA69m_y=9F_j4qELnlosW0f3+?zPW^3FCVv0a;)G!G)60@^LDS4o=7yfh#ulP1 zyLIgPo<#_b6QbP+RyTZD-jr^cyJRkwlIv}OU&ry)L+#B@@LuRO$}FRm*^0ZUMIBO&iJ>sazrD0#nnE9eyNHSdbg}RqF;0tA1X|RIL;BW)q6-YBJ2(qx}|a zHC9Gp)n|G_tcmg)<R#SL0f&lJy{rI6GPyWi+?c&&2>ud4vO}Mz<7G4&LscM|!i$8o`H*578kF^<5 z2IfTJi2%fus1Vf79V&&c?u=R4V5W;g!65S2ULUZxzCO)^evFU4y)$m`{4vWl|GI}i zG)AMn;KCo8bg~CqXT?IDSU(CFx21c}*cD)LJGh%h`4Onu9uKu;rpD%3;e7aH)cLW6V1UI0CfU_ipG~MmZEvzsVKk;p@Bzr&2(fYi; zTQfE78+5lafe*td+eykp<);m;DQD{-3FWA^Ah>~GZ9i1=^G5&>JF(M|L!p+e0Hxo( z1cGaX(pZ+JuiA88v$LcCoX7e{(=%b-)WcId7lK=WGZ#^x%yof5$eQ*lEAah~J%m?b zB)n?6fcg;c5N&Z`Ex#&vF6=D%Q`NQ61`Ue=_~6}B7jX6&AEl8aF5Z2ItAApu5t zh*0{D6VD+0l9zYrD_44WMnmW6ItpNM&pp8kA2vRMylOuZJKWyegqUh4K1s)RUE?67 zIk50>-CvsrPIpF^4|>QGNdO5P|J0<|BI$WV0Yy;&NzihVW-B3KwF?Biki@F{~5q1K8&S6i|-S!6t>~u+@rwsut0f&I~pppioTt?u;)4z~h zJ{1JeZ(lmy`XP4(;@?<^_|cQ!Crx-pDSJp4b_|C+Qq8M3nIRiFE=x`yU{3F&Y|y0u>%?u+&BbG9(1eyXy4WWOlx7Jd8kzfUa; zyh7|hed|zS(<$&a-LF^Qm&=+V2JA>mc%&Aa2Yr3PJmxgld9D8XfZH*zb_fBEmOFRH zoa25ZRnvpBTnAgZfuCyd6HW1ZP1NdIr9OWj#9C!g|JR;oF^}_txpvPW^4w7Y94{^t z;*LgdR*FSVwk_t|qSO$)7W2gVL!{g*1FsgtU%y=J-=CjOWWE^mrt#vuV+nEN&}jrk zi#Km%vjvu<_gtXd5SL#)PxsiA_vR9%&2)Y)s_M+~?5Oq71bnRKFPY3inn-jv2a3d) z_v+>)2BPV}1ZDNG5pkCALac41v-MwYxZ$viM%{+br0mf(=`XV&0*0Gkx^(C>$s6Xb z2Z5;zgJvS{KxM;R2qx$*$f-h6(vfXIvA*bgvfyzD~H z)UWKXN6Dw?ejAnwAJh{ z>QpuWk~-(YVHh|lQ-RWrD#0h@!g}s;HWR7dK3)g$n|aIVA6LfV;~2T_33eWzo(&de zLp`lhcns(6pB?D%XVb%80$2fflFz_av?Xap^qC*+WAo2X$^;KqWv)4G0=T$4*TDwo z0!%La(rPbGz@0egOSFF^JM@eFC78}HPrS2fj~>l*>1=wZZ@z!`KGXTxm%Okzw*CQ- zU;E(rGv6dYUbx2yq39HU?1Qq@E8i(lJey)bYkrnKG|PB61PbE>s;WI55{8dZ3z6g#|CZvtQ_Pj0)V3L*uy_Up*}A&-;8r! z_!KPB1qvjI6%MrD{%JSvC3|q?eD)v#IUNW>I&bZQSUCT6?7LnA^E`rl(e#|TNPt(f zg?LeT;rwtaou{IU#b6hmN+SQ4DNe-ftGR38jas_=l}O-pg-Rs0?IC&k8{lE^pYGHJ zCC<4^r{!8Y3{?ps&z%z|iXuFjBKSbATqhS4P_hP9U6V2j%)}Bh&`nh{FN-42gA|<3Bq)0r zHVL=J&DBY4k9w7jL;&)2?;y2M@-*Q9dqHT{S+R|4Srf9G05nO9u{+{?7}(|!Q&^@w z8<)UVr1Cnx7X}ne&d-`43j5YmXKa>zMIgKO;V}Zh_3d(Z;=&~0APwxWmJ9Gcd05ei zCF~vs)=#q(XzNAVXnC+T0Eoe^9nbXyouA%7MPAn!9ho3O5`f271E=6PIU<8K*hY8{ zMu+n;pA^B5bH@ZP0^Xy%;reM*%`8bSDQxm_48` z0Tnkb<17m$yl>&7M>NQ3oy`SO-tUI>0|MH2tz8KoyX1XRqsed={>Vu73nwXeP`VW4W%)ADsOAZt68+5X7XLrLrA+v10JO%Owrs#-t7%e5`>vPYFV z!R|cS7YeOcY@6p=o>{$5x6LFo(^;4w@A8>VdYS$#+9{ob-&w2lbUrZBFmN7pU=dnR zE|8sbhe~`NtQ@p*rGQs5Gh=UZ9hl?o*xz*+3n>41JMLVs*f_dOr{HATO^*cIWxuvy zurY6wOyaWC`&Lhezy9-T&cs4!qBB(S8~NGJ&qg3a2pnEme_&n0eTIeKt?Z~FXE+`2m#b2kck_kPAW@sdm3SI1Q{ z!H;Iqm+#ChsjiBfFh?(?+aGt|`_ChUB!H3t_u?t7=~5)-9tQeMYZ(cmcqw+k&zfl? z#QB6gN&C=(Z6a!iq6#Z2R?GzSZIM4_5$E3HyzRUb&^TpV{i?i4LMfe4UX_60!z9kd zNsxOfsu52Qv>m3!hYU$;0OjFS2v~c!FGh z=+8#jldyj=pV)}Lu(Dn@(`I-MZh9pwSJJ_;v%T7gJb}}u=RI~mjkFVPR2_d6ukHJL z2bg5Y>T6hZfpTO=+TZgIwe)3HSn@ zH|{pH0`GP7>{JOxQQjpZJi_u{N7pZm;tG}U6#K=^dS6!a|Kt$3zQ$_)Ar{8U>sDz7 zPCPjRcz2(#jN$S4czvdjMBES$J7+_(BUgEDd9l*Yoq_QeR%0f9jdRDaRkP&`mFOR% zRwr?$m;@$)I8{UYZ%prQlP9DW3edf+NAracN@-c#WWLx!byS_*DY9`T@is>-nK^3)Wy<4El`A&fH0GLC@s7!bTlcnQ zpgu<-mPF>{WzB~37AYPTWfMEP08p?CToG3_5;$gAqC&qk%Tjx=J=vFFVct1J4VM@y z%_0k&cNP<6HN76lEzyVMb^;eQci@UC0DRIQi|9E(^lTKjwfVj@H>1xfd(CjEIN3pu zxpq1u>*a1nw0GN-AdQ*VMFVJ6we|zHmc*9*hzJ`E^Zg<+zZ3voY+En&4Y_A#x<^dE zD6l4J9Uu3?Z);Xgpn`BEwopLYfN+%h!?E{;k7;2A%`!P5ZqL|10lm(0r78{=>whvA zRa#~bl^vu@2stij9zF1InZC+VvqEIx7b9&ep|UQVKLvg*0VsV2Rn=+fe(Na_dMm!t z%@v)&GZJNObGItu`_%=wD<-4Id>tURFScJ)ys`O7r{h~iLqe5AN}tQKFFOOn4x#LB zW)%tAFvK$7*0 z{V;iHMFgp|wY7zA8TfwHw7;nMlgdD|fX7mkvUx|KN9EJ4owZ?5hcqycAqh1_fT4^5 z%vT*Gg2cl!O!$8wfoLp>+konmW&{9{!MjdK zE2zw)|t;y;O(`Tc)g=qmYyi9%JPc-UeVT#HQl9{3l`jl+V_6Cj78x4$(qVo zTG^rRI6^}E4~)03Ce#@?ZvBu-hNJepMmen0G6x4TwnAja}hOuM#qX##%#`%kiYOIl0ukHEL+ ziP9Rp;%j9Dtm))29|))_i{h3VGV;>qv(TB@uYC_m#BDHzAC9 zDELxiI|+3zI?ni=eF=6d^j81BRYGs84&~#Gi|U8o++q&Y`N3cOD0e|Q!$(dpn8vVv zL|fibI|;drKQkhX?>wl!EzW|z>BG$wRciBL@1U&MO21H6G=y3PD%4(QWwI}C@@{xv z(48iW!+)idmUMvZm%8v?;nykgjr#_a(f(TbPt=2TvwPKszHKeCFLDguQ0YxP(GF*z z6Wpm@l`euu1PtI2Z5FnJj+y2dbc#4ZUfSduA|YSZ9Dc&_d{uflL+cY&pU_h|Tsw%K zWj1eDTIp^^UHlvPr(oa4f|>3vL2n~QJL=u#W$v5BFbo5N1n_|eb?80B)WC11X%;MF zPfB=VD`zov$?6e!_fPAT?-c1$Xj?ejYOdP5jU!r>5!GL8S(e7;ENkP}dn>eGjron5 zmeI=+TE=E|m4@;aE#X@=t0%lLn;!5|NJ{~EQU!iih7X+~7D4rl0-Cj-T0>aV? zoj>P>fP?}o{YBkHk%w7&bjyXu4%7S|DYnYrAA@wnEM+Bw_fzA*g0Fc(q=#!O#^iXUP zMEZ3d;SxQJYB$_?Y1+_I(+{VKTm92R00U;F1JvEgPU+qh9PpTU^0piWm13PbIwQ-ETfeT&^`ug}(v*70cpxcX!w@c{Ff`CNp_j{%Dli z^X0;XsOMAnFFXCUNWGsf7s6?bbUTL+Yy(nj4R1WpaZYfs+9uDhF}abQ5tkXIcC=UP z&Y6ceQ374pa~yh7BHeu^dv{CJcoe`5?$rvVw|vbC8IvL+vyg;+c!Z?w=?2d_RA2T9 zd&?e8ePE4$C1|8BkRsk&nEIUf?W*D*XR6N*LwN#Z>!fD=M6hV3;Cq+#Iu2cL)Od+%Ccf{7Tyg>7;0;^)1ns-vU>{C44|u ztpApVDDk6cRYiE1Jo7OU0GLXPT*01Y;Q#-NDEbbXex0f8be zCtYxoWAPkt3kO|u7n7Jo5gjABs+udk#lp$o-rh+kr_(W9ev}9R0gGecW`MCLbhhkG z>9CW=AchsD<|D%XqA%s71_?k}iszM5%VTO-7n-&5JOJE^nf5J=rTXD+VEcs97dT1z z1Hwlw7lu5L07r=lPFES>>BY`P&F9p&wk`5cc})lCv5q4XPAUMYgiHU3T_PHRsotAK z0F34C6MA!lydt__IL3_v*e3Uu=zT^R0b;j)_Yl=nhPb&iJr0|Rm_7jDWz!Kpu!uM* z1ApxeQ&sImfbq{$ia8#RVzc^}9n7OG$Y1J$6L8lI5FpQOUIA@NuDCZ3U|D)lfOtHn zCBFoV86?;N97==$-GKS&u@u~n;>{zsw7`W$U`Jr(5_oK(8~-Zm2VYD#b4)6hnX}GAl_42nAbT@fRLMcbZhG+=q1A@smQ+Y5$pMZ zP+kq?dEzUpxy*GHYcIt{u;rnp-WQ>E`Qlg?L;*VmS%6SbdOF%w;{nRi5=Q;S{BtnJ zjUci4*usG_Gas+m+smadFr$FVuIhjf44AHD*`Jog>TWnm(bQ|0e}Vx}9n<(^9D0Q@ zN|#uDA<^D=q4v1>#5+$*8;h>&>~zfyUVll~OC4bfvk89x^%xR65d1J-P=RQ)x`ieP zfNiPVHIENRS-vwh3C(&}+Zj7)VV9Fs_?VR&X+8@Vx2_I5;vaQ6;1!Jt^(H#JXs_XU$;5TRw|3$@k-O6ts|S<9B5Iw9r`7}B z4R#u626dej@<%; zpGtNi>ZD9|09=Bn2twS@d3FS(Lf++_L$OOCq4rm>gK=RBWcvR6PR1;$Iu zeXZJY)%nUEN^`_Sr1TKw^_Ja zU*i(pzeM;Oh;5w__Vmy)%mi@B z0jb(;A+qZqTJ>$2ZbBopjcdV)0EqAkm;o?oA(`y(yov}Z)&l8-u*Z=Sa`PDFmadMdM(y1i?(l(v2xQE!cIKze*V0HlkBXPo-5Yt3~G41?j z1VCV=;A8LIyGf`bY1-~T23|H|E8J~If{q*~2jGu~&i?{;Wj|I?dpgaz&@`n2!uHZZ zWw>F_MrxkY4-*>LNpRtS3(khP&oVH*3vnO6;S~JWKf;%1__KH^Gvn=J3U>gH<*p@q z1Z4s4aX07VNWzEh#0tt?A?b!=?4sc96!|(R7^l|@;5nS_9+(8TmrLS8Ww}FbmX9)< z`Ulte-s7TgAAYx(^Uv@aL7X^&^j@KemH)^xq@HJLx}wdXJ@N060}KK)SZJqF$n+ra z1jPvtSoh3!rC|Z{%Har&dp2QqJ^sl#?kBgiOwq}12=H>(en5H_VTXGFuCS$^f_3wj z)zC4<6G8nVxUJk)NXlr|^x8T8M%IyH(7w2ipf_XkR0FcSLeSv)x3yKCPpZ+P?#sb2 z1kC$m?-v5Xz+IOp<;Fp73T_OTZ4>21b(V?z2A-@1VPZ)_pXp=cjH9R@rUwSJHuFa@ zPe%0^hN_uGFc%W&&j}h?aJ|YWQ~}9Bl7xPLQf%(ys4zyWd|hWpc}4Q-{Il(ovjV7s z-b*pL9!nhz1D;ZvugjYx_c1xzQ)C0vIw+%8!fBA;gLO`SfmJxrHVW!gssQKl-y32r9&eU)2tBpTD&=~a? zw%pj5`^(^M_{2f5p%!{QrfAUWPIF;|y*2tJ!446gw zr;ZsU-!Hcu(RfBwylSxsA=0>3RsKUIdx8H#N11{CyW5-D1cADM{|1b(>9katdt}_?v$=a8<14y0dtulo0wYznG!~j z%PC-d0D=ygl5}?&jR9XXmaU!)T{Cw>KiHbJnL-;p;wiHO!xaOVOG%e{BN(Q9Erf@% z5w|?6_!~la$<^>L@Ks#W)dv{LDLfKE0@vNrELYaDb0-0TtUIbRX@^@o)pz48j%Cc- zK->vjxrqR82K8+yTdf3Z+S}h26mVZ%T@(*gaVjc`h=@=T&=zw}*85OBC1IF6f;9>G zBIxBO4hCkRE$oy5_<7<+333rB)A0>B)25!xVffHPer81t~s2a z62Mi8LZf=YXpXN*K#^@;({c49f}_BYV6;??((8Fl+sqco*3_l^hnt%?MjRw+f^7H7 zBX3XL?k?(ICn9lwjQ15Bx~3O;0-b{|F=8QEE=7Gs@(M_7>*(p*>~6*B2iqaD>}zEg z9r91QU_N-&KhVVwk$p(SN#L_;8pP_jr&m~yG=0xCICK>TsueKA7nq?qpIWM**;<>Qr)I;KEgK5T{i`BR zjS!fgAYfhnT#Bm%K)x3!Jc9$dbM#5y?X=fFzCt&I&{1YLs2cG0SqV%iHc7bcy7ESo ze3_7G=-@dlwC;o5K7MzBLD>eE5m-zUzjVTEf=c2sz^7H+oHNNRt_|R|>3o|u^C-k| z!>*Y^_uD!|?~@Oc?-((9pY#Gx#iF%ZW|hI2fQ-%VzQl%-yvhLG!$QPu z`nHHjai%WV&Ar`S_x*#l)xe%Oae?(2clU07wMK?3B_@{3YYxC`yGvF#Wmqo+%FS(t zzoU`*;&KDS7&1VMPW4_HFCI7cBK{s=`WvW%zSz72P~vMs)%MrrzaFb-h+YrT0`j{L z3Udb@nW}l$Hd-Rjbh&@Oy&hq3cTb&PZoZOxIcU9=?%wU?XlJ}Y z1_=foiKDG2E!i39B6^97k}hvj>0hm5q3FuW#Gmbx1brYR_nKGDk|6F0r?tlCKdPw9 zYsU-b*O$?z>6s zZ!Kgp4wSuPLLvKOcgmb71_r9pnhR=k8(S*#SWL|obhw=c^1%@aB;jo=BGP92 zcwNl6u$aD7$T=BM)!1q0x7c+Ayx+$fo)b@8a3H$Xap#a^$ljbnXf?4sZ?l6S}2Gt`XuLX@N2M>gVn`xyn9YqD{Do-{`T*S|1 zj2L?Q-EC}bN4Jk(U5f2JR?*;_T>#Uil;h9I8wpK;YT!32)CZbRMr|j_hijiodGx0) z*{+?8jR+DxT#7P(wpU9>QKTcl!sHAmZS|JBKS>$0eB37O5(sZDZzvRQrIVm0uraRA z5J;Bkb93L@nwNkT=-lhBK(AjZj6Rfb6L;&6cI-&r7*BHt@OMb}B$nOkbL#!KIukMK zLGRiPHd+!&7jKBlgBvO2t@jk8B5Oh%T|NSUwrBR*j;%P8mqt9&H&@xra4Fuw$8-YT z4q1?s+~FCGidnE2rt@lRF_X}}{kG!JT3012UC@4wjJL#P&MJmTCO!cR@}tF9)wO%e383Ympd4Cs)hCE;-Wsm8n61nWRi!o81(Z(-=sA6zAcN&iDPhi-hm{Dh2X1WpvaT>nQ(M(au8@Q|Jo$F_NYdK?3c7bSE21yrmBeZG zdUBTAhTmEz1r91rqFcuVFS_E!FSQ}q%qba5tLi%U)Wedj2`qOw!yCs8xy>ewY_*RN zK){CE0}3s=66A?iW)dd(*k95xsRUL%Zwz?Z44tvUyXd2DohKCeV5{v>Nr~78spyY7 z2uyR^QTFtiYW%rJ@orj{oKfsp6r5S#Z*$8&vQ-EbFg9oBU<}D=iMzi^Ti25y6HQxd z+8cpnxTfwa<;EtT2ko-TU;9@*2U#og$%6b15Zz!8{jQ3yqqzI2V}sP$%DiTQYS$6glXN6$`FyV2S;=g9j7 z{W7c^&C&(O=4p9vy4xY#Z3pKv|2&0VX@V*;WEu3NX47*Y>$F>28K2TLHV&^_W*Z0Z z7xLbzOq&Qv1hCEM^e97TBsy%rddk?pXW$jv>KxLK59$rebFm1Q5|3}6UG$ep)2kA? zhecD8OH&fh@lOY)>x;{4*aF2Y_;rzv$$v=J&OEQfSNbZ8@SV@9LxCQ_Zo z#DzZv*O~mvrwJH&VvsxXRB^S!hAedIv(kuGK^kv~^mtDZnF5c0NQxt^5-W3c3mb}8 zgG3Ewu$xMLaq<4^G?|wRv~5X0d+m;R`Lo{a6bm2dORuupxM>@xwx1orvFgc;%Rg$L z=W2JSLQLgzYC4Q`VGB!-Q>FD>p(O1w)`k$u+5L#@xT=r=swlyq2$SUTW5n*BUQ?ts zeXg29QSMC^S>3h`YRvKk(6GQ7aeIkko#h!F-2G?5-0ew8uTNmWgN8*ITZ@Q8~<; zf;BraihXpBi|JOirUlQ5ow39X;6WA1wx>o1IMz$d5oRkyGNYeSB)tPQ>;_j5n}QYu z@e{Wf~r&aP*?|M|eFu!f!0vG`lZ zSUG$)GQ0D0$`&{!r}fa1iUykwS${PGj6oF>Uv?pN!6a4VS zOLoiQE%)0*Y35U3PN-sDRy+=8|e(f z4KF4ISG{`~%zxf&UVX754rN~^DJ(Y_+?l3p5mL+utFYU8W!@~#dIQ`o{xe+D93d|& zYa2tl86Ng$O_N!(FN*NNgK&sl-gTHnkEjo6_vYxV#GzY;wEcu-ld~k8_tI_~#gB}* zn2jGF9V{rsIC6FTQTE@-;n+iKtP=4qrkl@cS1JkQ6l%YUZxwtN2_;C{lDL&H`nHW+ zIJ_uyD=p^xrp{n}{Cr@%sd>fCh{2w;{qYKkit>eJ`a`$gobgxt`~QyrDGq`nh~>;T z_Kde!S+K-iR>Ebo^+kWgyvGoR;uB#YOwcNEx?|%5Z73c$Hb|ixpn3 z@m%u`PY(u?2Uc$v)zxJcSBVy$4*nNGZ)y$r$?%;-srDPX?I|NwGan7ui)N6RX&7V~YP-4pyMRl4s=dVVUicKl@JGtz)xh zA>xd;N9B?BmAcnxTZRdR#FhvP2M6;i;7#-!6ymR1Rw7D-4>TMMi{=vg%bfJJ#17ru z_Ry$kdp0H1vgVSd;p%t9e-@~e+jLKuqK!L7I>52#$?ned7)R1@+oGu3Rcm+|92@%3 z9=ELi(M-4OG;Bd6FEgmkCW+6cchz&i{gqN2d(hr52?^&fdWl$RS6pt zg?7Nr4KIOQb1Tbnb+)PhKaT`_$+b87H$YKl$nWd>U`=Suda;Y`_~H_g|BmP=75HcO z&!t?66U{5#oBo;`QR1inWDr-<(k!6dJ%Yfi-iQkng*k3dHLLs=0f6cPCGOqf9Yc%Q zYzbYS$VQ{gy-)NxJ1#CPSvWl#3qtRI;IW4X!sg->p5gIYY6XFRM*o;BZF~G@lk$IK zOTZRaP*ITC+=Kw|8bg)5J*@5T)x zQt0>qz-!R}Zw~)&aMxbCCeAoV5ubiF7V&>;4AOD#5Yo_u#C81Fh3x-<&;M!y1%HKy z267I6$Pg^>XLxY&PJV<3>olwWL&FpxfnrN1m+$|A1@GdDla?SC_44#DoK)avS!{U@Y(HePQ|0irI3=#ndzg?L>nk!S_N!)9-IFn~!6K4q(Vz(SRcTcGW@T&3A^{IJOp7GwMTR3mbSZMh>`^WDB!jJaxU+L zZc56ctL{KNO}1c=@YhD=bA<+aQR@0Aj7_uk?OP*^1*xK=jpY#lmIr*&1qqsIp-LLS zyET8mEm?d>btsO-rVDJ`-qx+gslTW!c;Bvl6k{5fXUPY3X*rx|KT?>-LsfABBz^AddmXL&k_y`h06S_S zc11P7r`^#+a~0GYdS@wiGwjaVrv~+Y2cJ&xE~m*&KA|(8_izV*CU0^QdWvY4D1XK0Fc<#Qvx_((!bFFizDUiI0Dm* zb{`w{ z$iJy1j$#Pylw&s48}zR)WOz5Y?0%O=R^Qr zp^GW=ZotOoAOcuuvu}S$Bu?p=GOok}3TFfdK~&-&3TS|Md9tD`T>vm>YML03a|y6v$Qp7pnPoZj+n4kBgYmpg_4p5`Q`7Y2+i08$lYUGT?8 zltmu96!nyag7aikBY~`nmZ6oK^oLl5jXH{r_R_ zEyLnix_{BZJvhPL-CcvbyE8~&aQEQugL`n-;1=9NfH1gQ&>%qqN%oy&?^pJ||NA`m z%lUH7sSn+&eyh5=y1RNwSJi5Z-$kI!)acTH4!Tf>opE1}R~!KD{DUn|o(2%Tz8r1S zLOFjXm}z0?Er%1%WQ0AnhFM;!|K8jyUWthn_pbr~A?1Y-01P7m6hNhu`Okr|&`+BH zIHAux`~X~0F-fDO-fJlESBm_#=Mvbz4?)Q*hS{D!-uVUmCm9Zt7v?~C~Jp#K(Xf2-zy$Vfmv(Gg+Pk2ML17!s)BS_w@67KF?_A)QVCOpCC{w}ta%Lz5QxUM+_pO_& zcY(h`v+Vbs^*0+(pZ54&{Nk|hDt;~Nbeh$x#l2!_1`3k-E(d!kB*otX17^7Tu74GK zO8gnU8<+y6Fq+LCPwK4Nomvu|k}gbA$xJ>P6$21gWxmXnU(E5(mT9fux(E!g(UdZy z{Zd{5KQ9MFcAx~nzRhLoWVm8=oIkSxw3@>EVg2^r4ch;=IOf#)&AJk<3T|e7*Yk<( zoUXS~q2*sdH%mkQ{l(3fz|z+Z zrd-a(Xa373_NtHu=sD_u0cMMH+oOeD^{jl5@7jy1?(2m-o3D?dRlz^|fB%l;Q+Ye` zB;HR>P6^l+@w&BZ=iSP(adPWp^jyzVI+^SLWW*9xVB!~op?iK@v!brYUoR|lIdRg# zpT10T#^ZQaAmVWdt*odx85U;qd}vFFW(cEUX&F01!UgFHaYCyPs5aj)`Tf>GcQoa)Bxy&A#sdVEudi zp9E4cNs?DC0P?d}A#f#}7`%l}ZDqF%mFfKb9`P03?$9Y7E)%$mqPh0ve%kXh#Ak_D zPUW5N0dUKA?a<31XGj8|T+U7yn${|KyF)DJKY;S>JJj)@dPc-!fDdg^@dJbJ5EQn@ z^9IclLOW6ayT1;D_3Dt&xfxgW|5p0qgX4#)Bauhpt7>Q`1yu^jHqVt5@QUmcgdqN@yBP zKzAp{aw~VszurBy0#V^Flm4B#qOH8;f5&z}aEw8@sXM-}IjwOzA?d zkl!Sk_i@7eKf&MIUzY++zc24k^8arCr#pZ=O)T>&<@Ed)4-4Ac{+(ddC7ixC?Hqzm z{|)_%kS|!TA{9*xl7s@-Od-he|6)M*qCcJ_U2pjAenEA!d&Pfa?sixpVbYjuKzUf{ zvy$-trF!I%B&v&%kXU{*0oedtoseHu{7&UOhm+heTAKiXz-Q>(P)S?|U5me1&~*ps zw^hF~19ea*M}DS>4H}Z_Urd)VQHy z&@1FP*#I65ZT3lGQ*m)pOa8kIQeJrLJJO%7&@c#MfW3W=GeCAMj6*8rUj?u!0i-K7 z+f6i6E6{c7ODVv?TDA8Cb!>n?%@pLRhgj%M7H?Dlz|6IU96@aWp>D|r=$xVwS^x}I z696DvEE9^GAq>U;GYe4(`kb(Npr>HdffyP)KrAT%2#yg&Y|E?vu^}RgQ=khlLOJC~ z4Ci`70Ge(^iI;_@-T(IXU~yz-plyr=z~*=Ykcy6_i_n@wLSp;T`L)2@F@4>`Z@a{4XqxfNRFO`+~iY;-g3lvA*VZRw$C z-P6_AMIkl$I|*zZl{e|^Om@te)Kd($3a-bv4VPy~D z@ULGg7{?kJ?_)L*Z3v{thl!>J$8kN~;_|v3Qj)iRxHtOtmD|#!I4-rBCGf8|1|2>?(u0q8!#beVNc2Ryv z_Ke|!fNNE$UZePiRX2TZ2!VeH+N34c{;kRE!nlOLVzsaFs@EPKb-O zN(IYITBSB7UtcVUP8GEF2*TRn^@UBld})~$bh=dICwDq*YbsxNPp;#(m^%28Ze|V+ z&LSu;EJ`3Mw9`I_0KAZO{w7Sae?9e8O}^K6I>5fwe2`%4%jqfwf}SBfwnUG0WI0z0 z;FDXPu1%40*FI<0C0%siKv$@@p~rP+g$L+5Ni8Ky6-NJlc6^b4-Ua3$WkT#EOh zTjvJfOHh%++b?>*v9@5wnPS6jllJiCS>Hcrnc!z!AEI66UCAl%)1!SZ1W~TE+`MvK z(ED-NFEQj3?sHI9XyQUrfb~SGPcy5Ynjx7MIC$eYNgGS<)MqhwWA{$IBQ+xaVCK#B zU4TQ?NTl zPpe|5#@roDxd-`4uDzjG##3WTORSp)I=X&0nLc5cWkz>TGfAd_%_TBKuRoZ#`vVZH z^dfIE{qE_;(ktN{CVNX$-?IyFz@z`5QUPPF7MJQ{=aqYKmauCPAVTE(&Hc_f%< zfPKkE&`k7xSiG8P<}Fo%aCG{%Th(I7){?8n>6sD()yOlb2+~>=m z?BTkRxxhRX->~2;-@W3^t~??UYAOSnp*Ye4OnI=_J z6JKBs2kqtTDxD(}AOPsacfYEUEB)kgMzvYTLrk@o8!H{U z{1M&0;~9=z7icFQ1T;>JJ#18PaN2h>>h6RMD~mT)d_-ir@8(5 zmcD$e4reEVjE$Uj)?KLTsD{~O14c?yti0?;KIt3r(UzEmw30QU{ibcv7fl(_L%6w} zA5JY-H677ObYiBJ9Zn_9ysDcJS$m$tBwvkz3q-gA9|&h~->QO0%RH>}a$>BsdqK)_ z)s`+F5KXG_q6pc;1eGcGIB`m7ZOl-{b@JXuS!aIK)!Fn8cUN5;zSbgTi>y(wG5fZY zsojpW@&R}MmtX`2n3MINS{mF{<7Z|$aDDXwAaz@se2|w!C7T&;0mb4yZ9yAgH#d`4vT=J5!AZu<)6Qfy^78tLGOY6v%r~i=DF^-KnNMO73ahoP0xekr98eE&E(a&nj z-jr$2Jh-=LKHnyqlI6?|(8I>aeB8;1s3XVDUIvPkMjzU8a@T~rAMPFE z`9=FdKQ@QC(zci~gZy-QHp7gu=D#yAY8@Cy##u!Uu`P9@aYiNt`HrJdPa+LC^Xp~X z;sn+Dde^tC4?W=ATg_$a=`Mup>g!_ZTuCFFp7}Rjp3Kw=)23KO`^tUb$%?=B*tU;a zpkS_0vT4E^_2|vUe-eoZq#CkmLUVWNy#+J%|LY%O;xg4_Yg#b~?e@T@gZRNBwzYcZ_*P z3(Ku0iSZ#khS|&eFBKCvt)+0-gUNzk`132qW-<+0WX9Nl#!_{?#{2T-lT&x@m&#<4 zK1NJor@VyA0Aq+KzJMjp$GzU%kufcqXlv@i7Z=Dd1iJ^q4DTx=e5>d&<83m}1-141 zLD&L1;6ru2nQU%se?Fw0x#t$LaO=MzSKWT&_^nGifZMr?_s90YGUFH9kTa(yWv3zi zWu}E#X$A&IE?I*W-B#;aE@jomSp!}-nu9i1;qkn!Z!?SWmO@)h3>WjuKYMv=)TjAw(f=!4EZBf z>=mPmIXCb=mp5KX>Mj^N7jFaWTgLr_K8?W9O`M}rZZ55cx}Hj4Y7xi`x_eF@i^q*c zbP>pWMa1Lvd}7qts5C$Uv!q$QWc;)Y`ZB{eBR5zt)smd z8yWUdMS!SCVU1?G`&I_YEbhZ+pgd#e=cs}!=mQ(hUlw($Lq-FvN{`;se>5H}QaCZT zOLF(Bvp_GRZ)Wy*P_~g7siJrzV~7(!Im|%W{mklHE$lek4v7}cXSz7xOPXd3FPoby z#a^gNaYQ5}as|WiPd&$LzCKB8@hihdhQuI#7LSeew z>X^FL`T;c%lIAdN=FiB7$PTx>4ww71b=uR!TQeKEZD%8ab5RC+hGR2qtXk!WZNT^1&-%qZ?ta z@IV;q5{F}xp+A(tU3-AD2!#!aPcU=OR8u!x)lUB|K4z22c5pA13W6D9Z&fyQds@in zOmX)bE=4Ql@?Mzk76FNG8pSo?-GHvAdW!-s-`ce0t(yE)TLF%I=IpUm&e(_KnHCi9 z=k^7Qxsd(j(svw@I|~p%Pmn7?&8_yYRc%?Vw56oG`=)eidDqBSFC7X5w z#GoA#hJH@-d$Jl>C)r;7PtFVKjA1K9y!drgV_zE77Px4f$UEG^+SQk=0+?A!hkXy7c3KWcK%&XULaoD)IITD!mn{n)F+AHMQ&nN*ZN;h`WG@i|u;eu8~lh z8o}zpqK&bSzLj#f>`mHpo@#@d_^kRelewKF2r$}sdzmRrlti47U(oakv&PT+OP=6J z@;d8$xFm4dAQJkc4;B8JO-&rt`wuZ=pU2DV3alhR_g>$sf(hH{HJP1+gsl!>zt)Mr z=Wdx=uTgGiL3<8QeEtK#xOYrj=bmEik=gw=8@e8cT-rIvEW+6_hSJ zTi|T24~Z%IMhgXUsbW~gH|pqFPy+r0zt z1#>mge`djRF*(${vC}OCw zr^_7}cO`00GI z9cSwj*7Wzf8wToElqC`54%v2q+}roltPucVOXsQRF|I~K3M<*!5PR9tn zJzG@Q92BSMtr(6sdaG2lk(%l4HBqY@3b!_d=fMeABP&Qr1VPE;KB3s&@zjvj9rO*B zlCy2=Vg@kdHos~ky=K2-p5f2Q(TF|mE$$yjAh5tgZcs1W?ev@=bk!#&P!#J z+@IgqJ)8yFjT@Xb>;&1G99iEW94s25dkJKoell!JS(5fkFoLK-y7FFHT=|%_@cJOS zaI}bqo8&;9jqO|aEWRHd6pc?gEtGPIpLB&{Vt&{fzmdx475kLCF+m-`&Oyh?q-I#-uSZE237LFy``dIgYgd3 zts}z+?q_493-89RfqM=PPdg%Af5QIfJ;EavU6l;)(?ZS1=tKS7P4tFZ-kBmF9WEN# zDAN5V(ZI?^B6rpzvJqKnb`?Tij`Sox_yWKw>!h0hy6$u-^af#)$kd)TtKT;}M+bt{^1hSm zkP0gUHetixDz0np{N}uvwCpL;#@jGe|6nLuRjWoyhp>R2pOkZ14+TDRuSL-5e5)$; z@VY7w*;<Tg^AHL+1Zqer*R`zV|TQGJQv>0P1*NxfCW^Rl*z6+f=zP!?@WIpB?j139c`;HxvPjd z$%g*{NIAI8ql7MzDBwWm^Q9bgt{z&KAK_ai>)suGr?zk&webd($TN?wV_uAWilJmH zcvr$0{~|6q&#te2e`7sArpGX?p^N{=_tv8g7sn2hjkiNu-Vmade6PupDFzKQ$hBIB zezd&06wpSvga zx&0k7L6U~Pu5&h=JYyhrOJ~7QZOsJbNmLJ22gOj7Df@)e_|@Ai-Dl}=omC7Ae4Y{x zKd}^Rql3wZv@dz-+Z(4&?ymPex|)rqwXq3=TAKD6K`o}iAeNrLf7jj!7;L=7ywPv=IneNPn;)6vu#C{ zu|5vnlWDuhU=!I`-&Y|$qf~t|`U}F(4xd$VsMz}h;OElSvA9as-o?d%(o*QGohYZX z|2g;I@O(kl{U0U=SgXYHA%CNCAowH5CMb0t6b$FO-e$*Ki3mI%wNF?oKrQJoDG90` zFfiXBb=kh@?k_ZsG3VsyfQhY`S%6-&nU+5|`E5TKJK@z9xFuQAqsC_nXAd zz;x?;Z=vhztDMl8K=?z#z6z=UG1+%$q|dl+v59^w?587FmEu2be!`Bd%kk#FSa(!h zEp)^O%?FSWPV9pSKLNRuG!&)5E4py<*dP7WvJ-c*-w|&(OL0%=$ueaRa@O)9Ahbj>1F{Rq2B3O8OoM) z@$FNXyyTy^&o6ZM6tiM{Y98%hF@EyrW{VPKVU%3m1uE5ol<(CO_TIgk2cExmdVMWD zup(<9*!eR3PAZ}YzYE^{{de0_uk>k6QA)V*TUL|e76Qm_(|q$EfIDN&SH&o>EP-nq zpFUqYE99Qh_~SD{cIl2`QH zP>WK?$fN|t7QE~lYrIKL@U!vlP58Z@UKh`sfJrYOqv^WfsrsL`mfv7{EISnxOC&1t zPCBNjmD+F1@~XSj?CN4r2W`Ug{(nl4Gfj$^OTRH{p@iZ?xL6WHk_Noo{npJ}<@Xd) z(a2f@HkFPfT{6c%R2tl&2lxm)4H0n?9nWhMu&1=;8zR3nIe`zji7YH=*!s zg-+%41&}JM`aMVdaMW*S7I!MV?@0D=cBj6uRq8%if4G^;bL(r_^e|tDP2JDL8{_k@ zDgAP9=UTLewD)xJ^*tH_L*WOFqs_#_a3+}7Tt`Z47xC{=#%e12+d{1*{DM*sh!5tU z&!~g;*9h0Y7a{X=m!vj%z@20Ke)uxn?>%+e$j|0EX9^ z|H9CM4t;RqH>S7ldCvt)*FaC8YG;#;t_ExCh1tDyqOQDD zYKuJ#LxA^pH~%Bk&d7!>(Q(#|l)W)n8H8=iwbe#Y_5=Ut680tQ?t|Hf%jMi5d)Lja z{1OZI29fUUC~aFlQ^Q+@H~hbC7R$8Im}5&5L$A#Yp;s0~qipZ;-*T$&Wv-3*7!%L3 znd@ssc^744;KUTy?&}HpYlVi3pKW#@>1%k3pD<*o$j#ZTNZ?D z=XF!g5gOx~8z=7`x6<^`fir~d861l=`&drD4gv3}4`V@MlpcfXlO^5)j6I>jeZL(m zu*8<}rPJ4Yd8Y;yd|ioKgP0y&#KF;c?+|j3_LU%C!KY)Tumh77fFyvSD_E>i7h& z+I!ji~nSMLw= zUcOBx8JDiLZpeAs_+r0G-%bv%64^ms2VL$3VFR4m#cY|j{&v;)!3Q!B6ASe4^5&ze_Of8FYBBI5kHNl`V319UXw zJ^pfbdwCW4F~N@h+)SujYkh5+G*3H*orPTt8Iw>{0-b@PYOLSxbVv1e36sAakJp+<%Hc9Dka_uB%!5<68?0t5>Wh z{=Lz}l~XKw{RhZXQNgN@bzs(}wRKqnx^{zhf}j0O3`(y_=wftD2c2>2fXs5V&Ef)X zyGf2mOmW-sUM7{*{sU#0G$ri$KU-V&NbHh#DpO3kvlhQ2tEP`g4iMkqH(lhfW}?aG z!wN2APt`{6cs|n74XSe0qOB}98y(2={{gUatsOE`;lkCY?9IPcV2}p`9h4cHPZJ#a zU@Bp;kqQaaM4KeyI*3=l8{-WSpEj#s_`hAvS10Z#*z0l>F>9!SA1LE4+iGpy6S0Ke zRgWT-3f8sG)daOOD*E$sF_oi9E+y7?FDAWAu{AR$d+-Bm9@*-xY&lw2f|<3^LKM|_ z4DpeL#9%xjWG=SD?R(J(wACj)=IVLu>!RA+;KpW{87?7#y%P@n&JIuCevG8u6k%bd z`%(HBa@esHE6b$U?Co&qEjf0$9S}y+f@Z+6V`Pr4yPhtbsyP;Z$t%h(d}Kp07@a?> z--&GnJ|=;tJX?H>`vN zXI&h>j&UXgya=6N(C0^h7>5G=iqD-U7{4uogIU2f^?lu==IxL5YWzWje3Mv@4WEDp zHVa0J{e#E@rD${|>?OnXQm#MRiU$*DYn+!MAo_8@^lOI7R>K~4l8$r(nprPq{Mj4} zoz;(4vL0)i*@aBTQ496D>gKB+r1V9C4TL1Y^Gkb#L1x&RY&P=dt1aJO)$*4oHLThx zaDJyRMTAeO{*+W{Sh%Ti>=7$AgqJ+d2s8Q_v7*5+fV5>4o;}Tvh}4gM)N&OjEejW= zj=BRU${_p|!fiab3m4tF^#Fa3E(H-h}46H+>UGxQce&jt(|EQnQSv#@D zb_>?jIZRmL)+mF|bZ$UZ_~0qT$k^l3cW+QLY8bHCTv^#uJHfo$Qq502dbGhdP&daI zz@(5uVH0|o-VR1#!;hPOxB8=g#qHz4P98$x{kjoSq%U1YEi$$y320KJ`++T`|9zB+r{X!;Pekvi26x2wsW&>}1{Cq<+^xTHLZS{KMDe+KLZH=xFt>Z*!5a9H6nxLKLEwToky~h&!QQVBN_(T ze*hTb@$6nb{X{Mvy@I|FWR_)(*6M!%*2kCh)`pi1^^rlaBV2JOX%@{>sTJR`XXKk_ z-Q85*t&D_TZ`jP!Y(d%*<=U`Ge&&1DJ*9fB5j~x~$>-xnSaIesMVh1q{>=SpJ`OBp#1k;XJu_2Rw$M4D!8F}t8Fjhs_A z#x_D}1A~zgW|b*aDnCj?Yq#4Z@s^=XcW23z`PzJ_B~EIsRun(&LrL#ht`$5G8He*c zytwU+z39Z=+3uMZds~6s?toryAAQMlZB`h^6RCRjR+@{!K=@kduJGjWnVy)wE}5y- zDs;NpSaX~*i`hHd2@|~e0(_7`K*pj6KR-{hY@#X~o6Bp(H9XB3Nm((?VMBG;p)4*X z$V@Sqpsu0-LKRNrjGeIxg-F8)zALyCJ< z!Nl=`EvmC^e4p5Gl`PVeVBY}!Lvh7ugK%dHqc(Mz5D& zQ%GA;U_&58${O}UGE+uMz!-f#_4laIQ7+YP;G)9BKGroRu#gISW_wWkf}t$$Q{^tf zt|HKsa$cobyyo5DxhZXvEFhEbST5iw5+mDTlnZ2W6~>49^v?4p0seLnb&io>T-8cc ztOAZ`*1PVNv@{tFsJdJale?|8Q$QG{o^@QxB98b~nC3#S?KJMYXANpDc)t|hqQR&; z<;#X=w4c%8=RFI`XD_ch7zk>pue7RB>j{LO`QDhZefa}G9g+hwr)i*S3B3BMkuy>j z^EomD!w{QS6FY`=WTux!i;mqk7G#z(oT}fg=^v+KeFdPA1h^3%dN_@wzh7GsMq^A( zrR$lc^p0y+CxW#2Dp?uvDW#lt;x!Z*KN1I(eFgicf9F0b1kNORMo3eKEHY8k({lF{ z?l3E(M$hS3EC^!PW9@FF8VvQ0XzvG~y`Mc>;^F4lOGc3Snu)J+c#jOi6z|Zip(1U#${UqJP*3ycAuU_$v~I1#rm0*$&@oZ_ z*IU**Y*^uL40RrPa>JtWQv8fG#G{HLxma($c4v2Ki+4aUo(0IP$Tk?9>z99j!#Hx>#*3DTF@m zD$GQ3UO6y`s2p`rTTPA4eC_iomJ>LgVS_RcJHA zobTt76cuX8R&{E53chdh=x@D+_Q~3Y-X6tUiC#pBDg10;=nJkBTbPW2Op9!MqpYrn z)n%sIj~zDBU&&68c|$ZLj6^QDJEQ_9(}af3eCL00xM(v{4S%UMn$jg2{Of#Nz zg+#D*TvV943U)fC1U^pj+?<&Aqrs;0n*jKv1ZppCbr1b0Y8})=<f!MKTW`krKt|%&)Owq{aBVxf}E6Ivy^F1A6q6x%dtPNtQ@Eq zz!&3Qq$YZmF6uEzV;$XNh7Ge34U2dW8lErDi*#KmV+WZnfl~3CG|)-sXW_xjQ!LI0 z2@$!P1?J}Xu9tBFlQcbG69dtTmvFn1LBfBDHcaZb1V5YQ=nCjMwCWqH&nz6g`2=P7 zU@tW8>($}uBp(@K(?$&Lctg0=(k12AsX^{9Vv&UPY#<&wK)Otk`BojAVWu#8K?pwq z5Bdu?>;0u6jQo*^XvRKser0=3nk3F@278>aiCQVEck&Y~TPrJ#0jc%;kDOb$zTKWj zEF^;NWg5bv2&;`F>_FV7B-~@+I;}{Bk03Mi^rqs>UORgGX}^G5twkMvDiM*e zmJ)~^x?dX2d3hnL`qF)4$jWyxqR!rv9?Qw2P&@aVnBbo>IOu667QTixJ2#$+h;Nl$ zH*Kas$x{1i&lcR(?*6qJHU3Iae7cXezxfT^9FFZiCN)z5uK)e^&J`BCJ$<#w>cu%K zG0I!q+^J&7I+f(eDs~-E@T&pjl=x%WtU^yi_D)Hc9KnPOdkxhd$ zwpv&%p1_DOV@pp?99rg8JL=BI^V$-AezDYOU)6NiN=t=uLB`0`GO!ySEP^$DJo(OK zlC>LccRNUkmCmryCjB+y`J%U--i!`G83acuy+ z&fm#?dqKk5RnBgc(z+9`z~dEb-^I3h(zcuN9ny&q#rnnL&$D24wP zAXpDo(AJw)3t}{3hU>c0wC6Qc3(ZX)+dAS9WdCa2w8R9u6ma>@DcEv&imfwDb~TlC z8)Ou?ILgJ1i3?FMc;GT<(MMs6VCYAz4jf-iG=X@XJ}6*3R=_HzaZ6buQHDITj}0m% zI$o9oMxv;2ywyk{%^juOap@2*D=xX9&Q`D+ZDVT#ic-2}HR(y7B@E^TCNwBt1NHF` zySonu3y>fA`0O~$Lz6O4S1P?2PM%9fBb2MAuXYjRPX)6b7t4V2I?G(IS*ixTO{#wW zbR#L8c-)?rVbD3CtG(Y`ES=?%l)`2!&D>xhq;&0=MRTII?$fIa3Nyf!_-hARkBd3x zP9|b>$P^{UXAGLyx+cH+LZO}WLyu1Yg$IEstPgQM=Z#1Otz)>|){8lGk%Hwjkao4b zO&GfPv%-cGQ#B@5D-W|;3ftt14=D9ziTn`MsmLo-)|j7~KWM|xM$;2ZI`kV@Ekv$yCgS&Iy7 z>WTu@>hDeNo3YIf99~yHbAr|C_369dmKpO zT1~AK+bI@2is;>HG~Iz$l_>76m@EbiHopfNzV9jW7p{SGs)0 zNt3K)VzBhNP2Z?;-GHe<{}Ke>g6j=NKN-Dzxl}XhAFpxr)K)YK*)8jN3^g%*tH7yI z*Q$)Wn{%zOg}H9n{c=S1U;Uu}%+J!&h#CvSfi!!|3{h!S3p%;n>{2SgnrIdot6Z+W z;EE4UZui;mE7wM;UFMdjy9e-Uj@%}Fn#C;j*05mb>IpImnUEUB)snn#X>ZD9oWEA_ zFT!4U4QfIc+8yL6;NZHKtxk(J32$>y35t}AQl!xPxhF(6immBo8n5)!wet@AmKSS` z7kdyFJN1FCTF6PbVw@z@sfh)|2Ygbhih-0G<>P7>z-x7S=JGKo+D)7wqs~;S7uO&l z)p-U1D;vh(;i^t%g-jM`G6iVxu`g@de5Xmmny&KOq_BQ=TfTK;Ng#Y0sZN_hXps5b zhTBJIH6&9u#;a18L_qFji30a=Tl!6^tStJQ715mMzpTei{bYpQWBuc#hBh0oL(xH{ z@pie=>;s)kV-hwm>(N)V<&&y*{(k3_(aoXgw%V>L-14vx%-Q^5(WSdYvPSokYnkJ# z{bzrLoh6pi1YEWatPWsjkbyChUg~}2KskC{A%QAx>h}ji_P zCe2@AfvIT=!|Z`!FK1ciQ|HavuOr36rr|_N{mXwjc@N)f$V(ZUZ6k?+s4;Hq3%Q?B zoZN-;Bo8{aM*Oh=;jP<#D*T}@$Sq=j|A{WP@#8Gefc0zLO(yr6uG-4xg2 zDElp${40~k0O4ZJ*T+dOK%6)uFEJskYBs7(Iq>ael5`25)8;?o)0jk(^BCEO2{+xM zGbg}lDXmQ6w#v}Wy3OVc6X7MoKC^8gC;uej%RO5swk>DB8l zA+jVoWYs4uKa`Ef7%fYsEPq${(M~jOAtW!(;cL$rK31EQ*!%>)5*ageJe~pArbj7m zpU5`#A#muV1ceVsoiVbuUp``^c-o9A01c;~U zEP1MU?n3<0wu+v_8(?%0pgF6f_rNY&=o^)<*LFLPCYUi5(cC;; zmnkqQ%iJQM(0N5!NXW!_Y2AP9>2X$rOwXQd0Phk`6Nk*I#I^Aao}=rn>(ZgrSiYcC zT^u95;$pWzjk%Z4ius$llGB?7va0ellpI!dJw>+JvaR-!j*~f$<+2BsECcYyOihW8NXjJCF_AF=;BrKw@Epr!KCR5VzxZq$@w?z~?EW&SR~Q ztV17*P195PLW*QZip|ohTfOlku{Hjlf+n{owV$c!6%Vp!jYL`D>+vwfBY$oI(^Yvq z24zz`iwBZaSt|6;$jaeNZDmC0;3j)(+CBC3hheMJkIZ(IHLk}@F+*OWvgS4m>Ptd( z<*3F9c|+F2EF_zMI$MReRtshIRK?SzvIsKK{nY2enYG;Ud7hwCnox?(i8aO!N^6|7 zcpO(58Fg-l_bX?i*)XJ;5cytRd}gbG0pN`OXRR1^<=fZY0YFQnJ~h!FhMFSZg$XT+aijl zIC%HzSCVm}6C~il_ghF7j(hK0Jh#Rs#-F>oa4 z=aY#|h}TTByDq}uzb|K7vi7*RY$W74+gTYs$0gIFGRlSha~&8Eq2kb>)?`qeByTOr z@To;a85~ojqs^Yh82@v=u-l|^hdhhv%@uZaV>#{{m05O8iLciu+_8TEVxYUMKLFT9 z-Ok#?KblQ)lW7sQ?dfbwI~%i3nPMvxNfY=Elj1zh`)~ zSRrgdHSNoYi9i%}eB-~+8Q{PAo~e(~wR>IZJnEXQ@Pz(IIIe#vxHqOuzrdJCrxhao z-nY1#-zqwD%54)*muj(F`k>HfRM*zAk{d1}=>;&`)8{so3^bivMS-}KK%rjIx12$C zHJ96!33+QSX@5p}_jLcUBR=FU~%Rw6J5bWQmxoa#1*Oq4x~4Msai&ZsLSx zj?LV1Kk}ofZ7VXVa%doBLgh{N3kWOnmup6G*sqcW)MG+s^&M7~PATgf`>aZC9g%P)%Hl4dv|8#A9rPxs+{S2`d&F ztct1ISbZ$Oz}qXOCX>Libwrc8ljr1BMg|Qb58bhF_aLO^HEz$;IqWdg{+N)Y z8yb?Io{;z&RBR9#OXJ+K-ogSW^phLxJ#ug6k1V&-ifWiyUOGh zALzKd$;zs`{iUu4Yy)+@%E-8d=KD`K1VwZcS!i&Chfp4;l|Q&=>MVZ zE#sPe`#4ZQx;qEL7#-3L(rk2XY?Q?4kQ5{okdDDdNK1EZgovPYgLI2@gQBR2{(TP5 zqyO_cpL1TE^X9zUi#xX6*L_{T-?y&4Y`!Ug8B5>$vr*~fkv;1@E4l=v{oUGQRVer{ zHix zQbPrJSS3u6xJX!3lw6gq%57T>2^gp3mwE^4E7w#;4tefY#OiasU&IqmX;H- z#a4U%l(7JsMTuq_DvvhT@Emgnt$NcDx*UZJ0t4(>OI$0)YCKD^fxEnZ9VZRE**#{_4kShJ2Ox#^aujeXzPbIxSyrBu!EseF0x zbpbE40fm_ez1qz8hWM{+f}h4&bOz0-9o#YwU|>@EIfXG%FZ>p>`dueI4tR21(U((h zEI3Ce8>3Js49bG$6?v4XS(ovWLsJV_7*z@VLfO=50WtcHCThJHZ`PC{y2l61n;aA% zO84yE1Xet1fJ)dKk7In{9STU9RrZI!Gx?i!dl`EP%9`Wi@8GZDi?-)dLVWgg!-ox) z9nz6#kdZV?OUT+uUd<&N^uBkMJPfAb0y-tifdc}~8R9;G(Jo$qJ_^GF26L%z`p(@Ka6B_`IIa|0PH^eSTDq zN!NR9nhwx2YanDECQSgczD4RUjXe52DL6|E;?*n!9_G7`+-k$t*S^6PiUU4UqO5(h<|nmfx`{3 z`!9*O5N@Lzo}d?6Xh)1VUdORYNGJsyqDWr^QkH)GdT!Bf^vrf;kFsaXB=7~sC3^O2 zOx>#?M@@h#JK9+VNB7RhDLYzpjD12*$>ZSB=DG}neExS{p*RQv0x&NO=Bv_kTv)9K zR-drXDy!UIm0}fJRUZd6Anz523VA981TAr-#{B4@BFz|}L~x3Ilb1e4?=Zm)pKXvU zh_-^2zn5mfcLgt{B8i1!*W^a8%Q=Hwg0$DC!7aTB&Q~d>QVrA2V^?E;=!G61@Ah}B zp*oLsX+orp5)CA{C=;NH@oJOw#X?NM7UT$$d^b<&PMq(+i|2%aJDNI$qXZkdGF0ib+?xNHof$&M+^Q|JJa0i1 zkBPxjHTQ8kS@}4$O0m_Rl9C6K@x$%z1%#*2lLOhqt|2Z)DPmsSvZ+B~Y84{#={%;q zd)2QqQh+C-yxwwviiQ2F}>WW3yY%<+-yX z-Et`qc&clB7=Oz6ipXO|CAH%v?|5Pq`Jp~hFdT2|x^4t?azuy|5t)qh!_W~u^{byh zZ0C|-=1;rTFUd+!i&p!2!`PrvL~rOuP`2S*@hCR?CWxULgLaRBWVA(|r4ae!4i`zZ z+IQ}j7+xD=3IW@I;{(hRT#sU30-}kNvLJ19t{nw+`IE{q#TNg9e!Gk@vLTL6A{1o} z-AbRFs38$9L60V7N?y;8b|ifcrdtm4|GUWT_k3JqmG}A&-gFFcIN6*a$B2e0p{UQX zHfD5mWnpUxC?NOIcedk^_U;0aO4xhJi?pL}udL6XzsJ3k0@(2KxMij*or?dyx-Td8 zvvFfXCLdPzBU?sCfw1~KdC=TnaCusi{5_L)Xd!gwYOSWGTfxr`SZ|x0TvNJ7MAO&$ z)VsG)M^QmffaC`L2X+mguEr8Peqo5DjKN_vvM`iFu9AA_N?BIJ#8;xy-~0j2d&TXs zmI-dQovUc@g_pXGnUl^a{oloU+=!8)cJ zm?XS;Qb(Na#40S4o%n+`JKMC|cjG|)@#40W!>7W0!>Tg#gCz7=rLj=+omCQeJ6#M> zBFRo56T-5wSbjD4lg9zf#*Pb+`vX~EKBli@b#gGa7zIM>ETPwYJsZ5%9zSCtR%e)Q z(2mzmO~h+g8#HgsfCCTeYnY3LN~yR;gTyt>@+c*A7=>&ecoWs>mte-`Pv>?P3!~>+v+NtIG!3?hNrCLl1C%}}Rp_n>pLD(`f)e??u#8?e=d z)vdZjr0$Fs_1^5a5@;OoOfIzXTZ@`)vPuHU1-GgDhT;_*7kj#)cZNjKYI-zbbrC%5 zgxeF->I6Ej)*DM%21m+n(Iw~aWpfKrZJMBXhzm5{eKampix-&!%6=XaYuWP=j6Fr5 zT3W0qSBP!arDGp|?N4F~hD^8CP#$U?vCLKf4`4L@+GrIUmgH14zV}mf%TqFfj*;_Pk^8?GkR^rETA;zSmKSooeS{Q_y zD`a?f4qF?AzDXdKyO==2h*7MFJ66 z)MNvLW0FZr^n%SKi$)C@MY+tGN^14b}zEEt0u5PB{J2wbWZvjDxkb=Rr7@-R1 zk@^+b-jTd1F5}M#(K5>{^;-pCqC~EAm+2Q|jK1X^MUuzPmU@5?$xv?dIJ{H*dIyL; z+ImJDABVoA5$QTBp7N~OE5ZevaJkJ>UQz1!%RTx`ZmUip@2Q4c`Qdw5uSVDP&hRe^ z5f+GUv{E#q-#G^#Q;THtEc$paS$y>uAjTu)rbcUSlD#WfoiK^nTxf>9tqL< z;t}3#dRzgA(In4{19;d43{)DDC8=m{g9FDB6JP(>I3!UYQ0MssW;2u#Bu{zAS+l?P zfQ7LC6;E|e+tCXNsbTHlwy$3)!!_74s%kI$g!Xb=-#C$bSr1=XFL<&8^kUQlFHee$ zyuHQ9hlk1VUn!~MKXglL=0UbrOAu!}4DcLu7S7fklJHBoP0;(g}3WwXSR5L2qv-PIBQjX@hH#9uMMu`ZPJclgnUZkJt4mG#o zOHqZkZ1*O|E)i9VX>o@;D;Ldj@tR+V`a7 zc=!5}B?I`fOdqfoPNWx6#%fay3=_3)lFsrimN=1d;)VTo{Zk1iF8lB< zM`I~qa?yD#_jt!BKjK+2aR~iVkFmPx_Ui{F0}T|Baf^sSH4ofleN>UPC{h`k5k+{3 zvPSX5&cSjF35`JyGhr*&%X}%40n=DH!Id=K;iWH3))9}SIbnu$T}|y?yLn%XE0`G0 z#a*~dsU3Ld?($_DYELeKx<@vw`&_jHre}DX$T_g#{tHer)z(S&-{KS<$iFYF2jjqL zpphks(NjH_*whSc!$%svHm4V{G5D%w|Qi4&vB>A>ec zu91lo?9~taoJVz>Klf2YQ)&<~lawH4uPSe0qbX`4)zv>Gb)Uo-Uaj|@0mMHbwQB?okn<_hmDb;dlT;%$%vZQU}U z0O5fWfopenKCeLh_~-T?oM0;^OoxzIhF(MI4Zu+D<`LeWrWRpM zhGI_((4>$f^Q$kMc7KRcyUakf=rT!e70aX(=Fk?-e=w1h)-WY!sZ)k_Rwo|z zXSnx?8jX_iEsA2fP^F$FJoDf&@{fDSrIhqMzAoWt3m>?m)9ye$#;`Qb2romMaVSmC zPLKe+W4p{U<>op*S_X|r>@$COQ`qsCb0flYaH`t zMj8BoJ1}U5og+gxgVb9m5t*fQ1j{deqd8hCcgJ(SChpU5?t5tpa~m5Hn|HZ8a(X!v zDxpoI5iG0f*|jGAfGJ#?1X!$oB9v8#6w zgFa>@>NA(2?eg|?uu4YqLeQ0?ft|i!Ydy^ODEDYCtam92FY9R49oy)6YMdjP)faPy<%Q!(Ics@91rf2a9gD~sFL0dt z$Kh-;7=E|Qp)2@Dek+x6#CAMVAc;=vel?BE${szP$d1Hp86Z@fU2-c8JFxKzApDwb za{|2eoH0sJ*lxwh(cf-$>H+B`1p}YdbZ-6}!YSg6JCr-oY&R-&9blXbAD0!oNN&KE zPH3q}vRaP!HwmW+&v4MX-fhfq_uRJ$pPMO*#T|W6@2{(-fiZDg2ivv53`=9gBFONZ zM+j|~WqIGjz-&}IQB(!nhZV!LyR|W$*!;lriN|TrD7uC<;|N?byLtZw7P@J*HT#cU z!(?-Ea4V33=}}n=3$d&ZLoFy3&Hj~AC)u9!jn%x5?+SQ_fo?w7dbNsb3MV=O6BCVx z8O*buA`m&B>NU&$|KR;di9^{mJ>6}1{d4BmO7lf^m?m*-XO2+0UdIG0MqDbko)@qz zIle4weQsrIOi*t16Ra(F$LW;k>0PbAda{bPQi9!*o!!i8S!V*IflWUZ2L>Y~9I|ys4)=P0ULvjJg4TLemuSUgrD3n72B2D!Wqt zhkmSadK}M-;_o01t`mEBl^T0PasDyNk7NiK9ckg-jgMsyK|0bor{@ZGGkb~1+02=k z^GPO~2FOYB#zUaUPm(4wnWv&4eBl$PdgM4}T!Xzm-r*r}XQEycXHT>tY1 z7m`*@8LC{YNJD%lrhB)Fo;HT78$84;gW@_r6@e!|mgqk|(J2r{4SF3pW(ZR<+Ip@I zEpaGwfBdUCfQXvCqu9<%!|?cfmUMX$27)qI-$AT32>U-f)^$FvFs6$Ubh`_qDrX(g zMImV=qu9!mD0mWHyZEa@ug&OFKe>giHG0F9w|NFw9+-&|cYc|)puDi&omsz2#$Y0> zONw0GGk@b)nWl)NJ#}$7;0o^z4))QYZCIES#oYA~^C@gM@D|J;=ED|IW?@LV#rL}_ zI095f3BfX1mt>d?fQ@i8_Ly0dWm;fyw`j!bqosUd?UzMi6r z{&Ci2ydfWeX8Gn=c`1K@L(bBiMP9w1ih$`Y2k@+cGIt})+QVZk^?G(PDJ{IqxFvY% zdS~6LceJ#e&|{TqJX>-8yMe=JGEp5_RMajx;dR|nIl%Jex)O(`Wrv&@m|CcWnzgzJ z{Ji^b4Id&gsu}H)w?W@O>_ygPVo$kfWSC>|A3WxMg-Z$w$GDoMkWnD*a7K&^Qo_Zy z^rSRzdv>m}fNfm=H$N}1wANWj(Lfb~v}%(qS%j6?S<<+{Eg&ra*EKu+I#9gfco=6a z{?JM+4k0@iAqscU9~I2pKzmwGlRVcFSfU5=zeR}6 z1&ommF>S{HrE6gse1o869rVWd{HZOLpWh9`X-xK! z%3#=`FjPy;*A87)Ps@-$bcFs-49xvA8N-5ULq8LAM&Y`A+e)~eRff$HY(Z*+Y*td~`*)Zgf-*@eFi zS6?kD8KfAdF6yJB`~*J;4kqd4i!oL!%Te6%#;P`_UZ?xyiMM>3C@-@(s1NjE{c7gn z*%1MgupPVH2cJs=kH*oWm!DT?*?d$7 z*vEGYWIn}iTh|jN&9k1aqt_j6Kao)9O!;_aBn&J}IeT+j>#bD;sMvV^l-!G8C|_sH z1Q(g#(=)1liO;2q*l7`-ac*de5-dEF?y7rb?Aow%sLrK=XGOS*1wB@adT9CPcH*2z*=vdCoJU~I$cm*i?977cInvF{*t?*aDL%s+r zOYA93la zX-|g;x4EN>@$n~4FowC@yv-+f0#8nN>*@ilg-xEeHmhm~p+2U*`PGgUt{$f#`Y%X6 zI!4D>(H`x^zLGrKekg-fAKq+Z5`_Spot(0{PI8fiPsGP?XXoPYyojVMyO+LQMW4Bs z8A~^*7>RioyFb|DCaK4jA5bh#D0)+!3QB&Uh@M2#wxQLPy>uZ>eE;B_(+-%~uvfggtq+*8fpj&N5LoGn*9qOJa1rGM#`wY*v`-*i z#;NZTZGe8Hf!8c0f1LZH6gvRh7!{OV`~;0=buRB>PAjBX5nGd~NJ9({@Z~Sj2}F5i zR#5e|z|Ea?+SMoo)jQZpKWyrjhknvF(f+$|1w^E#DfFCsLc9qdxYsP3@0GTm$suIr z%!JD-BxLisll1dk@=m^gp$c%%s4xXDNgs2*_%aW{ti3!Dh<}4#z1^Tp_6qgx$8mGT zqo?nTB6(YXhk5<)mGj~Q9f4wmZ#SY!SmuWBR zZ!)pBB&lJOP#_u9BKYN>Kj-sRf0_S#zQkvma9gd}iBhptVy-$ev&R2jaCuJo{$bVs z=llP^9L{(9lm6Z=$I1vex@Vk&hSnvg^m+IyTbKrL_WPdwD*(zjr}Hr#JKbz(t!PU= z$aUU+ATQge^UhsN5cJ4xNk@TAq%UzNm41sEA%#DuH>@rL!9RBJXytNKbm=94XIQ6uqenU5IfH-0 z8)Jn_eCdi-LTLhGd}nRlFq%eL^nihlfyh)+23bOyC<&dQTe_-zMIIwRyKgu03_qv>;)pNNSZx|382T${bhbm~ZQgz!5ki2Ltl%gXpALc8sQdbrTXCFV=F+wxJ-IqMH`1)Y` zBhHLXXQ`MVFTkWLgeQWkRU&MA?7NG7%!_u%082@jV25*iinNjLMitf z!@B2<8=D)oE{6+*vY$JxCbr5~Q=-SOP)Ujs_dnQh2r5cnof`fX<+U+r_uxv*$R*)CrU~sF5=u-ThUb zuI1D__LUbf#Px3)w_-gNV|BKdV;BgN^k%fRf3i(u#}GC;lgs6DrY5_$|#{(5EqcANiA ziq$XB;v(L5%xAsu`S)x4Ug#;PPF1Vc$WhPJmlqm;jB&?ttvG^TIIt8#*QP)nr{%)k zl&cm`x5d`%O*=v#h?q<90GW>;?-W|sokYC{&00+33-M+K-%26Oyya$ z6OhGM>vK3;#r9DuW#C|jd6{<$Y$qq^`_W|@%DNQiWg9Tti=4x`)7>Ucs~jKsgsrP2 zle+*NhukkpM!gbf^ETP*Wb5j>8IHB~lk}-`KSz;b-%$gH(4c33nH3YG=L${PmZoo8GVaB`f9^h9a0KEab4~W(N&Ec8h%&JE+QmstQqp>sH2L98(xT(3 zYoO!S%9z~T@S1fCzeAF?SuuTUqiECWMzYIDvf3T3Vu#BX+wn)=N^|6{_21NFlV%cg zMz9mCi9pjB$D;gZ>HTG9(70}v+zKm2_i(YaagcArD z0g)0c$mwdt>#ay_&(vh~rqUN>50_RjD7LO*EAhbKuX=G|H)}^x{8a-TyACFH1^`fd ziSiwHf)G zNwIHpPRx+>)L%AN%7fAaWOI>rxNzGfc;my$C~lDtDl^my7x#op$<+$K^#ipYij|}S ztGEiKmtFR9_kFgUs4VpOf-bmIEKmiVkx}h2D&+!53B9aX57RrU{xbttkR*cJ6mmkm zkOA68PuZ51q>8#x{&v%`Ldg$e2fBQzP9}Kvxqm9{o-e+H6e;$<3*(S3hIK1+Eggu8 zy!S%(hp#UaBO@YL{;<`NGIJFY5aF^qOM8=0O*KbTUhG-kGJORo`57d$5@)5yXNbct zz6$Gg-(_)7yhN;0nG(ilHG{nZ$WI~6tbF05A6KC%-cp+S_n~bX(8(XWr!E4WpB+%T z!#~Qseq0N1sW7CMSx3K*cur&0i8>~t2DyKBLoxr?DDt5m(@OgVNl?%TV@=h(hMO38BU~|z;W-_kO_Kly$XzfW=^q8%9ty^nD zHAJI4sE^#j=UHm>Mp4!i+E~8Qt-&%THzS0&c;Ko$KP`U;j4>;Dog?vbas#%G= z)<@kM6Vg0^@A>%XfcF)#3< z*L3gdCTZvSj8WV|p7KG9IV$*xBm`EobxM--&yb}y^mg+QXXj9kvmKm^syNVbcuwJ2 zWzbX?_26j>4Wa*JwE5x>fC-S*q?O<(FD3GE$s^|v^n-iF#x!$^b=`EM^~ZlHi1*>^ z984brc)dSX@!8RiV+XD`)ZVE5TM^}j3j5jNr>{n5M041%FD9W@?x2&gT_jM?U*k8q zyecKihGUPI%G7Fgiv&cNMLRSISx5(s|AWVP(Y(+ti!!%-Z(7;`)JCjS%qtMYW2~mf z_)x4%5c`!?##s|~2<7dca2}wj&~9b{E9wyuux^VsvYYO19OWdcbR(^8ihk4VxcCKx z4Fj}=nt3%CM7Kt#g8NV{wOmg+?-}?*ZQKZ-(0c~yR#h>}>(~N}GcqAHQgrM|PW~1f zdC18p{SGcjnEY=1%zN!)!-_`he8*^n(#Q%8)v(Rh{Bi}y9j+9iCN8W}uBy~uUEL2V zgvAt5T7=o8zVniq>AV_W+_x-zBO7%*Z4sD<6Uu#K%-K6NMW{Z`6&xia$#|Ev=UWWJ z%7e6dBYn|JLrV*RimrGH0Is8Jh;C~duT7E9qORQie2!VV8qTh5Ab;PeM?4*(@Wu6& zxEX3pxs08NgmyzxiYQeY9=#IA^0I0~KDp|d!$OIMieO*kKQi!PanTPr6<>2AICpM` zejic($yV}WD@V%`3^wJ@0*%~yX;ea@)c;j%>Q-XPFYYJVI>r_zHIXzs1pBc%EObOs z_$z{7%$VWdwc&e!UQc^s+Ra-)!t%(!Gy6s=WjH>FvBpM}Z##1`V}NRvihlETf3`O1 z>I=f;pN1}lPRzqX+h~^ps1t6-WE2-2y9W!fG@G^+95F!h z1rEcVaQy4Q==9XkJdvA#5b~iY&?_>OW*nx)oq#}+BnhkMM!JN^a9jadka!6yL~anp zu~<=zO>lF(994}-#ar=KkD6Uhm7BrsigJ~V+;aeSN4Or;=~p$-2C|vsf655QCgRf{{AYTMiO`lhEbzm`G3k`ldHZOBUm}Ozr9NyS27++79 z{?TpJ+QdSzV&YD{p-Y-WmEJeSVL=-`m4f6i-i=t#B#$~f%72K*Jkn`gy>-7~hWMLu z*%LQov}=BQDLI@MuwzClvfDIZ`agCcF1-I5#{!i(P|jR_L`L?$s^A-m>KOBx?Cw$^ zMN-3#1!_IO=!SGNu|dIErJnjwvl$7BqQe57r*NvGl!S;>@5)u66w8AG zu+5GNaTeR0B+LrPPoK2Do+;!e{7*SLsnU>hPu;~XI9fE{aU`R=JUU2l`O~%zuSnxB zW|dRbhhag13E2%HIzI!DjZBM~??CS-Tb74IxzUoEiWPSq&3it*0S+&DyGpINB64uud%(B{L$+C8R zbBsEUJGbg6rxBpO?Uc96;*w45Xk`*cQx|Zjo)QpZIG3}`YZfjL1*NWJ%9f2;^0$|3 zH?u=CU?3z}fbg0Ym*^3+!vmF>VQrdt_jM3Le2H!?-;T2Gz-b2QAlhrE22A*P;1}Gc zDzDwDVXMMprw8L9Z<}9uh7>0BJ4X}JF75u{@C1wV`WL274F!Znn9*zxvmeZ8=zCSAtF<~!OYT$B2E4$-hM zu}`hMpBk)MPU}&dhL-f5j90pyw-u6iM&d4$T9eSl-$(orL9r^zmykgGJ+?+-PzS~5 z#WS>0+?gO=kZ#qkau(ip3nGslc&*oBAJqx>YF4GxiHeJedN%wb)eof94&*(O0@%x# zoF@imcYX~MC`y0y0u{CQMfQB*y2}q5l|38m5_gy*dlYin8#c#SU40hvR|E4sHTEj! zGkMaPd8e?02>EDfag>XTua&cyk1b`4D`ni$EGv51`LeVl>1&9+SR-F)EG&NhSvBDy z;<>*IqaUrq0dxP-bnd`~(6i2g@?i8O;mkb0;157n@I57V<(F$h85m)5h$n{E!4o(- z%_Cp(AH21=KnaFQ5h69yl6;^8^3&)l@FSyNR6D>-qIabV6tJC~0gZtAp5kde+~D3to_0mD_y=UgH6T6TKmslH>|qh{a; zNKWW(;vMd27UASlnvJ*h`Ga74P+H==bN8sOet+Ex-l`MeI64UnxEXe4mdmLXgTiI; z`f_<4&MHVmpWho3BLK;?Ryxcm>9*JH2LN^MERI|H=+^$AZU2a3(KZ}fv`_K^wG3yf zn>>cHC)ah;dPx{&&r%{8An)5s>bqbA=Vtv5)Ywf72r5)kXI)0NsM`HHuZB1vR2|%3iDNP}A1v=6ewd z)H=Uyah{`$-*y6YZqd589BNQ#C*RCQE$=SI+pStn(fmVurz2ei)u1Q*EL8N+bcIyv zQ}Juz@|YaC3`3r`v|MJ`Q5#X?IK}e|-a4eHH$A=e<~pJJgcp?Xj=LK%8=+C4DPn1* zCumz8*-AN6@V=vi{dQ)~LXWvT;^`BWmyz>JGO%X~C0nV8m|eApEd zXA62>sCP4P7nptY4SUzLqbSSu>tOO`pTJ0GoI}iQow)e+gZR&rNWQ?Yn$V;+Cnir` zLiw4$rZZw z_s{y5JRuilnf1-A<|HYM;#M-B#S*!eJ||^6^_%A-NNjdx7cDDRV6xg01eW8MNr6ns zpSLO|jet|;tgH?%6>}|Ms;$yR)4J`p``X}-joz!v^OjPk$3FC%Z`(x0V+^bKax-Xa z+<;Y*jvZ}Hkw((J&$@p#VvMBm>ssWL{EiwLHyu9ZDBfCBB-If1OL|w!oV!2A5?9<3 za}hH1w-ZL5YMWSRaxQwKY^!CZU#HcC9?p{AFAM&u#YDHr#BG_*>$P(v{a*Kvz-UwE zQ4XL*(ZblX{bX5y=)f89y_~(!&H^@mt?-J@ZL-z6kiXIhmzkPZypLpSc;}%lxcJYc zNYK4cuksizYO_0Y94+z|c)nWrFAiClBvcJ*^Gv~BS?_Iqj6lglc;UmBkx*xmt=|-K z4~rJI79%UZf2}y+NP3!2d$DOgd^eEvz1J@}_!h$Qrs085-Nf;#i^Y9ok^Bldz8uiD zQdv8cWolzM&N~)t@O9+%UzNg}Tg3zw55wrn_KhjhzKdlHP3o~evlUL$y636c&?q415;0eXt;6ZMYD!4A;Kzbmy*^r&FA(%{ z)Bk+wT_0)qoAu;1qs5LGx=6&!RUPo26qw2k>My2rG3=me(cjgr^SRBDhZzwihxjL_ zuou>>AUUV*7F#dAp`}75b94Offd09_;BcI#7U49h(4tp(- z;QKq{1q=Jfe-YMi13d24H3S5Z{RO*pztsW`zF3r(HNIF?@?(2#kd-sEz2aNvF2?C| z8S+z0f8m$XO7>g>5!x3J?VIf@Ki*X$!MH(;W@kZ_7m3o|=U#1XW3mGX5alYum)49l z9U}AqNaExI_v#(S5qwQvE|~nLaB|6TVz4z-TUmrB(Vyj+n@m_IztqqK!-H%i)(go6 zIU@o#goCVtYdms8wOwu=uM2Cf4Vj{ia079Sg3`&y;J+@MfXV58 ziUaMPT!r~F}p5nD(W2umqUmXLKZ{uf3 z{PmSHKC_#N)$bjrp`*}-bGyb=-zU8Zw|4FGC!`!M0eihhED!PWHC}&T+`#UmwY&I&L z6S(LqL}%_DM5c%|ifrN|)EN-FdZbdoDRE~5S*=y!X3r7rLdt+n&7P-$3FRALWn)!B zv)^N8aMA0XmCCOeJMH8QEMUPi+scn`%xwY8u#Pac5rxeybkIJ0wA2uu{5{^pi1mhI zMEgiBQ*{Ok8!&;XhMw%F@Q)OQvowKxWn5m+9(;?a_Jo+kZcfOcPqr;D7 zF!7O4Y8Y{0UR|nQ>7EB{W-`@(rAd4NrB5O9;mcTQWDAYxd@I0icoRjaEIZ z3p-`Kv+*eAe{6nay_pb7jv;AwIY7xz-KL14BC=ky71~m+F0kUcYPBMol%&UUuv8o` zGMCK1xBPNQxHOP_4Go(0+qt;7|8rCP-|ppW#Omosylxa3X;cAefQ|JqOh*OX-MPxK zaUte6ASJkRDB1I{lTnm7^>XaiQ@|`{ryZ2jt_ccA)pkLRZHMUJf3o>YtCuZojp{C5 zutm$^y2A{Drzrp6B7U9|8_L|L&!Yf4c(85W{>*62t7U4qbSgoc_({dZ&EE%GFY$}V z(!owVzW#Hlm*)<_sOAoKcqFGT%5gl+IfQgVEDXFnoaSXlSCd%0?H@n;z9AjNFOmEM zLl(io3m^H-`iD-m-!Jj>qe*(>HbI#I#*U9jZhZ9*UV0|^q|s%`w{ucl6wqx^;M9U| zOW@Ms2Wky`*n}tOSB0=5&@5abDyWmb;iU`ZPfxFFDS9!mSqFspBzPV}>2AG+eETUE z_Zmd^e%h|nM3LC&P$Qg_3|yw({tV>{xkXo_dEDfd5sk2YGvky#8QVy+Ox>h|->Q>g z9pHWQ15d2tUs=reezR5+N&ubt*2}qh)(Ed9+1&Gj7%c{F<^CXMFMnO0X*Z4EsNqp1 zG{9`WgVjQ=$qNl(9t5-R1>S}bSk6^5Zgtgh*V*>2WmX+iT#&4iz@#w#l6_RZ8c^Tw zx@6c1fr<@Lqr4n|j}vb=Y{r3REFggesZ{BUqx38nYBKdDNX-rG$?O6#Ohx z0of8=g<<=|`F(p4wtoXiG~oL0R=y<{f7~D@5$I!pZ}{^`h4GB`e*~l;xpv>weZt>y zYlwiPs(C&M@r^rdW;DF%qOV{LHB{5DZ}BZdZ;$SW$hlFas%v<`_D_42D7blKJm^0C zjC~bJ$fw{T#tmWrU#NoRck~}N;JfYc+jCjYrm}nc(stSp#$CG--)2pL%-TcS({vux zPgVOL-!nKpSg(ka+vNl+1S!6R^4K-MJ-rT6th=#irYQZ^hSlBQ!D6jyQhpdNo3VV( z`@dZ)nC_`i{t586h3taPuPU$q9}cs)y=m1DhgAxE!A9+QOzKf&Q-np0p>TA}C$k?f z(ZqI@Z%==}le;%}V`DV)(;8k5{eOO62%~$qxm@+5zao$D(ITNoi!%R|fr(|9ovL7& z)<57vytlJmx-#9T5hFCI{Il3j4lK-S0BVEBTlUpHowre<9j_O`SixoVwU>rK7(N&o zn%3OJDyKN@y?nKsxq8q>t%x=oO->oQceK-k&x5d4q|(tXQw(kP|L-^tQvC{X6VzIz z5K>Fv`ww3E%i5R4EQZv2ZWa!`pn7q#3yZl#(vl8XvWj1|T6k+ao0EQUh-SwJ;IPl7 zjXb^|$H;TSjrs=GEF|?gw6n_5BoA7;2;zPHH;HC*B5xo;W$K~PBI~E`jL+6`5CQO= zL$ssG;0W&+u2RgqTg2Gbx!}L6%?B?}ON)Y|MTN4eI`cygDiP+&xO5%cr*TxBttg&R ziA#|kh@mju3TGlrvc6xOfUVA2&a8WhMmbCEJZ{LxT-HRvzx}@&5rG)p36>H$mJBl5 z!LKNNiZF*G=USXuA20boYvvmBpF+C-W*W}!x1*{i&QA*q6~76nvUz3FWAlJ73L?ME zCPhmsjjaoRagas5e0LP1dzJYCN;h>IuWrz_ykP&r2KeNI+<-4_M;4t^^>ixk;KSK3 z3)V@^hS+Syj()692!Ar6vCvV;A7$M4*I}XJBx&gwuqy|b*r7VKr}a!#9O7;&N~x~Y z!E9%=LZBZQkXIyY)X)JXU@uc`g1DZ0^#49)ktZP4&9co9s4~-T(UV|E1`E+93T3+~#N{%;_VZVOcZb_7<@i_bR zip#x6y0)gd0s9)>P^TZdcfNVJbjZv7nOD2>@NaMbttPpU1(M1N9HTPY=#4|z5gA2j zP$r{q1!bi5bss49HLs1tK~2t1+EVPM!PrC7& z{M?erEn{)OU+jnTl$NXEv?v8%dPg=Tp&BShVgDhaX9V4kMh;MzkW_=|6dNth-F}t# z`(MN5jhZR^^|QAuywNXK0%gZi%FWcdtVbH_yGkPOcPBsU`h9G1@DskY7y0@n zAZ+Np3e9)Nwt&tbiQCAdvyMI(J2Il4++~6IM*t(w@B>oerlW zj*+8+1gt0WAJcFT1=)nMEpK98#A6i~_09B+t!a{wu0`Yh)aLZQsV{-pNoO-GKP z4sn+*%CMa&;5{CvNU_oLu(b-WXnL|6AB2CsR=I}v$4xM~D0!h$jwfAt2%^tE|4p*> zPo;^tWb?RD-xG0dW+hCS@S^H4cvbWv3MPAb@n}L2qIw`g-t9NZ-#wZ_{g_+8D+ES4 zOuV?Jn6Vl7x0UTr8i>xy6JRXwwa!=fa0e*Ra5zUBsXLG_O!tkO($ zPug_mfC3ANMT?f&JN31Jo~(yQk6xuHkB&0JW?kbI_nhV)EI};?Ec~ud zQwHdi**>zRyF7gT?_0jt`3YgHW~X@k56UDB?iA9xu&OiryeG*ihb`?F6ZCA6iaYe2 zHJe+yME>xUV*v%EGG(T`==>~Goq;&olGrQgJMtcQ;aqKGQa_~G} zs}uyGS&#i_?s9nX**OIb@&~ny{2daYUvg^neuVTn>_98u>d~Ez(Tl4;s+jwfN@W`c zF=B$FY%t;Q0*iS58-D~zxIE$)tuhB24K;XgYzS4tzN%i<)l$)rMhxmJ&EZRPbn0(} z$B)zw$PQD%LE2$toHI$&+aplf5hT>l)+8cG+W8x?k>p~B@JInj(l8M-IP!D!Z=fT; z$Fqe)COgbf5m~F)tGE4QAwF!bB(LJmD}Q?_bIFj4J-Hjduni?8LOy7}CJu~RIE4Nm z?7d}Bn{T`Jix-NO;_mM56pFhP4^SXTaVsvRxVvkMO9BK*aEdz=mjrjWA}yue{MUM( z^}e&^+g>y8ynAORAMQyea-HXW>3RH)Smf&Y-0V%#2NMoBJ#pVXUn00?Vn4}F;j5u_ zYoQ^v*4S!Q0L~Bhf6;o$al6%2eH3F#QgID(mWUe)I5Vv;cK4&&__o%iujUuxgr;7wtMB$%ta>Z9R(hOj& zAp?R7q6>i&0x}8q|H|!tfk13zJJ2f>27(1rCFrQb`F0ZH<4^j?C17+0j^njL3i$~$ zXvorka0#8-<-?c08ptnJU^Kc^eQC?7&g`5YJ7$)3kxBRUzY5>fnVhpkm7h1uEKaA$ z{qEI5#js*`*9nWdvY8lI;zz$>NK0BMX@E;s5CXBMnVkAZd5e&$Az_M*Z{<-8^g)73 zqYRxZW&%g&nW3ZR&&E9iUQ10jO+z#OVn+N&Z~=yL7rgIV8Td93gS*ig0s;cUumF{R z0W@Du6q)&boyMAN)K3et(LG0!%700C%xYU=p-(hoH|V5^f?6ToFvz-;iYMHf zII3tk4gLtJ-}3P;F*77I3*yc(J0ReEIa*m$9KW@kaMGLAqd1)(8j|!3-HluWUczNw zTNlZmazN7Lx%#JC{FQIZFqBoIZoy4soQ^x6ZA~h?U2=T3nj2JXzW<^4R|tMc{Rv}=clZ~p;;T1q{_ae6vU^9^t)vBz-a4nAxPcGNx=TFKr z%(AfBbOE$DJ&NihUY;){^?DUfWg)Bq22akrS(J+D8~-}-{vY7&@v*A&>e%|! zWBfgK18{H1MJq=^U?W@Yavjox`FC}31;2E&Sn zzI0&aiAEi0l|C_qWV4f)CNuwgk*}ZlB3RKz=vF@TP3?t=DY6#!WFrp&M#%lnz^?cF z{7y>XZMth6YrHDmZt<#S@AabH@_iHou0k@;2q4aSc&#(!dy4BH4V{@+A}eN^7}Tl8 zyDjfXZIiQAMMXSvR(F2ZG3(*$u5=ND6NHH|ObCao`WvZ-CRIs(G1Z__@BeF;=NHYt zy7PX6=dns#J=NOZp>n`-sb3?*##X2$>{||kB|;eFIk2RS)7N!}tdMAe9VXsbTzo6MfC};-zO-c;GJ;8jF&}xoL?`+m|p>?{W+zc%tC+*OEcYCr4 zpVYzmY4B5s_JVM75^pIb+3%iSYrdGT8iu6-f^gCa%+ewM{c{V=SeIo&^RS1U!&lPa^*# zvQw4kX}}bzz$-4+$`0v?Aj1rFqr38gagff^CFBf%?$v0Rh%Lzo=N- zB11*$E@nGLi_fb#eFKPZsNiYnvZZ3Ev9NvIjG@8%G23CH#{+Mo?H+M3TsZP&6D!_C7s9I@B-8X{lbv?jF= z;XMY`ILg8cW~Ujw3pF3uxTorGoRdxjiwSzSiJJ;D4+1}0dhK0DdMLL~bPHm$<;nNi z8cxJ!RfucIpURrK{j1*TfApK=c^{%9Z!{Sh6A)ot4t7m3Q4<(Ua0ky7YWgy^yyhWx zSD+FNnjV7-_`~&&6X!FhTYa3{&1O&hoTbO@;IhT1Z6~=x?gE@mnqFHO)Ty)@-%G;p zlgICh?&6O`9!&JArSsojyJ4j>WT$C!sU|LL=inxqt30XvE_ma=agqVB(`YO|8Lo0= z><|_Eg_CQmaO=mi4A9@oCFWoJ%-}CYev^OO13Gl60__X~I8XD6%?i7J8=v^z)17i4 zeXF+l5MnD=TmdKcO0{(mg9A@d`IlHft>qfFi9ek}7w-cB^-FAjk=B1mtp7!_Uyg!& zvPM1uk_&~|afK(FkB-UB{yGc6lP24R9;L1Bv|QqdC|sps z^%1355cLnzb-b*_c?LRlS)eyDr{(O+4cG1delT)lwfW@c9bDzI2*VeE)wEU)@ej#n zlUFci$A`o7orE990tkrDD5xq*ma)+~6wFp~k2`S9z^(&f&4c)7=Zerb~1195HRH6IbEFZ^-a^-nm zM+Xec2nOP*$1j@o_L3hyOZcZ`=2izgIJ4Qes`8qN5A^dGsS-mLT)8oU{q0%a=xt#W?E4C&x(}3vdc~xk>ceWKw%Gr%B zuhb|S_3jjIb}t#ia9O%u;Vq{o%Z zU6;p7tXIVxyn3SX`fx5uOn|&q(!e2mzhoWL&%L+3!``;25FmyTBjHMdSl%a_q&AMi z#%X>yB8CTINHWccCDy>zxiI1E(?V}wA2^g33kh}NGvf#f9y2;#=Qydid#??-D5jf5 znv;kItX97}zWKSd;R*1adnfb3G?^E#JRu?TPUTM*KZx&}GZ8%PEB&8n;XcjLMv&pM zwQ?M{Ddx>FE^d-ik1M~x<%DV`hBnTPU8|osRO(kL&0*$p#c3;gl^L|YVN1+UOi7wr z$L(Wn2^7vUd@b+d&Ix(@`Ozf3I8)aqTb$|zZL2ZbicQO1rXdY}M+1DVckG1q1=~34 z=>s)#4wM3&eNJ9z07!@M%rL?!6m#WJ=&Ixa?SC9Z#X^A0+|YO06m43JNzi`l0k9=G zi5oi>bzz1Ad$ej0Y&!$9I)tsb`ImJ2rIObe+Pci^?Djf>J8>GMG>pXkoYiW1>=pl) z@o-47zh-bmrTx#U-X|38=Da|PJ5HLI{eztC?c6T#8$~@C&7Y(WUz)$m&h4lbJ23Qo=v6`?5AiIrS55tf#&B96{W$vyh_rj3bR98ENUlkr@{uUK%~2K2GL zn68|xdqlC7;B{PF!MmwUabfALJG#ZZ^z^k+L8(u#lSIvphXiIUmUc5=tu9P7y_h&) zG_CV2p^JLyH%TX8#e#Q9E-hU?+Jc;yR=m;PQ8!$(*Vw|0fx}4Gfaax`4x*e%aSv0) zvB^Z^z5n>AIyq)UbDUf~QfiO3G7;&qHc^{;zV+hE^90-@eUK?lY1H`OSR*WpQIaYf ziLa2-8rPYfe;F>6Cm279Km}tT} zSSz70i7G-pU>8LV14qrJ9PaCHAL$sZSZM#P?(sr!LHH)5It*LtS;9Zical7N5B58Q zOC!S*Mi{gRPVXG#qR*}x*JzeWi4k0G{8=g-ct+{9lClo9dom+ck*{1%dSk^g)KwW4 zT5esKsbESeiS>hCQqmpC88+lpu|ggKVp~9Zpb2$hj?lslt+fUa3-8Lxus(y#g_^3M z*dq08X4-c_Kz#o;y-Pr{LTFON4>aRUFE)1G0cv+mPs9+ za{NU?uZN5rFgGuWQ}fWvAuke&xpUut!mbc))V6EV)bs|V7!2C#1F#5L5uo=3+^Egc zfyVIKXtHlafi{6H_8)M$gDO{u$x3j$a`;)k{2|O@N;2MmwsN@ZmNeh)tHJm4TmfCr z*btj=d(vt-+a^MP8t|}$xZBQ5P)ON(@jEx~p)}l{Wf@w|EsX`o>b_)qTnc~Xh?AA3 zl&Vg3+4#Z6IdwO`ICgue%1}f~W5`Plr<=4puQ$EN>j~^~U-@qawZO7~Ky@0986-jm zPS!XqYJ?2{T-Ryrk3l-;m^xG3uMOvPoMqSImV^kwLG5dZlmdGsw$O6p_^&Hw?+zPg zR>Q8HeOw2=kBv0!RDL}AY%~7=HE$g@Dhj%gFS8OjmUuWJqQ%G?K-EbE5bM=01`oh`$jN@x zADo+m0=l~DhuQa`O}W;1omXd^iVXzES2d08fwi?1p{gIF&Mu%6Cnhr9N!yqMZ4hTc zARs@^){f2qiVYVH_du_#;Yh1n^l-bRTCL@(ihGrqlJ4m;G3X)iNS&GdWFeTVv$rGT z_-U3fj|ovG(-xA_SQyK6ntUaL=658t)%& zo5+n|l1RTkDFx(njsooqqC*d%b36N5J^0FJ%E|i>}1QhZ_Gi8 z;gE-L{^dSC(Xo&*GiqkS@^gjy8TsTQN=GD_zaOc1ZZo8XRYQ_)z z5UthY!O1FugjXoC5obwH=(% znV;{pY_byM&Ij>>F9|I{96!mav@$Q8fV=?>R=B#I>`bdwt##etxIR$p7$NKQ6-e$h zZherEkqjYa&zt*Qf4MYn@+B3G&O@)_#K?>IfCdN9D}|Oo-8!edXJ2mUoL@s;`Z^Ib zUMS<<0Co#mHXtW|o8IAPnL^A3tsN?w2aJ7oLGdaOQO%gQmR0Z`N+0x$N~i%YZ*LeG1e|<^s7$F$6$Y4!Oi#1D_{}t?hHZfZo%Z}C z<3mC7l?{nDKfxIEL~d=;4R0tBzqQ%Lk?SFw_Mey$2qPl?w~df(JN^RTN;uOc|5+Y@ z;PU=_4>%Td^gOM9xFtRnTJ*ssg1{;O?EP z#XWD5rA4BzX$Q|l%a0E^4TSFMU*a>25OHfn#^2EC?X;;-I|3V&a_9ZDY+bTUR1K0? zWK}1g0n*>G{k58*P!RJm@PGt=(0{jZ#bq$u;-p|S(4&O5+#68#Qtd8ui7m!Gz z6S!DZx9q;PI6FW~yu31IY4xHu>A#pHtG&jc;&@mdl4k z3CYI~+;2sw8R~8%sC>SwoxDqNIQE)&FA#>1Rmt+Wo1(Iy(tYebxTa3vsipI|( z$3&asept%~+Q_1fM<`m1Ll)f4<-D?2`ud#j9rIeL`+BE|RKBnRmXZM*)>|?l`@A&! zeBZ2@9?DkgAMrVYhdje+#Hu$blh7e2_J)^P3QU|lf}w)M6X3Ix1ZVGjX=PI%`~$cZNHV#G1-jVQj{@oDFEtkJJ;FTE?c)m`M7*@^qV0Ibre-$BJSUXL`6H;P?) zY=K7XW1Ci8>2$2%*>N^4{LS{~pIX4(KX!h${!*QJZO;&xthQb*#qcI=VeK{tq9I~ z94~gtP(~mLNt7g#;@7$bLk~<>k0s#T-=~s=R1S)L`zbnv`nctz#BdhxQpE?hTR~nD zY>Yz=45ey@2JxF`#YS_xKYeKDOytVLi1!3jl^}v&5|vsg<`p!zhtC?NUdnNh9oeJ0 zyK_=`^E>?-p5=Cx!4Pa&B);_#D8ie0d@Tq-)i%q~SX86pa5?AJe#5rfKt!e^eOOVS z?sTfEv#Hv6w9A?b!U=nP#{U^wPT;r^)!;JX4cNFNSyI`g4AKb!9Q_-0W( zg_RZ8`8t#$65Gq3#dL91OUV${A*hMw2X+blQw(t(7u?M1P+8Udz9GeImw68e+2n0& zEcaEre6fH&{9J3z6i7J3tqLL~YG7K|y#Jn7ztbc{{Pt|pe2GMjT9~N%M7)v+T2%QT!XV6F|D}|=n8`w~$!eGWu^gQD&vgQjLh2%WkzQ@%6HI2cf3G;gTt1%M3g zp3F*QHj%-XQW=Bn4wk7v*{cBA4**r-599CSxAZn2CNJ4-$|IW=IdvQFNn8{R;8GXF zL*Lj=zE1J{YGSDr3_9kz@`xdG9z(eb-q0ADN{J5;SB0O=w}1;I?Zdq`s@@ESc%)=z z>5)qL9g1n`<_~A@7_Jf4^$greg4UZQLv+bnmA{P+ty7pD-HlDzzd%uMArk(4HfaXJ zBhGgjj;r-=QftUbiG+2-y}+K~k8P@Ty6-(Xy<3I#4Ic_pZF~ej8=m#{s}0*!)DQ9` zRxe{wJ%2vVUnCgKq8uSi)P2Uj6G#^xGkB#x6WeTtfxlK?Jiv7 ze&k0n`GCXWm6c;DlD%^CCazI?ZY%xp0&c0ms=|6ltyBg1IIUL`2*_TCQzNGpcEdho zh0s7DvsW6hMZ2eL^4CpT7pK7Z34ypcPXKj6{g71;K2rz-n6w)HfslNi3Pwy|zs#QyF4j;?vlamMBTJx;xFA%9X$9cb9u7zy>|T3KVT%m~~B zLhv4Hvd)^YkYf97m^e^7ZJxZl#mD&D01oTt(Dpq+TjG=n7VgKI7l&M|LdH3Um+-tN z*jEg31KRiTdW+u$(kQm(Un1NSL4DWNgNezL7G7 zf1pHFGp4mp#FwTKRNmYUi?kF?hamvecIz9LQ!cYrO`y>aH>;m%fTyB!6sF$Z0wlK3 z8EZT1hm0<%kQaBTUU#HAK}c~ge~pqe-~f}d%x<6 zIN>NwW*!7p?{0x}NQUXg3|H4``!htFzTf^c94;uI>j*dED(B}3j}G$VL~$3vpo7=O zDsdg6lZq2J2|T8~s%mSliu;<0@$X%f1V}J!+a54`QqdQaC2-lj{u?oSEIR?sb%dJ333_4c;=!XS{6hPsdve?_)w#Qw zPtmO;nD#@<6C^0c`z@zlG>dJS%V2c5WP$b!WUR%#K+A8E`P}!}GKDX)`~Alw13x895^Rs@Qu^vTXgB)k ztTw6?H-`))EcOP9Ec84SeODj6+v*Eu)BBljLtEpuUjJ zo%ZP~*j|oiq5?;Z5_O00McX$c;gkG8*bWdMj(4a;P&$wQDcWn(lYXUBA zcsv%`;nJZBjd^&FJI=$o++if+iFsck7&VK3R?$OODRZFV!d*2zQGV56@Xi|IPpAZ& zeOj_V+o?TCHcQp#xorFHoZaQ!T7%WS)>SF90wdH=Aka8r!Bq_dxii=4nx@mwSEg<@ zo3Cv8INU#0=9jg)SsF52JftcIqm1LK)Ufwscb+LPy2KIUPhY7;%I^B43hM%CG?HO2COBwAnC>mB&5%)3y zQoabV@-JA)pJt)3R;XUVU(c-D^7O zS@%dDTv{qLDP%jC(0uZhf$s%s6vOv5S05?|1jSehTJQGcvvv>BaZMB!EbQ-=4gICW z+0M=0OTbDIlFwi@%iX+-9+P&Poh=2lz}*>wQB_rI3q8Y9h5j^#TA1`z>B{YjF-1QPZ8m> z&{7*;84zH}nR)mW6fwDdujT(!?J<$ngR)jIh7(>-3rImP5-yxS$94B4;|J`;Rbd{N z@jY_)ercS7wt#hr0FJm9U&6wWFUUSDQOcUUIJdKQkn0q0vF8UEwHu0KAy3PQY2D~k z$bQ@YOd1GmU->L791fgEy#M4Mp5Ed;?{E8pJa(-k^y1E(TQ>N2tl_(} zPYyOVsN^q_Oat+bK;7u0c)l5yC)Y_*Z-@82@3#f(mOX@|`%{Z$UguMe5^0XRn4Cz4J1B@>~8IQ zSC;j`c(JuZKw}A~D2R(Sfn)__^NyTkb;_K&<`dr{;=GIazuK%S@z>NWmhcM6C8E`55o{$X zK@zlZ9fc`|AY%Mg^M?Fmar-6D?ijFS#i~3niXWSIrKuB6@ZL#f)`bd4!p@8%OPv>2 zRNU@XBbR`aMC#iv1n4de(awJ4ac+k~Pn0b@fQwT%XFTNb>?EiKq^hcO z-L; zyupDJ*@8v9u6P-ms=ewi$&1MfNTPvZ3xV0tn`qUl&f`~c+77y3O>VziOTVAd$`-Z4 zZ@w!UePK~OD8@VgZ0~&7@@$MK9NU|yR4Ettr&v)!%Tc_ODyAwX@gH5ta>SW*Wn=$R zDaC>jqb@PoP@7qzg2_;5)vreSXIE-|CYMA8Ye5}MzAm0ADV<}FFB~$U7+`LyA{9ZI z`_Rbpoq!T2%~02~hV<1fUow#g!}Eg`Z3g+JX^Scac_ziYn{wDk(|=zbQN&jfL z7E1xWRWUI`9~TbikE9b)85g!pMc8Yg@j;w8FbXp|kui)# zktPQ-HKmNtm{L?|8%I6oXgJPb-ZGZxM9TWxX!G|$hnMO~k*rGmbMgvy#%1hG1Q_xpXszg&zD4>7oWhVQ5Vpj{RS88ODzaW5HVSl4$ z$N4hU3P}Jv8-gn!&(tr^)SibKlL*XXQK#Zlka`yB2(TgkBgkjsi2?3`x}%k7oH1{y zggD|-J{p$UK0D_-O7B<6#bQ)3|mgih<3cQoVn&@AIo+LB=>SpvpE7XfIbN^G`xM zSrkysdosAsg%R)4<5Q4omY`EX8L`6HbE%x;gpx#r6P}%$N&?#}iRM$eoPK@!lDFV_ zsi`zz?cd#_E+pmGR(w>ovvc6PFx?@n>eiCoz~GUZ{L#&6c~4o-SlJ_KaRs6qjGFVD zgmcRv3+z9+P6p%qa}>z-$*v)^|Au=iJg>Ni*aLvj56a!KzmQdE2PZ{hi# zt-A8RNVwj-4^IEPy<8S~ayg6NKeab2OnJ+S?;c2T#&+_XbaGzx{~Q1Rzdx`dFL)QL zdmCDMYVKcBFrpTi%#{;_jSviA@#bl!HL6pWgOuw@f1&^5RDVc$TXItU>GFTybo=jb z?*I8FrTy*4k|*JQB>pibrhxD-lC3M)Ees}4M;nc{J7YUHT+d1T>4|HP+$_xX)nL=9 zrz_-iWinK)ll+-V`<^}2FFt8mxP1lqh;gdN`_%KOOfiksiNHxFOTn}bpRs@s%E<-~ zT&Z)3)v1UWB}Dp>-6Ya>WXLPxS<@_uw<_7OcqD^c>C?D^5&dkWI70{RT>hg;bwiYn zmLRJn(40TfZquXZvMOw}bW)n-2 zgzrp<(%|so)WM`!#hw}wo$LfsK*8ntTGxp7>mZ*g(W^5kjp&!v=O1U#RV zQ>khSrp-vs;{bWtgL;Nr27PSGGp7^RnlE>v zdU8Wvo(5;V%WqrRC$>S^f4FtlU#YXeBS;wc1ey!H;al6+2X9+@V*w)fw(MHVjI0J4 z>bTq67F`U4{Qhv^RLXVc;-XjUlSlEzdUzGN7O}BL)j`zCDqF@G?N+C=7WmVZqxW3e z;a{!;6+$&pTgCraH&I6ck(gzWTRm-{FTR^EavRFqw&rpVnT1Gxo{h1|S=`;g&y$PU zpHDF|F|)9hwQnJo1s-a$z$8Cf!XK0B!r&`vTUroA=Gkf4DrhkS~*2x5=hw8XsY?#PwoAzhdF-FfRI((cQ z8^6+sgLcT2q9EOzE^FXZ0R-qh1j+Nx7np(dTo8^-(2%FBXQvJ4Gl*CA<1|TgiE&IF zykH(Nhrw{#t4!l;?|ox7TYUvwZuK&@dQ1%#abcm%d-n|;+VuO6hLY*(>exbKCj>z~ z)VG40WS(FsQz|~OL=EpLC)WK2^fX&ul`aqGiO?pX3SK!c_ z-|n*07unkvn=%4u7wMv~!Q%@GqX?7vP2s`oc0pdtKu9 zRGnat43bU(XF!S42Vd|QgJMy_2JnulTJ58s+y8W)CkTt$fK z7EKJfjWhZQu&iWtE|mKb2+hNM@{y2a-~xo!wp|>2uKC^&Lp6C^7wD8$!QDW%Qfo+@ zPFt{%-6U(K3q+NEe3xp|x>p$Suz&)e?l#I^%)Z2O(fJbHBJT3z2ep#CQl?OZTb;VM zi`cRfC;Tg1b3Iv5##GW$5Bgjs8KO1RlrQ1wFqA{};^So7m!9@9RElQd4UN9TFuTEq zeJzY-*A)MU0c^IlxbHGLq5>BAfFG`ctS>^YDLT_QPJ5_A3EJKw*2ceAR_%hB zrvy&V6^@h>{M+9hK;EoIqfIgtO)qW&n0vZEMgl=w ziP!Oc-t8aaTiR$sZ?263YL3#>rc_SmJ&w-eE$xDR98l2nc`1f zVgW@wEV0r0M%n;aD~6X*2j4C%lK_*a&P)A->H+Z{qqgoHEJ6wq5a%F}Z(6d6&>%Cr zpt21rud*c$Y;U!7PVT7$k2<=;$AaRCUe6|BBr(@8?A+D<_Q8LqOziHQE>GIV&g@CY zeDsImBjt0kG_L2(aPoqh%r5Y;pVcfLmfQ}a5nqy)S8%|GKGfe7u5C$;S(`fF1B??j zHxRy`sQ)5qC5R;thnU9r;MR&%&YXyTq7J*02G(ig+ep3#3f1;;m^Fz`&6hMZuvb^r zZuSsn6cP%&Q(!wgc>D>?TN6@TElBmY{Fyr{!TgytX^qbhxoQ^$leA9n@lCFFK ziZ-k2>D-~1d@m%G2d6u%I;&*$h$t0bHsHg+PTtIq-*KjD+>fId;vyg%OPtXrWJ%6o zJVIr%{ijx;l0pgB|fZN_>&j;o3y0IsGIod+{HN?a?Cp< z$lF8uYj^K-R@-L`(r|rhwkl5rvSrI3k6#j`A>sh`!GrLb2EA%e0J9AI;&P!(kAcV+ z0Sb2Oz@vCeVqsVNw*h7{+dV;c;bF32|MPmS4#RfZ*X_WNmk4uX}uo=erx6hLM;a4MDMQ z0_uY9hRF5?fM`2$EpMareMl&pD8T{OGzaZFw%GU+Z)n*>`vBkFPicOT! z+0!}QtG@$G@glsVHM8!01hlb;ZC#5xREE1)L!S9F!PZ&#>E;VU47wnj7tn_+Cj)oy zeL&F9gN1YAJfLJ$hCdH72ZJ*YPbz*HNLNdGQ?W|TiGDY(Nk0C?(Xh429*|{zn zKiCk4jRJ#?a0=q+R7G`lg4YW6t34h~+Z`QGPtdt0OOs!JRmd`HdJSt`QQ=RePh9k? zLNl=X(K5t9PbNd_Cf90`*>gFuOvi-Pi6kAP|L2Kxtxe<|d2&g3@qq61uP}w+=F9VsTq*hjQwZh*=L-W}KEf z6adae6JHwmrkm^f;*(cnhS+zY(xcQ1vX-x_pO9z?$wJ1??i3?T0h1qv_?iMQv41c8 za8i(ZM@OWq9g3a|c)J9ph9K6uTUpHL_K9ea<6W7=&2njMeX2@aDzs!Cd5q{%nYA>N zQ8Ra<^oru=jVvj9U;`;UZ2Ah3(420kcR(wTtaS7do-#QpJDyV)u zTdf#n3}eLL6@o8wC}xRGuTn@44`Hj-KFs3ycK_!_o8K7qXGY#7$ROxZQLlKoeQ$HY zJUD2D+MwexzEuKgdS#ms)>z089G%J#K1^`)sb6ggh!e<>cv;joMUK$ z=a8iAfmBbP*VgDFO&wXfV?qw=ND$c+80=pfqxB_c^rCI6Q1&Lp3Cwrj9o-(N@L`(D zEJFF6W~N|d>$2sr*1@C0=ByDN4T#(AsL!4)Z?VacE-Lk`b8MuC{Jt*XnDty3A*5tI z?30Bq(7d|jvmiN68_uVgdNJy$e*8f`i=20fPopUP+Xsp{*OrAs3xjZ3CZU z{v@!&ZcOJxl)H?D_xA>LwiD;J=sCx-TG=J4-*UCHj=cZ3J(YjR+MWrGK6`HYL)6?~ zqzW&HKG$=pb@=nDa9>Xo#@u&%b8q*EJ#{lsyZ1_NSZf4*8YYUHj|s&LG{$GOw)lku z;24>7f}5-TzVHK2vrvw5A`M;tu5=T9DP_beeSq3&(z0vfms4&Yw}5LK=_*4e%erGi za39;*;tLgP_2*Zbcm*d;GGpt1|KRC{uG%UVq$eRRpf=Rwg;LDZOYM}rE3HGxnPg@L z*KqOP{f3*ryYiu9!kx$`8kDm~vTZeQg0&~@${h}$9O(h`Y{OZ^Q13*gpd%T_fG`WQ z92&Wg7Qb?kMGhuNlv8X+yUG`45E-L_aRnD{*cga}hLVlqJ=Xk2;rp#jKIVDz)zQ(u zzR5eg*572fz0+5XUuZcCEJbQrN2*~w8Zw(d#h~@0HBGuu~$^SL9*`lLJ|}}4YkUJ8%6g5b zbp&{lgR0)Y7q3X^)!ASOa=NYi4y>M!v$LLN1nOz2Q8iYU5+L>ETdnQ_X0pp`f7nv2%i{J9p)qjx&j-4{x)@odA-)!Zj>-TJVj++&R?5!Nf z|JG73XW#;4M3k@AD869h)M4#AiHMllW3+oppE+TBEcXIO-Z{{~+V2EvF#2l^Uc%O1 z&Q~tyauNinFfT}xOwFVRQ*=Y6OKVbm09*dJ1(Tq=^42^=y)zje zEc+s9-6NJrdLlTF*I@V+HU!cT{SrKvA?jQiT4UO+KDl< z*{tM)bCSNL&m!=hKB?YMWuO@-U&&9ODzkW)o4WAXn-qvqD&Yk+w&(p3m-apS5!>iYhDHre#}9mI`ZK?FxCG6iU#IlM zwQU+G0i*Y{WQ*EB8;>glZ~>NcIZG6BFq-!LRMJeeP-qYRb4ilJ@_Ek{mVYA3}+#2=JQXC~_Cc$xnbT&pd7qTFKe z(WH4r;YBXJ_G%66;4hK}(T${qR~Tv$5?eHp>?s7Ecfy6Hp(OwEgZ0^@dw!q{RsTz! z%OE!6cIe4r4J2OH0O5BrweviUPG zT_glp^i9NgF$1U03rJ~Q8xdVa%i0}9rS0O;DdWwCyjyVEL_x{(>{HC+U==0h+U6m~ z-?)8d$uh1aNX6}A6+-RG9cN&5iv`eq*~l4Ofpc2t9M*n5Ru+Fs$N9S`??;$QQcxu( zHfM90REbKI#xNGPkZqs_Q;cxtwt-2ez~buAZGv=0o$|nV;A5apLxGSPO_o~21YM5( zs{0&oHXW#=5e(3v<1|~ZXU|9@Gc<^qw-YuGTSpJ1Y%F~Rk#oyfUoo6kqk0a5`%w6c z80+n=90DS5TR&JK_H^;nz|!aOXy>H>>M3UzA>*tp3R^ zzI-~mlT10rzaV%_W+#}H`i%v@^>isDFIth^+bmq^QVU#Ej{vrLnQYZ8AEf1fxNH|B zGrpDn_~$nDX&Ji2@~l|QetN|HS%ZRDy+B@`WMS|0TYvXqtl3JIy3kJE%J^3?le)O^ zY1W($I`^rLq627L_zm`m6RVKQMgsp?YRsKD)rN9=_xQ!_=-hdEPua5s`M*YXo~@{O z3&ByL9A#SC@v6pLTwC@tewIA?&7e7zpKXYJ0D zafQ8dZiK4PfQ+3lu`XfUG5Jh5$L+X6#y`WT{ zlqfOBFAob1{Vb2Q?}n?5%&}dgc5xU#_A^uY>y(9wiHXGvrTEoG_Hq+~Zx6{P$&EzZ zjQcBFU*2V?tNkR=4aTs&-~NkaR?wBF`Vh@_95P%G{bAtGc>3D0!8zf#R0QMiHvz#( zyAt7#10g$Oc1-F80WO{)g_dh#gk7T5T31X-WV5gJuX210TE(i*@)n%G8Qtw>)NyEy_Jt%iQfOlk+dnR_3 znIfP!j2qTRkuoX{jxds<9br+TP_G=H4O>_u;_+1J@+Yp<%`0gSK@5R3&G>uiOdq4H zpE}KhXBHL~4pDqJs{?}h-oe=$C+U@I>Yr4ekqQ4bPcWZ&#-a&;3hzauXlwxJL~n`n zLZB#rmK{G< zhEo>gA?7^f2XRTNbTDCEsJ>WuhZ3N1VxDl53VT5Kte@H_&68%QII-9%q!ZqOszdI4x@2L62hqj~eR)jUs zAqedT0F2O6yJw_0=+dp;@f_Nn1@>LuxS{vL$TSAR9S`alDlQ}tUm9j3K~z|0buhs< zEpObkD@GuwRii`Tu##0ZPIdBG0{S&j+K54O89bkm{jzhlN&L%Yrl$$GxbhHDNlu>|hL*OkHX?qfw*;fl2FEKIJfyLtpD=LS zP;9d>=5mcSh4(*YSmd{f#oBD`MJWy$F;SYi%6*Ch1q|28iDIH0l`0ye1$Mc3aa~)B zvEK_Xi)=00T@j+WYoTYJU%p7%-``=H%}}UccjA!bH_6;$nKNn`*)Pqj0w4TO6N?RJ z7dM}CdCTNj0}+L}=j{f{UrgT-v8ljK1lo^}w9#(b5Ja@jC%d7QXiy<*1rvB)JFGA9-7Xc#CTeyL>3Yk z`_9#HzP>wWx4h@x!cRKP$RFygOQ_OGXeXP3TVH$fF8rP+{D=kF5u1Fr*bal2b6TlM zJiz@3ntB%XbB)#u?GQsWy*=4uZsLnGQQ%DRLC+;} z{|9$(85~#BtO?2%SS-t8W@eTwwwRe&EwI!rW=4ydnJiX|nVHcRGcz;GtM|Qozi($^ zW;bSH?wxP8e{@Gxo{G~^C+k#ZR_61_x+MqgSD(o{MRVr2cN#8DGRt^QBj&`|V{=?S zhsUa^4 z`~%T;VGSUpciQEiHAaXwb4kjRL0;Z477+`cv_DgZ8TBO2UD%2+dMT*MgWsq*&#=r(!aT^Cn?enuLmx9q3@_?cM8PL!;FV`w3#)Y)BhDsLy|e@If47 zgRo5t($<1?>|slY!tUGfT>;v0Wn+(A(0vv9RBL3%gF}bkslp?<86gjgG>|$XfoN>1lTASeE%dM$xH#@~2k$@9uG{IfLcJD5KeyP(6*d)lg#>wKPvw5osr* z_6NneIaD?ytfQ7ywbfr8!kaw|oWN*=4P~n_ADn^L+)jsiu*Mq#|)EKmLCsDm;HZGeHhs7y$D<4DUvd6EWx~r zIjU6&S-4Dnn-4s(2g&Qk)nfG5$VLmwo-?ERGF|}G=Zm(ON@Og+}BaG}{=k_zF$C*|;h@n4bw z$1HQCC_tr@GuOIpMJ@;C$ z7_L_C?nkpVY-qq2<%?SDs|cYZ{9ruVXw8!J;07V7@Cr1F8SGVL`}7%1x!Bn}Hkaz< zEyik4o`3zF!ia%e+DU&Y<5wX}C)Y5YlPb;jK2{_KjJ<8ETOF2Z+u?KLZWe^AYvt>) z9!ew=WL}UUbvoT4L~1?nFEP^?tD^vU^nyeg{DAG-fU*84dCz~Ga9t8iFF!b}nCGyP zS;G<9$|M*Ydy<3RE+ibFu-CpRe4D;#Emb@}7%%0|WU=@39Md4Z%&MaLSco*lDC zejci|&Z{|)4W$pU6$O6fb1fV^+~%Z?P1LT{fQtmTBv7VSpw?L?nhH6ZrhoWnJk{_q z3$B!v6@|Lc>vAW$Xag5Sbx=%18&S^mt|1i&xzjDGLzoXbD9gpYs#;{1T=<>$^|M60 zqRi1bok6i2dbXl0>vQG_D{8cs2m;2HqN24o6Zv^TNj=irm-my)E8XKBo%J`FOjj9? zKM=zXm2fsbkBm;64Cj9!C??t{+W$c8G|vY%cD^Kky-2$M0};2c|KA#ySLu?2N=aYP z80hXf?^FXbR{u#8H|xK3<^Sv*%9!w7Fs6N7lhMMf9Xac;S2HlXyKIJ3fb}bv6B+JJ>Aqyq^8AjJ_vB)kKE3 zF20oZ9iF$4QqnNZyq;zZ*V1#tLWwAXF752+{^a{v4zI)fT#1gN| zE@i3uZ&hijmnG=Qu6&t`sjgROY0~@slepab?ly<`cx~PD=j(mF3fM%o^W={O%4n3#{*#+7E%&0~~2 >Y_ z(-*16QLYB)VBpru3d4hdi6kO00mLx? zr@8e*Rn?-!@G7uKQ4y#MHyg(<=9GO7zu(DVD76sBvhD00#4&5Jbe)l=`5*q)dXMxOoGI7+Me+9WH#z4hCE?B8gQ zdr~-P_>Y8hTs?+9`iyOqpKiAfvdTEI#R$}S@ElX}DN;lvs4O{hP=jNQ%VzCwd0|Dpv>e}L)8?rrvidgm#dB&?0 zKRX0H#DW9kRHc41O0zK1G4-iN($s-){vC|a(_Yuq7_M;Tq|wido=Ot1!{pJDiG#LwlMD z?gBz-X$xMErdA-?TQb0adFJ@gnd2HszT;oAfuHrIS(^Srdf4a&6T|6ln|h8oLYD`* z2Y{K$W0{{-Xm3j}yqvmXihn)9$uWZLs_(zck>Mnq_-mK+_GV5IJ@xIlH^j6agN4jA ziUyE{DTB83&_1w+wqL|ZTN9&l&ZWYeh6gXBk`fxe&-LH{Z%P94b5`jDtW6@uvnnc*4%|<>O(?ojpizT zByh2XTQx<%lv~y~2mc_ftec}wQ`#s6Q9m$T4t zTm4>9(IA<%C-uYT^cG7<=B~U6yTLr#41xx|sK)#aMWk`&;mp(_7H0DFwbui?fAM)o zZ0mqvDvRrHD|UoNgKU7F=C^mQXS(TQLE4p7^4_~A*+1^i|kRV*XpTds>=_EOwHCUmzd@S&Ts<&rR>}Nyi?xHU-?lfjz;IMFL$$2&T3# z#S5;X4}~X&!)crL{ZQWXfUr^=r9?kN>Tkd$+0Ax zjG!?|PSDZN(YF+D%-L4*gUY7yjrD8kSU(PW)hPNqI*qAGwMU0WTxbZuWQ_oE8Zjfk znrXPg@&CvlkMzDi?_cZJ;yWJLXD9DF?%bTevTD4U!>s?qWw#((w*Fu4&;H-;56|uP zAk@o*m+QZZV3zWDiwCLeR;@^m#5>-__GOflTZwjqfL6oUA^H$%j-%cqG~7g37wYpU z&GKN-T$T_e0iW1^-rv{2Yi#7I+nvpDJjVlGtsp>xnd)=|JWvR^srDR>2czH~GoCKD z{k_cv+FUoXQzt9`g9L?5$Zt77?MF;u-oHq?+IPA;g7%maG+Q{dbMl$UI*@Z<976|- z{RfIgiaxY`deQKHPYtYzM*e{Xf2!dtR^Yqw>C1>bMmSQiv7ZW3x86fb9<8mxSMydZ znK)L!0cxVU%fo2}6Oh7c$R1vP`E0fVQ3Ntm-;{uV+*w2gx`$m73*5FMPK&E%N%2JJc$oSc)`w)!MO3^zkr|`6?ifNXE3erwFDrjdqf%h z#&4icTIp<~oOwENXAuMZ?z|VyS@KS=S?~BFY~*vLeF^>J-N*;_VPd^o_m!VD4PKJk z{`U)dfu9O?;gAe71tt%>2YW_bjwZ4O%TGFpt2!SUT>X3AU6A@Mg!kmSxcLxzrZ*Y= z|DOnSnj7k{)%oCN`70}yY)tF;H{bDR*0zme_8yElLgsSgyQ%Xf`7T>{ngxvrk;~%g zIGLWZ`)lz{=sPhuV-mz0CYnmaS<50rjp^biP^RN_yB0d}Mp$rl2QqKx$;cxo@2=)Q zG#nv{r4ZDv0BrI4?929wp}Ik38{9mL+;7Jn0z=ju!`n+PIV1Pm_=EHX5G+OYRD`<- zk;_D%lZ4Pz3Y+m~)JthySXS4{huG$~e$8SaK6YHqZ9L)~hL=#M0v{y-P@jin!PUsP z%golmt*Q!I)*t6P+3r@)>7_GzB|~ptD^#5{rT;pF~)wo;5GQ{iCcob71afl2e9@d z_gpDkL|s=>fiDeN9_+6EKmg8Kw@-q$b+h=3T*e8F=|%$0Z(!fESUl1AXjq^2Yh){7 z`tF@k=`9%p!gQZ$N1T(A@nLEdCt=R{B9MMQ8S@%zRb|dJaDC_)y>f*zB(_#RG1aExS~m0xE4*Hbj1N+O_v{_yw!L|6oE6F5?z!D*Z5QR_f#Jh*lb)&8>gZKnAM;cW z?doHLd7vJIfCIE0hE71bRIo-+m#<2>mDRlsZdu&J!+{KPGHqp3uir-TIo7jp|wYlegmpEVY43m!bm(mzG2_v!iXEe_x%s(nZk(Uo&{ON$ItsvGRd zPtj{QpPdtU$)%ydJDg_VtZHj0C?2+J8+CAC{>WL{&}Q2TZu=OXfZ8zk1#I+i-t`B9 zBVC{OLU7z{KI#SKTC0A$6Y^!w%JqLjV!gMs^{9`%bQEBc0XAT3?;SlpobZ(EajA(W zKkBVNnAP0u@K%9#0Hltqqqg9*%~dDeO`prNx!F=^{#?v|PK?pTiJ#s`xwOP__Tbn^ zYX;esJ*QOKjg5eM%}zmksz%S$qJ5_+%CU62vAbxyG}yy@?cx$hs|~N?avBc&4s0h# z&S!b_W%%v&B5ZAE?hKXw52BJ21&al=H3%}Eai`5NV?u_DcUI7T)KWPv;+# zV|S8*k=|<@;jECYS9FLY>NW&E$7Ia$r?hyD~mfJwQ@N*-6yWUD0r)cy?iY8f|88 z#9eW;jl(L(=ajzcsHj=&czfnM9m8_fBv9ES)(VjGQA9O482O_V=v!@6h z&b*og^|5eYXE&||hDY>6JH^wy4ziLrS`7|{s{Gm0rqz&b(Gm&@9{lxCSq=6j(G;cs z1}Ff(vI+0RqwwLGq-mZi+G6z?$Z}YUP|H-bxGC4XHZ@#d7$K}SsfF@{gj-Qd#P#<4fQJVW_`(eM2x)o%*u zUpm5F@&PF?S)tm5xZWr=T5@`!BC(Vc&(wM63=mqFZ`rc;BmNJ*y@HeGm7lTAA5U(# zAm8D6__NxCjI#G@=R*+LUhdp4KLq(?P3jXfPhKw`_rc)2dGNdbcgM^fS()($Z6Vf` z*_DdHu-V0D_)Q1UC~xwjsVPixk$KRM_be`pqwc(+vbLMU+>CSZTYmXX6m*wFMV6`2f8Uh=)#WYoD=apGhh_vKkE=c{fT^85QiR?wY%lG-_pGygYMwP| z&kri9arcrs$}SHb_+C-Xi*riT&8fX&9hD_t(~ttOv+ieZ%0Mw=2af$FAgqH?vZe(R5@Ex|jF9PB57 znNUmj=~GY==Dp?o1Cesh&i232sjbc-$F>UR%blL<%(xGKvQ*1r=YHihmkk#%R{gjD ztl?P@=Nd3<7+EdCZt`t7*TW?I73CHvxLR#@6W5WeDSYR=zlwV`Nh-Bx;@*FWC!2o< z4+UQmY)rC+0gL@Yp596hN~7v0Lp>QONhTaQwZuBwxpr8-yK=v8clSR0hu!4uYE15C zn8hB4#}GYS-P#Pgz&p$10!{cNYY7XOd*LGKX;R2B&wlIgk|jdHT=r=Df;Sa5){6Ow zwLiRo;}{R3i^~TMMp_zSBdOA|p?={by2SuAGfzGcqLhdqiAUmpJZsR!p8KS5ztrKSY;+s>I5x{LigI8jt(PYq#{jmaI{AH zp(WMSJ;kRX{aVP{->r|IGgzGq#DosTl4u+osMKaZfWd3h6x4;GGS{@?#PG{jb2U?l zTc{a$FJSMbKVSnF9t^|Swr2iV+++D&019AnSRt0(ip?EmjnH*k9_s#5+mj$YXtXcV zK)Fo=Wbk`{{@~hysw3;MWyk+_fV5zgg_(`E2?$zeMNm=D6NUUxhKvd`NAO08u$R|U zdU^cp5tAjI2oA<89kE>1vn7)xM2Z~1;geRHhY91p2;&2wppgci#tgvMrgTf!RY((* z4^)?JR?y~=;!GogWmoOjQVCH&J_XmPH18wg_IZ_ep0ipc?FIaFMXj6Oew|0Mi|0n|h47fuW; z`;7=BKtRtSOlzO!R+EpTWvqH(tb{GkfG>(Wa5MyHeq#R7H9VMXeEB2x@WZ{xCkYX) z$XN*;WilAdctmi{5W`uZ8@!q|j+REUmPv2h4?%`5Y6tevJKLe2V$OJipAAvJwG`^O zh=*w|mmY`f*dc-cY@e3Qh1V&ujDZ8aMa}a!-Hv^8FB}VN12(B+oY69?(W;h9 zXHlsFyE6>-m9ybHf2J*O!{b~$ z4QX|!K~atwWs>`QL$skk#j~)eWO+A@vr%tx&tT)T1n3kZxk$#kwlqWY-70q*W)T`c2&Agb%@QjJgs zt)U;=(k_?%ylp7koHq>8hbsx1u=cKi|H}n>XYUh}EW3_~w62#w{vS0pCR$08J4wBZ z%iw`T(~jsSHu@x(}*dr>jC{v!|}2Hd^CY3!6D;3r+3*&2Q5&O+)e94YyT{iziBG z#~L+19?=iqt-al461!S_x=PM_1iiY+{PJw@ZYwzG&=J&EzA<3PuB35iN}8PiPa1GE z)sSs%5ouZ7_L3_v?EIUg^Q_lThkh=CTuk+E_s&I;5mEzP53T*ptGA8C+YHP54VK-$A2We=pN z{&G-QHKzv#9dFOO83S8W1n;sWeFq}MqPL1;rC*z*df|GUYq|32^~nTQ{zo)MI3>^v z`%X^=l7`Kf2-*rJ3>&>_N5%dF@3@B4QP8a=U(dv#fxM`zeUDOF&#Hq?HvGQbzd2R3 zWnZlCYajW?$l6C}`>KoKwY(n)cfXZe7w(kf5sAsMx=N|3jg+=&Aayaa(aee&3n6pV zH_dTJBtnVEif*p5|Dp?s=?x210^i?%s>lQciA>INzHQvGk)z3*ItSA`{0NDa46}Pq z-Cw~wd+U9DrhA3+$(RCwTx|F=oh_PbckWpQBT968O+eQI?bG3y6m|DnWMuTwPt11U zj{#T!Rbgdgej;ktFILl84EEmxB2OQ6dGDL~1=zXtz5|Fsyqh7C(!!*vXms?x_0U27 zx}x0&*Pd#rQKY5_ktf<$y3u?4z+rpA^vp_%p*L&iwq&x$=B59!?$HLMlm;4rb1H2@ z3tl{*N;LXtQkm0EGtv0OeB6!?7q7ld?90lj8>7UvL;e3ycWXvLxf1B$P_tyvxQvga zrT%v_cmL{N)*o4m8E;g!9XVrameTDyV`3%s(|NM=e1ezDXaR6Upmq0m{VtK-)uHxP zbj71%xtqkiXN!8<&*Kg~I{p9D0dq9%-KJXHs(bLS6BY2&zMQyre_mPK%v-+X5#7^aX9t{=+1q6YdE>iUqNkhH;?~J zPRLG3dtI__m|tuVJP^N?c@Wq&kKMc_kemRX7N#jv#ku7>#+{x)$(w&Kqmrksg21i9 z{ss^8jmvqY%QCG8Bo|AHWy=LW$=B?8-F`9eU{$fJx#5B+7JEGnFAEd=K}34daDUQ! z!@%W^=zP)OfQXf{#%pNsGO0QKOJHKW^_j3|g)a>+#7_+YQ{`}v%rbhf0rH@pyPiaT zcABGhbnCI*dC)K!N)i2RR=g8^8(j+yoa9-YJrJ^Ffbm2vbN8LD6+E($zS7X;pHY?v z^F{;a;;QYXk5e+3#={t;tyxM+H(o@ z=uyg|G^be)@zB8v&HRGVIwPRwPCUcT0Ud+!o~H9v2dWW9aeu(}w5R`y_zZGT?pPwZ z5|<{4tFI$zB|x;8K5SE4DS7!uZx$(1HsyvHXnoIU)fv{AzC3>rGgzufflE8c&dv<0W>I7=!5H z0(!0U8m}z9K8A3Z$|eToqk75fs?)E*{hd71@&u-^k=&2|$3!?k|Klff)b+00d*YF~Q;bKcfUAs|) z#&O{eKCzU|ahCl;eLX=SZLDAMoM_t4X7&z?eyJExmrfv5Mc%I&$uvcx9;M~Cpb!_}4pII5d2e+vNDytU z7A=;E`pB~z`SE526ntS`xCTB76GZ|H&8f;P=l=pMMKej1VneXhYuH zwsZ`!(vR{}A@`qnViJr!>Q58tnV5;oy~6ka5_+|35-)2-dBUND|tY!v%Gi!|aiJ}TVLMii>#VT}6)H&8U-CCf18c)~= zd|UC#*i@T(9q|zp%3RWe;FYIEe=$kBm()&kc6etgwu{>)vVfES)bs;PA*7&qQaLIBv-ZC!6uE`Tw_WEl2J>od_IxxpsG;X?5v|F`CsG z@<%#Blxc5km^MMV$0pp1SFZO!dGF17x?ko0cXyC$=#N@qI*RaYH(3!b`AsF)+VAVr zOD#lyt2{g{#E*o$0uyFyP9Fh)`3z!ZR37&_JvfS!=gKN*y%xRVbblb+?tq~TvZaU> z{Lu2N7K}L!)#geiUWu1(!}&DG*J{FCeW@P!`L+xBb1b=t!+xhNQ|mLz{YmAZJ#UaA zU|@+qlix&(qe0Gai(bYvO|nI5e}=e4N(q%iO@4^EjOw+U;{|ms;5X-3;$@J(p&Y zX8{Bu?=vh_?7BwY>XbRDm__AOi&~Z>QZcJcJz35jgXQVTh%I)rJDRKZ+IKd@rW!Vy zA!*VSt%#j^K1I^9yZom2>~$`o9aY)F)JKu(hSc8;%S1q(fbxf1?1siR`6NK_B#*;K ztT3`f{+yi_Z&GBuS{`n-IYvIO%sVBqHTXI@0i_=wZL4GGIPa0oXCqXP@I`O}X1425 z4{Sxyo~x=v4jmBY0Gg4Rt+S{rnI%LVne8vdrJ08;sjRQtP5FUI5q}`45QtKK%*X$T z9{YAY+%vdG;&UE#}_O{{zmyv5YQfRjIbH9VZoR?_D}hrVpPL>`@li>U8=< z(<5Njwv4BHv*Y0!sua1crkTm-lnBWQ%MWAP=)_}NMm{EdVjm&BjK(8Y>!%c%Uwl;OW3OaFvP)zYL|!Kks%oyAZjwqW-M|visVD{>x*M5R*K;4nxtH z1zAmTCgG%53vU-C6=FSmjkw$EsUtd^B%v zP=!hst}vD&pY7!~c+g5{1Z3EVy=7?~yksoTXK^)F_58pVf!xSb;s0?b#@JIH%M`vl zZZD}3ax>*83%>qW3I_Qgxjf3c-xPgU%kZeSV;?(_m8HK?3C!blZw<1R9S`6?u4fqj zG8+Sfg4^Uw9{Tn5WGK|Yv=2CSjlaSY!7Dl@C1yyPlrZvCx|P_n5(H*c;Q>-Oj1=vE zN1vN)-qdSjFe%ZVfQ>1Gzv#)~8}mr`Psm=RQV&25ZJCd|4Q#^EuNzG5)4LB_ zGlFyzOtcQRc4=Rgz;Il)tYensTr|DP@Z~)#YJDt6qwc?q1ZZW9&cFB6WB63BoQ^$x zoFc{N9;3HVw=+sr@xOmZ^&SDw{qms8+aEhsjz?&&Idn8Ikgu`2o$XECTe!cut7+zk zT`TeVNS)h_sT`IX)7^}h%&Ep!2E>1`sIS)n9NE(?@Kc^zD;p-VAftSfNtXefO~xFv zQPO8wMXzkQrVcnfobLRtwsN?ua{4EN~YYwznE!-QLqd~FtC;ALG_yuLk zh)GGqX#PMD=XY?fQB#MB|1=bAy`Si3vOey$u!)L}4Y-fh7=h7EI$8pZgG8DtCSbzJ z8atv~w7G_Ex*AD(fQOhhSEBOHCJ9CXtJuBF*C}f{*zziZe5B@dHGqH0)qoU2-oTZI zr~GUZ`v9NYh1cES6^tmw`M0bA9uaf#G zdkASh!AW5U=6K|5(G{fAE`iG9hnB0Tk{91qHwo1@A?vpPqyd@?wM;G-I^XjgWp5S- z3<)tJ$G%IY+*Qqt;DOAY@6@m+7Cwzj;tcuH9s zz9pFmhk*{%aL;@yyT6NZPg|?=*Sj`50cqZ-=TjNrL0SyO|B=P1(gw~MSwCy(r`KO< z{h_JpV^oXEiKOAS`ErD_iF7nPpJk>ZpJdI~VH8otrE&+{JzAcQXm|R8>Q$Yr^rqUZ zjG_SN4|cTq8IS)A3?an@UeP_x0f~dekgnM3I#mzNkieofsKF?oTP;`ycr&7+r|iSa z>{3j%Vyg`p=Ry7=GpoD3H~FICdGB!KH4W0)GVV9 zmR5bqc0l$CK5iI?zUN^aq6R{ByG&?B^pn1C-tDc z14by~b{E>Vtj3HmdP>wHu`jKTESDZLvu0SrnR0RWQ{*p%6o0^#+8<%Cho?;g&>p>z zLg%TQYB8WM2yi-iRSLc*da0!?F_}8*J~!zuCY{1X1)kBgY=|yMTNk{qV+iJJ@Nclmba8e_pmL~tx#}WF|R1VOdbs@3P-b2Bd`6P zFjunu(}CMt{x+D&p23a>?_;xc#h|@3IIFryEiU?Ar_DQ^3< zW5@_Ww+R>hXe5&WmIJSHJ!FG+uD37MnMM_ZEG=WoS+p&=zp43QSd1|=r~zYDw5Z~j ze!-rTN|o5yE@QX2|63aCx>;f8Up~UO`pTt$Z%_Q?V3KSLaNWFzvOT(EO!9bH>ZKKo zNLzVuf2|$DsgPH(8)P)RA$!kvemQsU&N-$lX@OZ>Tq3YDBAFu}lH#8_qd!h7hw1Cq zxv3<3d7C$oz7m`~b^4!ZILc%gv3^!ba(fE#NhWOh$5%R{oIMZNnCW*!!1Xb|7xj=J zf9-S)@Se1OK1n*tA#2xRrNYJIdnM5Br7rGN#<0qDqNl?!Sf8ybJB4IE;)H4s)@hp; z?$Mv%UEuwHg1|97{YT}j&nMjFwB-~`%jp4zZ2z^nf<%Xf&;i+`NGoCaz)?7n5WMY( zxV5;QJ8RaGlNM}yH;jeLQBAcQrv@DxF28i~|>rw#5aBbk?R5mA#Dx)T*FvPPd9 z16YAL#gtLZ62L+%$`P6!qu`%woJa`>v1+8fUj?)5gD^5#&BHKzWT9#c`7Wi`(1%#*f11N-ubSK_txSIC>y62G;zBV|_l`UVfi(Ds=GvyV{mf&2Eklx<#5RcY6Jg&8q0#p7 z`_@d3x8g-vL-2zVV?L@b6dajgCtB5=69hW{`T|E~XG^Z6fH=kZUcM8HWUi~bs)`9I z!)T>rZu3JcK*@M%`>r(V9KX+$@M(>$=oCP&kO=z&fZjFkXZpEVQm*$M%QfPv?g^Cl z`D087iKkKAgcbVft$i`( zmJff-ljiir11LJFfyV1IO3FfCA3iyAVYp@$4iIt;pB0OlEW%w8K9yQ75l?;1F+@h` zsu@e*lfh%$n5?a9I&_g#2}9R}eAi=~IzgmwIDiy@XCD+sr84-w=T}4&Sr)v!tX2oA?QUy*gsYNaZdTWkoi=uz~agI)_Wa_7!aXltG3*~)Td-c1o9{`3LQL$7xHk9xUGD18P-Mv8C3l9YJH0rdHRsZ#o#kjGV+?%z<`BK*qC}$*(G(v2a+?EI z|DuCP2CP*DMst-^ot?=dc^qB9Iz93AC*+TET8~1T-P23mvE4i5AvwX^7#`ayj86z034 z4zH(Fr5#-31C2+kjg^BJNCeO_NZHpIRTz2qB@@ftMmcNW$IBp6MFD8RrOL?DzAz!? zf}#EGyYk^2as9|VHY@FtM&mJ`>imymA7(TeJI&C3kjU?~>BduS|1{mW&`!NsdkcH8 zQ>W!yIs3~pn)&kZVZ6c$Jx8{_f?Cm;HyY7=+=mjbfREv)CM=d#7u{sfm=2>Q@6%H4 z6=G%f3;!n#-s@6Sj~v>FxJ|LH8Rt7-&{(wl0JNS1$IVZ-^S0h@AihN-UTv)RHFFYc zV|-}kMnm$2SZR4suh7QUf@%1XUFlcyO*Lg~-~-v(!oq(0(46@q&2o80sIbU@5DUnb zPl4b|2KsBHm-|A&30|J7ci=k!+D03i*1%P-4t;&olDO16Z}WUDcrFPF^AE(0_sX-# z&le&WORR%fjn6!QtS^$o=APtVrNEF7%n2n3Ex#jkUUq(#z)xLhED1m)L}XN z0)yNbJ+dAlGC#vknUhV?gkN~du&}nvwN>*`3sV}LaKCVT%&?!6ELhJiMU71HTfKs4_PY%^X|W{n(K+%*Z_M7#C+6{_gdAivsIo zvQnr22O1~BgYUN>8d>Y*$^=kYYEQ@5zodkV;Y zhi=^vlm}eRouGq}CqI#QlM5TPQE*ogmhE_}rC7HGS?p`|`~|SMavzOfJ#0$@Qx-an z7PQF&J)w?>s*Z)=WK)I3$t8h58iU=pv+MA9fO}=%^m2nlMMdYc?Ts8C|0DTwNc6Y8 z4cEg?z#$Kp!i#-K-Gtmbw57LNp}h^l+e@6&G!Ku;dxoZ``w^r3LW}#dOt2+^UoY7+ z(3CM}ksh9?QHgws2*_;LF~E&`0FuE&2{s!%+MKbIKtPRU0h{L&r$G5l$Ftk^@GxUR zn&W=o3tqeTanQ41yTrGakRC5u4l;6rw>SY-G+!{i@g^u4ze*jz+{&Ecjb;u(3Ph?) zgR@`B8U>~fUisHNBDNy_ zkno)mNu~s}xa-Yqq$V7%?yz%AGPQF-p#UJXcnw_ulKeROZz=qWlu%exFI&`6(`9NA zxJ-vdURDI^?7=$6Gy%=K%2&k*cjG%nY5e%^>Bvo!22HEaCJTfU!|2tM2oz!B9sG1n zR2Wa-Ylx4Q`4-c^o)dA!eqBdKZ|{EN8@YTYo|+MD z*G`hj|9<5JASe5_0I*~w%;-*3L$gH1S}zC7I&Cq7|+hs0$W2;wH5Jrh)kR~4w)phRbY zS=e%&QCHG{X63@_zFgsu(S|_RGgSbQiTmHu@>4+2R>=ra>0 z%xVhoN=0P~LA&>AMHs1KJ4l80iurlh15kBPbWNQ8sng>Fcwe`)UG$;Igts!K&?>pJroz}U5sj7H2*qh}tr zOM9cn>BxyiC!2A2&Y|ISLd^}tX&T;rW8osL((6QHtS2-yg7l^{VK!TuT2TLya^@tD z1=K~|o}^=WUCeDSYHEy)hk(NS0}&w!&|=1nfu~W#rKdo8=ZaU?*$mcLkR&6t2yMne zGLx#|ymO*p_j7)BtkzYqp`ksIO_YVds_BVMCc{HG)@geni$2N1p4;93xs{Ur9rhvJ zw0`kKD~cZtfs@CEDht&x&Yr?VvAYFZii+6IB+5-t#F zLUBZ7Y0*$o1wPPs@$33!u+U|k>0;~EYa$pd>t!pXP$)+C#8|+hnk#N7x4=sCR6Ns$ zuX`-MBm1pHn(bM?H2fCC>mwrDUWzO-V;wqYA_boDM*o4>=8=2(D_rZvV={p4kjQ#t z+*q5nw=znq5wU(q(0msvaoDKg2rFWilb2}}Uha@lVPD$3<~WCup=IP;!ab=4l`{ma zad!oknMw4YrT>Aj{B`*>lCRH1Rx0(COk!5-le_}~m6S4v28T-6G5FASV^%}_-VPXl z=R_YjLEF=gZgdvp&fOnkRyV-DnHG7#DY+9HWy!HkMikgB?z@;^+n-ScXqfat{@tTq z$u?SbK!WeE=TCF*!jXzm0$QjKwdOI=>S1`yj~g3BRy^0FpMeD1Nk|`v z1(BX4shW&e#$JB-lJ^siR`kb&!|o?I9%IX9?EY|wV{Y)yjR7W&V!|6DF?X2%wDn;r zOhTCU&5t3(>avtLw=QscLH~4b&av*{S7y=D3#jiTHBkC=<8hk_IEJeT%-DxTI~SiU zHAG_MW46*QqK&2Fkq|=J*2`IBEze9zCxV)WyTKKuM747tnF04jo3pkG4#Xj%gx}!O zxQ&X(FT=N0Xo3(<@t4F~`aj>Tg1Eof*($t1Hn(66LfO_soIlf2oI@S3iz>O9KQWg?Y zF+w}``1jOTnN3j0>v8TU%7+Qn2>f%}&j<#4NOY40YQc8Fger{FWJ!Opu1zz-3OSp3p+%Q+|zjN(Mhfrz6zy zoK{y9-nbHo&D^oQ42o88)REfTJv1iY;+C_&CwM0=o9a6<=QsbwJ_$1k;h@Z z@DVGnjKfaHCxD@Xa^Sw)3e6X_NmU7IkzOz1w!|uu2xH88r)~egxO*5E9&i zI|P@;-ARzfT^kSX?iK-pG}>5jfW@X=RMym1hjsKAD0Tj&bnk>6cOK7(7)S`;3>a@f)9vGdyZpQT`PhEgQZ_ zVANS!(p>Dr@z48ZYq?-MLxzi#&mL{)zB<7nDt2Ms&(Q>;=?E2(5GDQfH^J?Y{j;myPJ6Gr#mTbN(k+(YJ1T#6v4* zqiT!0vj=YGLC;;UESkRIVgMuXVS_$h(!terwF-cG@5}lM5PVTdjX?Fux!t&})F2=* zBR}<}geCr114sr=3X2&(5FFdL{YA9^Ep=y?FI%qa?nD`kVSa`GrSbi3g_-Y)?r7Gb z31bf9FflsXhO^^L-Q)7q77AkVbBX!l51;!0G}7paqSXs_f(vxmB+|+>a9wlfJY+q9 zn%QlgACiNw%udY!T&w)_J{Mk8mfq2}_H5!B$`>Dr0!;j>=geol%Ph6W}yO z4F81Xx(jP{3j@E~+;eS5clU%loSiX;x@$m~7m#fSfwDU$_Wau~VlcuWK&C0!(%a@6 zmA73ShD7|_PR204xCXuK-G3+o3hOSrROK>ofqIuK&+xbz8}^FzMP|{}U(f8VvNIgd zT+1tz2NFbPZQ?a;OS=R^W)#bAVMVPtM;nmx9UoKo4?#c#YP>F*l7HmQB zooceEaSJa_L8S`hcUxJ=J59yVuD`kz;AZ0oKcXP7qvNZ3wCy3kBwz8%-3p1xCo4F3 zGWl(-|K&~>k@SV)Z!c@1LE$Uzd@NLAZ0SMqq{KF_IB9)(J2cUPF9)N@G3q*KB~u&- zJecY>3ti3aGin|nboUqiNs~w0V$3wAudk^|#(xn_QJwoxGjl_SjA@riNEH(}b6qh@ z)YVVD=5qc_@TuSZ?u;w!1`n=ZVJ#c6#9UTl(=j{Ge;fECDBp*RE2UahdsF%s533v! z^{k_8dA)*>t94)0A`R5CZYv%ka@)&1c0*gTwe6`O3;XkABx0aUFY}N+8~Aqn_+BJ- zqNVdc6xH*oCbf5(ZEYGRNzw=J2b~cy{6MuAbv&ov!d&ima2AO*M=-er%xu{w420{H zK@>jV-Qa!32>27D$W(d_e4Uf}qga8(w}dJo1XioEYfE+LN>V(DdtjB+R-sDPC4!uo z(H6~t?(H6I&m04wOwPK7;5cODgP)=Fag}90eN~>WP26v-We`%O2zI+YI+EU7UiJMQ zZ(AHp;Hyia2Tp{rs{Kn?5E2FIcqUZAw~G^7)#uLw7<#DaRu|S0s^CsYEZu*YHrL6E zfReHMdwGA{RAM@D|JA$mL=K<$AD}uD9?Rn}|F?vbWL~%6S$$NE^cK{)q<5Vn5N;&$ z+Mk_c?Dp26xppa?*8*?}t}E30b>S4>r(7Lp^+N*wtp93*_s^mFEiJ$~uu~>*!4=1a zXKsV3>ylFaX8bU?>s<2T;Tg-1l!oM8U>zt@|t#~<&-PKgh#v;qtGTFC0UoGzN^ zo3NXA>%EY-3;oA=Mc0)}QMZP;mF>!A>~-Ie}D8-*O)7*NLaqRie>)L(X`7q+lJA)_+j!;PI(l`nH>IC z@44yY(-WlSkq(Qfd{(Vlr%PSK3qOlRh)5zrqYq$IElZz{W&YQG>|WbF^>3hs{$QNF zum@OK;M}O4Vru;0(!z~gpbByCf{rZ@ z`OtQUs-H{ie*;jsh6}`vw5Y!WMmGm@M(@Wz+kl2278Dp=O-uiYA1(jdJ_M0GNLeU9 zHP3(Q{NKG81>TTW_K@_{5iN!;eKEdLIj@j7yiTfdB(43<8%{Ke3lPXjFuF z{)f_m?J}H(wwYW1%XbAa+%DyyBxBdmQk|%{HzHV}GG3N2{Wqr)H1BP^sOQ3~O=)Lk zzS!u3AKzR2cw!}5ylPJC2}_PTS8i=fcxOvpvG8}9fKtrD6<=IEyyxt=@}b}z8YjI} zXJ>Smy8aGvNt!_((S0y3b@Li#WK`S|fypTSnhk?eJcg7}4t1#j$>)-nMfB~(lJ39r z|JMr@WrO@-rXpVSq39a*1&4c?9I=^4%W^RkJ6bVhK-h%ZM-t>zRO&O?3e*-PlFfI>8;pu{>0Paz`P9NtGF4fIe{;=g%K-f+?f>WG|Lag$E!6Wq-2J}`<&AKV zhXUl%w4?nXsnxpnP|-i5A>sr-vizk};pr6y?!T)e+U}nBvK~y~!qhdS>glJ=0!mZ1k;Imh|_0 zmgyTekV2I~#j%k$ ztJ^prRpd#g#C{H7N4I*1K3km;HX2uI(;Niw@-@^?UMf8X{CQMcV(#Ebn3XwYy3`i3 z8USAzn6PdwZ2f4RvCT_qr`>b@f{VvxZIm2Iic~M@HV5aZ?7XHK-5R#><9w^9{U~@U zfbedqkMi<{`A~)hN48NAb-a6sv-VpT(Vw*V``Jcn@6gO|~ zr<_cgOIEO#TGURKpx{!SmLyEgT+2NrtF{5_2Z#q~I8kuF?&Ve`yd1*&cr~hi5iZ-3 zyP_o-KQ*A1CpG*_y}d^1y!q!RIs^|q7mc9O9wTjluPgz8t~g@Nh1wkfx*Y-C*t2)4t~UX8NaF=Q3SE(BRt{;B%R_;J-2H(*xfO z%fbP*s#(L`C)GojKQsQ+rS&G_fbYd>>SWzcGwSXN{wqUlUXWtj?8wyi2vAbDOsk*% z9{MB;pWEA`-0|{wYMT0vCQ6QLS=}wUxk%c|U{7_KpX-B$B&`iNyqbuY=3n%+xW9TM zB@ck9OxZKb8v}>DpJO`tO-WPptE7f_DJCkEYhi8KcHv)GioJ9|mu$x~9|cd+&y_Mo$Z*YT&Gr;R(FKwT@r| zlFkhZ^W_Aakeak|5OP^?h&SO$fA(@mZs?iV2WU*kB)S?YlR`P}YWiTNjd1Y3w0j)m?$X zPAr=i>rWl8E9|k|&0Re~S1A0sxhbs37TUC`rR2B z=DVKiKJmK5VJu@PD+Q#a;iv!|P(YjeDwEzWWbk^&| z_X=3C9K8fmA+!Qca4U);%tlE9B*rm#qDF55f$*-fKN8u`nJ8B11cB&-1m%64i3c~mOQ_MZwE@DT_mOd=s!tbW`}S-y>o_n*)qC5 z0#aLuz&t?`0iM(vuzh7$mfuEfsNfr-DkUyId@uhJhHZRWqEAKF-F=9LVMF(17n0!a zKLH@qg`M{*#5!*D%Hd*Bf}KEg@7n5tD?i)Fs)W>Tv4z@^u^O>=LNuhvpivC$$fXZW z+$f5w*f(a8?S_5COClS@3gkssY>6Xh59jq#CYGq}N z_{lonTKDV%RSpx$;+@d3!AoeQTvPW{Kz6=-X@yq4No~KqHT{~AmLEN&MUdwHqdIpJ zsWVFg{uW($Q6QVp*DSX;N9p$+%I((@=Kn5u60ZcAJJ|XuVU2Jb7o0(ug#M>NlKYkXDvVfnGAN#H>*l$zG0k=p5uY_^RplkWo%9a zg@E)U%5}A7Y{PIEnmghQKUEYkW^YHnF~IW$wR#oX*4)yH88VKhs5pF2&}P&lnwffz0cVVr!&iZoIr!A@>uObA~OCNOS~hf z2A@GNDXqD&g7Mb-!9Bu2b=LXwim}8wgho2Nn|j_DW>%HtYIkaL)F}rNnCmfg#6&Gu;Nx65$h?a42mCFk3+)7Sj zXvz_C@2gyk2;O@Aq@7t_WZdfAKLWY&;*FYz`{);I{XA;r^NQ-N?3h>5bZ!mxb!-p# zZ7-qmTe68CQBT15Izk-dptI{WO(|e=)T8oc?7w8eW-(c_%)x9D=RPhbv`ah$c^?-p;QY@6M?*S-a1SC@8= z>^+I6rKvinzjVN^wpZ#FGNn%Hs~s{{(t65g8r3oEUJ%)1R+EUOQlrTJp8HALX|kwB zRnB!n0$VV0cf->E5IE~Bod5if(L`B`@A8*B8&lRD??7zwm#6c#H$_kn5i`Mt|4@L< z!G9mv^hWGLGb@V}o2%17Bw)#%_C@I~4=Zit z{nJ=u3&qF?dvnx+>$NyeHh9iz$R6m;wnsTogP9!nFVbz;t20sU#>&gb+oik_D#!#& zZ?b{*hzg3^C6b8@Oq6K?xpqQil8k=1i8;rV8U&M8My1(NCKzidP=DQbO0XQJ`B}X_ zG2MQZ;Y>~J{s)}TvFqmEDPN2IIk+}HsCRmG2rCYR2?Ul06(wRL;fAqJRI~|6yzL8F z8?{@<;#aMW$mU=Cj&Pq{2-z6n3GlJ;QPn2w1QSKe9JRGVH(;jr_xmpg?$g@#W+eD2hLYdkW2*1JoyvfVxNNibc(#-G< zf|`9lB|p-TKjL2Ir1;%ZHrV~+`Pij%NXVp%kzK87ES zjF0juPE-Gv+%1ikPNw3}B9%tKx&h?e)kA^$cwxuEMbZ18+$dsRX)0j%(Dr`}Ow zP+GiQjID8E6IH%M1J|67xj2_P){ZsTWY^!|YpyKVnNRL~~*2B&|@}`}~xb`L#HMzV14BSWNbFWh95s69@EO?+NjX%Y zs2VlavHQBjbWwyFQDU|MlcXM<)yfZ2px1QUbztFq(g|u=*UXq=ZBD30DRHl(<&S@* zC&vqSPmBnV2EPiS?jEeE1nW)`$d$nx`FA88IxIUnmgj(vvYJu0M)BzAh6(y_Ue}g% zpljH*%DpDsz7FAuk6VrH3H%S`yNSCAYwD8Vpfb%=hg2~y4yG;1ci_Rs`Pa;?IZ*_`r<4)%*R~x|b3c zE}XYsl-_8O<&17H7fmd*y=yCkW1;nfv^|8#a@ zf>KS^R-nQ6o5wCKi{87RutRghTQh^78Ua*ad0q?%$W#=tH-^+E=ar>wmpE{+B zkAs5WvFon1TI8N`vHiEYCn$}7L{Tlcn18r`#TC?fS;Gbc@I$?3x+#1jJM`}<`i83( z0!7E{q$NqkvL(l`-dl^;f<{n+&Rt0uSI1x2`r|pNsE+IIt+2IIC1s%}O;6tsyhc-= zq?~UNnoqSVwI^0c!Fk(`YExu2DU%~_A5i*Jugs3+@(MbRf!VDD{d^X!5CLW zEkTd$=LW%d3NDyYRpYp&2|58G{r+aRhB#;!DMo#P4ezVohk7rIs%Firo(PlatmUtEYP~y1zTa)lo*16P8 z*D-Y1K7H0;2l}A2y3yDiu@#njS`P5_VDn=`Pn5ndv6pi5dL2mrH=&UuEbR-ad$g!B z4H4u~8hUWB&%*_4C#K{)vvzki`D#2!={=)QU3t2DR%`eA?a=bnBQ?0?l#3t*@5A*$ zCF*1KnzUbtj&)8mvxv9ra$BPTU5vmoaxVR7n3)Z};~=$7tz zUSC%~$4Z?{m(*H+S-zdLpz3|1ccT>SttU0y)nB7TUF|IpA8dkVM3YweP7ZCYy{lfj z9I)gpLvXesTm2^JiVxdx-J&*`uf)-TosJFSS7;m__9*1cKZld@wZ>0<#}WTuRANx} zz^5W+lguTX^sMl*l%nyMtgq-6T0aMJzyDC~eZKMN;kgMvcIG-J$;G?hf^=cTAH!D= z+e7!%GXHYKVZW@2&XcGOP@|ZAIkYM> z=5zN~-OH{CEkH4hFmK(%$p&AINvf%ZT$CF&AncGI?})md!i9)V`q|Iau3s|y*V~YK z!O#*r<6?+FmXjOD04}Zmw6UL&{*e%)hTGWV>P)jXD1rsy^0>zH%kTo294gH5=Wb|CrE*h=mBlc(UTqoT382b-$3}UsAN5u7Vu$bIS>V64gl>lKcU{si zn@Wn^IPM)Pecr*`kjZ1c@X5*jS|G_sXUoq3@~2EtbO|gt2iynwULGjU`W^%YI+4Z| z+d4!ysUUER=71pV8U>^^iPGV`Ild1dg-?@aKrMgc;m+JB&Fk8Ka2Qbr4_jC-TzN0c zCy5nCym1=ioAga}ykp}kitRHRn@7=*j#9ZikE%x_yBi1JG5o=vw{#d&lP&G!CN%$S z=U1+6&(;s~^5Ubni9b4(>_jQ|O&S1P5`W~Wh@=XRY`2kxl!^9ZoF&?|{?1S98*Y4? zr*Hf24}YalSN`7kGLegbIj)etK*l@L;jbI-R{)omzM}~^JBiu44bUsgL$=C?pPM7K zzn|jXh^_*H+Daatn!CI;4K(xsOwvL7yK{-O*&7;On%I|2Hzboe2D9Zql5(n%Wi(;=~~%432U|d>_B;FX=1_;FMqZxyL!(+NSuF_ znjd;N*_kV;Kxx;?drQKBi+-ak3-`M{6Zc~~X+|^vo*6?fD^eL=P}woGc;sFs?4a#! zK~hn%+C9QdElI8Jyl{(Ex%Z+P*LtiV-Rkjs)dqk)@xPMirXJ-7)57V=QN`-ly8=$h z^8nXVsk5Dq>dkM3@r!{>SO?ALTL;A@=n?FGC2@&?Lc4B>M%|SMBL+uwi|By?`oW@z3Z3h&?0~EQzNq$o>xBYYE?LmMty+ z%ys$T<{KcvMMg2)wYv;NM z7}##9ChzqNkvs<;naMC{XIJHuJ*o}m189?Q>5Ph|IA1*^8-E?vcyVO}@Y)&QjmXXLr zf6>-ss+RRhS4;2`6TmT7SfYwGQ!oJ>CKgmy3hs&Cb7*gvAR>eZvD(1`1J^=xCG~4cfOB75W{s7^!vF z;kbTJ6n7iW2H0an&@i<`$xdw;40+(Yx?vamPa;v^Ot25E$yzhNh}TFNyFmur@J|$P z;m?s)K_7|~BCm!9S4O?_KHov=eg zBjMjSbc}S!u8vK%PnReoHS)L1cZvdC##Mm;Yx8--DM;%Q?0u zOONTxgXQ9GmOd5#G^3HU$Us-l_C%Mw%&p;2vvCR2zo|kk^h1Fuc}y^^CH+*~+`te; zws4_w`P9{qGD^B;c_vN*mlr<$OMJ|XAq6-*=;Fa4>vEi;dB8?uy+rU267-dz2H4Tl zJX}K?-Zw|7?VIKyT_?H3njy}^SSU`Hyx5!9@c45(0 zd5!rpb_C(Kgb#2|IF>rutrd;;jE0xpn;>EvZ1-&D& zAg zs5o(-^%Hr{z4#4ZoStfr1}3=2>9N@%8m7uVoA`G5xnlJm1NFvwj- z`6{iu6Xth`P%S@o_2I+OskNH|vgby(xyFdSkqZpLr?l{fv(**MYBKb0>(0@|wa9gF z?j?kq7)ln*5bAB`FbamIkkwL;XS(D{jjE;<5y}!Nt}`kd!DqV~EJZDp)R8wapF3=$0>^5O*M$D04O|A<7}6uzI||*p2P7JoIyGC`-FyKh$T(H z*4TY=8ySp}0qlpQ{7Ts)NS!3&gjg)%(!RbH<1@%;jutO%^w1o6VHYndb?ny6dakTE= zYrXcX=5t5Vb(tF8Zr1h+D)SdDL&Pz4oevW`g?rN6y9)dRg*QN=7ura;<@tcgkfgpt z8J#%K*6+8RwK*JybwhAcU~HzB5$rrww7bABRY`F(ch8lENC9%8=rCG3JfiVw{4LPJA2 zpa5K0AsFF}wAM+s6PV@yD+o`(5l+p@q@0b4YI`JxQ2=8tgjl$PCA}8*`}68l3u!~Z zP6v)^V$DZzMA8x0YSIR6DJ4^_>CSiF0p@iSA3vp)MRkG*>K=Y$p#?4vL;c>1;K!QBa$05KdohB_#ORazbn7#mh8A2TlC-W$m^nrX9@|{mkYL zUjox#vJ{WQg5IUsE9)kkugesCyf|85om~2vF#OP&X4tBgbWvt;cv08N4HS9>b8|Ng z`xtJslxo|Kg=|eWMw=lN)|bBt3m?>$OFLxJzZt|Wma8bRfOvBBzZI_ENwgB96EQ9> z955GuwzS`ViHsbTFx~S36qnt0DuZa8JPnyQ{}^fE8Gj**+G9ecolFT`pT;i4OPe5g zi8gV1SlTN?t}+%d*|<%sjo5@jDxrr=!tsyZGU4BKtIXo#{^W zPYB2hV?33XI=SjEpM|lvzrL&}3qarv<)WBnv*T8*>Cx=pMsN_uCe1J~P*+Qcv3ac47emePiwi<} zJd%RJm&s&sQM3II{d-b=HDyEG$7AXh%P!&NzyF~a(}_TT=s8Eq{2b6(l3As1jCt-z z2x5NDFe<6OI<02a8q!gpZFO-UKI#}gdhM>XxqAy3(J|x=Xr`Wjv4Hr9o8xJF;^A2H zofzBLDXat5)+JBZAaR^rTE;++-YS-ee({c!(D4Di6QgsqI=ON zzBh$6dW?(XzI&OW@e5k-G^Fhav3$P|=T*sUMdQEH4Q1+KzO43&I2X`F8&OuYyVzPb z6iL}xFaf@esAV`t7_*O6x<4|my}A@|vy)a!lI&fWTJ&Ox-p))x428_ZiWKNW=$M%c zXn2Z0lnsC6^syk~>)Mc3zt3=^*glXdGt1n@n16%XyqJZdj>oS-HeMIkPsA{~qWta7 zigj#t`#Wa;WTgGYaE7IBA7-T}KS4a<82mu*4gp7OyIida(XrVlZ*E7B8EANhf0UX= zz+G^4G|zRKkM5XXg5_Z{>derX$zBZIuS)f+2mCXqgDLO>JAQ$4NMfiVS=ZmviwH9ayB>&>=xhReYl&C@s3eDqF{AS6&c#_k=0q?e5D=Kxkt(W5vI9vB3&;u*X@}hE ztr1Z6?eMjC`nz-PQq-8{fvK^$;yAHC75$^;fb~)BkqI%zaIUix%@Vg*PD*ka-_1pT z12+%9(0c|ZyNshhqr?l@5<2*mrE*qT4r|tbWdSISo6iXfC)O!i2|*~dd_=^de5hj# z%GHSMtJ*JU%L2qU<%Ut>+_vCS^JHuhJ!F?Xw&tpmC+z-V7+7<}T1#i8e#8oasc?z2AA}n+nK5jsW>BHjVG@9~ZnM?~)f91WWsc{eaX1a$>MczEbJaJK4dPae{Oz|kRF>g_<^qyI7*GnLT z#d6IPQ)@1rOy#7?*hE6zzNcN+rIOYrdalt8x?r*DpfAM8o*A0DbCg%93D;xidorfWYsxi}#cIgLbXadX!`;yD@+RC0K6?ix>aQ(<)65 zDMmLPr{mWTS8VqeT`}ZJctPW(xB7}i-CmZPkk*W0-ep^b;JpaFbN~RnSd0!5e*4v< z{H?4&21LjdiY7EFJp(~YN^-*mcv!_^+UzUxb+#|wwLOd9F^=BhIPY(m3|s#mRqQ6U z5r?plIf`$yNHX8wTN~_5i36vB_ z^vz3D^xled!0V%x!lDl$Y}uFM~adh?M5CU>Uds%I+v^D@GSx zgvie;H4{mXOl5ZmzWumc^)^4oV#v8Y5pNX zF7>9P>ld$saVk&jKpO})w(I21D9)LYIu8Tn)t~di=J_rUTHHZlT=OB%AjVqxUy?7m^|E)KJ7#ARX5# zI2IZUqe9I*$6&wmchh`vE4NWXq#)^yZ5Pn7NqRb6y|z2JU!d?xREW;Dtfd%`v*hOqjyZr0pAc3P1IpY^l4K&?Z7KIaTs z^2V!MYk$n7qf@QyAVs1#rrpgGy!5ebBDMpxd)rP5xxC8GD7rQeN-{Bc4YNydihrzW z+spqx;3{?0S>vW&yTjg=$%;Ajmo%+OFXo@jUR4tiFTQEN-ugBrmPa9HsV=cj14^QU@*5WYqQ8Py0uk7x`mqJy`mDLYy|EG~Quc+-eEI6w1 z!7yijd3#ae$FD#wNt`_w3r7>4rv)!hbBn?H-vaAIv#MO*z|fOm=ER;)lCU#tms>@p_lhoiN6%W>_MFegD{FGa z=C8_C(c|DRE<@Sx-uytG!cCn|xrtDq`lX3^r;i z2$>AtG*X%m?6k%bu;y!PB3)sj@De8F0IxubSK2 zPj0JrH7{*4e8DQ5rXKk+bZaD2Eyl96YicB9&k|Bei^uft0Vr-?M1r7yZloS0M4E>J z@<vNL+XG;5l* zgE69lI-qaWJo=Jjy(|wQdP7b;?>2FK`P?cprpBuK^QW5`$*(PpD&1Y#;F4n|7=6`@ zyrzO>L%cLLREk`GQNNmeS9i(ZZX5{mmB8;AF*>MlUnNcjtaQ>+U`SkynLse4e&3 zpxpMElwh{ZNFJbkc<>gG{uyhIYGtbdT8t1*Imr6Llj_BqgSMvm(|&eH6EeE&#?D5R zJy&3)w3awj0=0$EU$eBX$9Fn zxW%UP(b(l-cEb_^&1BE&n=HdSrK-$ZxeD5#^KQbWIBeoaRpsb_8;7`5k>%#s!)~Xl z7E8W+Ekk;`BsL7;aJBr=DsCsc2C(Ub0=H1oN>K*9Wn*-QIr-lPvYihaLs_-Ew!MlM z{i>h9IXdCs+#%4sGNZjT$KT^hA92rmSvq9=?Sfv_D}yMLg-hEIUBu1$eUjxN2Y3Em z;P>rb?+hg%rcIr*ctxF^{(-3{gk(Fc=h)$hVi`^7l6*qLrAAk!JO$7v;W>FR2 zCARIGA7Yqh{Vk@hl!{2x1TX9hXghR?U_Y(u!> zcl@(5)aB~qBZ~R(0j|+)zRRYl#+c^bDM@498!yn<0I&2Nc~e7MaqJjFC(HRP`@i^& zToYd30jgO;FyX>z{D7|Ue<<{{elwtXEzSY87rC_aB6s2s*zLrJW9erZHMRDSJ%D;+ zzI?x9J+`ag&h&DPEkwJiCMauWq`;hCr8LTDrpq)aDJ^V7>Xt5k2UOjnwuT#&D_o8_ z0xOi`cKnD%F;a=Lxe8U1vWG9fQW;9abV{q+{PECka$ej6rS6QuF5g&SKWtsxc*bn> zw}Hz7Nu>5hn5__4JR?G4_PsPy|MGW7U{1&9Sto*sc2KnL`PLgUf{`fuuRYc<8?_aU zp#!;!IwW@Hte3}bEN4K3S5g08N{Lv#(2RoDTKao=MkA&slpgBIDt}H2{@4n6)dMIO zK||PDdWoHxu9eF)ZdXsgO7gt{gi)Y(UKei+KU4J{Bf)mTLNj;2iSS5+ZUbcb^zZ=j zQ@Qpw+sj4YSZ)m0-X@S_IM^S2qvI_3^=#VMP%2u}tI~p6v-c;AmEOWlByQjiImcvv$>x8PYthQg}3hE)^y+>wSD4Ys&~3V9JV>e@^M zRg6*kjmVeGB2;Qr|rY ztRE?>p>OYl_Z6gBLEQjz??%EXb-DV1%z|l6W_by}tCvb^3?5gzB+Kg;=jYby*_-HbgrVa~8%ZKb1gr7% z{$-~tt4f=YEHSLT@jO5bj*maR>I&jErYA_p@QR%FbU?q+=D3X2^{QH8&l9R74{IC# z;i8(C|YtEkwYIEoBB2zXg#CKA7gfKd^1^3kXTLj-!BXg5QO}>4JLs=QMgu5d~D|&je zwyi-s#cSNr~WTHClNFM9I0k zY}wd3mUL5aS=pSvGaxbPVhD%r670OzKR0O2o1jGKUg%N%un*{$TY80^q6q2C>0j-s zlg%y%zB2d7iY!KggetsOWP#~vE1+vEQ;RCNRMZkn6GxSRnp=3)@+({W+22gZ?`|wl z7CR~=IgciZq+|H5<_;d}>7=8}3ykR`KT3x^)<7FO@)>JUB1#bf1Q%mPGRL}0atY`E zB)~$6UU+&Eb%ltBA>eO9;`R-%f8m_}C{#j$~)E{163Hhz2CRG&7HewIl|@;(4; z+p>UmCedj=%qrGuPHE@BO0ZRMW#lYUJs~u5bZsJ!mxkjU9&1J-gK;uDH!f`CnXdFL z+CzrFxt@4(l4U8$T#M7e?#Pd4TrBhAk0q;^S`AizRvg*M((t7~aYBd^LT2jw$`gqs zF&U<9L|t1*PG9wq7U5Ift%pl4*X4MKvTAMdTEMn2)cFk9c_R_cOKuC!Rdd9s<$dGq zTnLO)CGNNPdTp?XZ%!Mov$`pj(XcL$G~A{OBLS^OVL>mt6O9xR?W6lQIMwSGc7O6k zSxI>tvyYzgPmoGAkcD^&whTYb?9!fr+I&4@WocJ-(vPnlfds53AfBwc!gLXiWa7Hx z`Xr%ZXI2Sxx{IR}np04+U1E-j>wFOC&%Ueu7gd1?@)k1VZ9k@r^w;L*9^Z`Tm9|$% zzY`6u=3syZsE7cf?u{e8?)+Grvck1?_Y$^mM>GzmV4Y{#n(RW9ZJGG>h^n^3PaVKEFMn#sgGdX zXB|G}Llt4Yhl96gYPL<|W|*nu7O*H4&bw!)zqt3phytn~3676eVAp+qiqTjOr|0~( zZsJLxo1Cd{VX_Gu2RL7kj(ZK|b4#@c*vjDllTkHi0WRA~_%Arz+XgL{H3ObHyT4i3 zklm!s5f8sz7hmS;{U6rgThx)sac^-CEe!s&oJRhN=215otn^#I#o6X>=HfcyFrSzK zl45AHcm?|3P}x4j_=%ou&U^d1^#igpSqi-=Nw%K{LQp?}-6q~ihl6MT8agfsDHEBa zmL>k)^e4ucd8lL%D=Zzbb*k)!ii>p>$V-D*pZ_PrF7h8rJAjJ6hQ%t|*8Ec`84CM2@RP@W0S%LYor z(#hiu&yA~O(9!7!3_%~-0Y;yy`-%<``YuergFvU8(c=@L?H3StG6ZY1tmJnn2%*bI zFhOyA831};`vtt(0z!0~u`cl@qX?0>Qr9vyHr*$&U(6A5d~`E4A9Dj+zcil}QX?FX z-!_J7HC2&oru6m@-#8~5Dx^VD6uD^ZCo-)U$t4ha%^t>maB-@^&G-!B;SJ-X42f^5 zwMRM5fv*B&em30ohzd+;VZkLp35J%jr44~xi!7moO;nAr!QQkX8$Tl$w=dT!37gk7 z$F6+00eqAc&&>j(1F%MenrDWd)_BgnkYU2C6Vtzew}vzJv98-O+I)!z7f_4lEVm;+ zIh;G~h^9=2{CBP?W;&GkvneZ6+bqeRklMoM8v#{zOpd;6?~8MTRQ%)yd+7%4P8cA{ zqwkfr8}GZ$UX0Asbd2DW2481w`pllP>Y^iV$lt^x{)W&Z4Xm;xx zrm$48uT9M+@8`+b-=->AaIBEqwl4+n44&JRAS(s)s)^SH_}9meYPKe>|1QgHL{cHJ z;)bz<34U(3lK*L5<5{fKoSy*L4ySQagLz;RHE^<)qT%f%t}|_p^}Ok)Rq&H8;xo

    K7bP`H3X?7*)qLnTfN$U=mo1nX~JcE~ZUHbnR0JxvGISvhT{p!IE= zs99=cVd0nk!G3QEgySb(8(#eA8lu&on(byzw85ysq!MIC-tC08K^zo@DR;$b)SK@x zf~qNp8v<-{?N~4;%;so{JwhewXT*OlIWU9zu!>> zvt}8Cz_q_Wm;-FRBkj}V4KwwXv)^$>2J-}%*R&J>3G*bw7bZ?zE{y)VoUCUeWqKy;kOFOc zr8T1W;%j(0Io#2AQjfekKiaRlJ;?trroJ*Lu3!rjcXto&IygatySuv#u7d;(HaLSz zaCdhI?gV!TPS7BMU?Ds2?c1vT(f@AsOxNu`ea=0f1iNP>ACLs%)P5bi%tLmwZJDSo zYvZi%@C9_oG=C_I(7FJ&MBJs+p8qPe5$u_@|9CskV{{sFM?{YrZlSG;fp+VFu>E!r zE}FwWVN`A)N(w^i2bz7rnCli^R zRC5{~Xs!7Tu0UQQnzQH~iu0;20)L_3a93Y_fS#u9!VrLf`NC0dezy6MckAlBr1-J< zah3pVVy&OTh0Dbhrw4@$d=;i9DkH?V0mf&>kRkpYWZKSV_D)U*GbWBr#+@0xQ)Hq5+rT$@$_Ivu8#LdBHF{)p-&s1zaF{4tntXm7$ zPrCPJ!bG$&xosYiCa&6Ic3y zjuhycC><6b>`<{Qv5~~@JuQ78OQHjYV2VBR2stzk|h&X>`FhIm%mXlcfQMO zGUlVLlrr4o2StLh(Z5 zr1TLUAzN+Gp9W6^cQf6BxZTD=eS5Xt1kiY84Bq?}@E;&)ViFR*di>`J=UZz6x=z9}mf8q9+)6S$ z2?o^chjiV~^c-X{tF-*|4A<`>-bqgvahYAv!H*N`mJrg2OyZC)UlgA0K^wKX_3BMWrKqZQ>Z}w|8XOKB(6Xw$)4uL@+}r zIN`QJ_l3pgFm*ngosi*Vjjer<&mT`SJOOMI|KD&~I9~7S7b1v4Q6B`_%FmtnC3Wfh znq?X8Mvq3*h!pfW^fhRTdO}FyJ}~gA~%yW%`Z@CLe=y;ujDE;W4TB0RN??1 zevMgJ6N}%#FadzGZL~Q%d)z`iqg>$lvBd>H(27ypSwxeeT^l;gR*bQkeLn2GM%YYu|<78e$LEQKrOr; z{K<*jfoQpbSvTmq&nKs7TbG9ujO8Rs7H&gKgLS01HCF8hU z-J^`>k=3K4PFKO)DE*cAgdFcE8qQ z?wy{wlP{P9a~yZy?#S4Rtf*ccc$6^W?d-`MR(( z2z9~o1*@n1d}lH%5Ycq$XGo}4Lgd3LFr481O#9U}>5)5@t0fDU?Rp2a=4(p*0AHCC=7hKzHohh}!uV#Q_EAEPmW2G0}Gx~t!e zhF8N)v|HwFvQ-5b3@Wy>28$=}FB|+gARh|x9Du%Cj%@Crb^p)sZXch^T}&fa=#ROK z%uGA=o-NPsQN0ewZcI8j+{nI}<8+O!m!ld{L~qh$@cK&d(pWXCc7Nl}yG}9Wogv#j zg+#2cq$b`Hu7OSzqbD~SYUth9>rafd(8cIZJXQ>>v&E0CRI(?Rr;}C5cNW0>uBY~2 zu?S#~$jqXMQ`Qg@!Kn{BLMUH~vbpaB6rNrX)I_(5P5ABQwOz=XCt$%UiT$Kp37?Hg z=8thwQbc|-B#_m-5mMH7oFAUd`#@C2y5@e$;|!sm$~`0{k9yvyq9*<@a@ROl$u4w$ zH}XSF^B8e3#(~oBUfUVVH;h2VXOfy+LCLDd)~t9q9)ng+)jbg}PNff5G77Xw#uPER zE=ZX@!wPx)!;2>%7dw~4NnM-z1oS$Jf=3pjpJ}K zdg5;8YhW&1qp*3;r<0fDEATZPd zVyU$&F1>DKM?$b6U>vst7>p2fzX5q|>koS36;FRzIa*F{8B8???E3G=q?A!PEGk5A znpBYGrQE#j@97-&NQm=)jey7}D_OVX_e5|oe}sO`tsKY%dIlwe=;nC&n`X zKBG2zBi-6}Dw^+^lT7ca0CB5Eo66@SkX3{pOBhGv7}gmr&gZ!=(Sicjd$wv8>)n{S z9V`DZzOrd=(DAx7*-85oDJr^fFub_b>jqf-Q1y~u56j;JoX8y>j|3u0%aD!rCM(6& zQK*(r-?n98Sc`$YpUM{ou;-Sj!|$Z&wpDwX*qds)$~$jthpd{nEgX~VkOY=v1g0gb zQ60|(F&DHgNyO~XRc<7`PI9paZAU$8i;qtmGfw%4veo?JR(n~3lYkt_2#1ON z82)BHQ8Cb!Td@&`eI)IXq{U@YWzzZj@sJzbqSv|av$Yb9J)={#2VTia+|KW*gtFA@#a(X0!4>NUOW1JBZd_ZGj#{ zf8lYT1z^nqeRR-f;p2pC8JmYW0~LS5+5zaMb!En^*rlqwsFnE*nZ<{lBym%ufHqh? z*+khtBzZ5@^qK=noAeSaTAl8xqPLh0DaEcB{DSXdIqYI1EsyWQy9uk;@nIXQyaN84 z><}DRnAZnuzqTkT2!6^wDMlKT#?{XEMN4SS&62bIW8}`GG}#|d;C)3wHN9%lwXE9O zbnz#DcWqdccg~JDpBv%)%|95|X4c@3zW5mRDU}Ilqlv@lMcFfF?A$!fbnCmQyE|gT zFQTUM-L$=~`9kuQ}BT3^plgA3ukDMQZ0;0(1Bzj+_+Aw15rl zIl25DWxbmw&g1~)Q{(|D&eZ!We*}?vBalZ?T0*3bUGzM+$5AY!l9!w3{+v{2(<770 z8RjRstXg+xIDSsekbyZQN$32a7pjf4ZvAW15K~#pG&^xm+!$hD+i{;Iy<)TZH;cfd zuxGOH!p@qMKs8Z-KmHgVgb=N-FPEo62tuak@*{T64o2Iqq*f%3io>uTN!A)q^!W1; zm`NajJ{8sF6gnv$f5Oq6A^4r(V?$ytem;#?9HVuLz%NFau!7YXq9AsSQoW=oVGd6S zM*6k1N&rU~_&rsXmDw;@-sra`XD#&#(u*Cn!Wf>70FTw{cPZbdBuDadMVt5xfqub~ zjh+43Y{N1+Iy8GxwM;!jM1#31+ri%0 zPAz_2$w~yc?bCLEqJy(I?kFJM*2g z4j{*i|4JG{)sjFVQq7dbQ=Et-Mi$c$n`D2*SQ@TS3M|xF6qj$1z3r+VE787PYpEb> z3!0pBN#;*3T}4Wym)r<*#6M~f(mFgzxr`E=q)VxtZeW@LypnT?$fb$f-O|LITHlp) zbEH={YR^)}EX?95Qq344nu=urpyf;L5@kYev+kFaHmjkjAiO%G-x@At?&-x7h9hI5 zB;ubrZB%QDDpR>Xuo>e`(>^%wIG=6w8$4SCJaP7aDobIr6qb!fUO%U>uLi6byE*>! z+df0sYK<(=n>fJvanx)`N+xP1GQk-&Ua8#1wvrHOdW|TyYfwdh%%)V`c3CdX4zOCo zD4MDMMI{Oux9|T{n=gwgQ#u=Y-E3l{u9=L%;i$Kd?FW?xr=yShjkS2AoJCabJw<#8i3&Kq?oMd0iQp1l}sH-)2)py%?G%36`#&o<6iacLmQ0*}o4a1!*mf9i3BYVIW{~wHc4!ESo2ks^e zY9bIapKT)asGF4i$@CkK5|OfhxOpz3PqdcWuKlM|KFTW6<@~z&79YKh-4y)H`r*L~ zmvXO7aO5E!&SO_2PmKWDT$^2#4RCVQ2)`)9F+jOFqXyVn%tQN=v!%Uo!_l+LC(5>M z+{SVk6@B%@-`&7fjK8R$^|iPE)#H~GmfzT!hm!$MuLD}lDrZKBv`^}R*RmEBx0do` z3%irBbz7Nl+0j|<2)K$t`5__+ghY))N=|o^S+q+=%Gtg?{%tp}HxE0y$jhJ?C&9I> z$ch#9EbFpNf3x8lMQ19< zkk_7&(lvHDz*+g(ePsd%KOfyXB|e~Cq4*G;lu4%s982i?L5*HDKwzp8J?B}f84n=8 zLs?CSMgs*n-D^W}DI8b|Q^hA{gF9ZGKtGN^UqkAj*X$cP@5S9i3zMhYm_Ophn;R(8 zQ}Oxk@cB}c|A?D>Kw^B$Qsf|_W*c|r=8wt4@9R#FZ~QjlrKu+cAcgWOR6Kg5T;?5W zb31CAq*P7eE##unpt^@?yR+2McJ)QOFjN7Ke;MSsZRF~=9ed1 zyE@;?N5~@_U97Yvor(x9RF0Uvgm&Sk!sd7Rb@vAPB(IW@(R-D+ZILmn%1g7MQmF~E5^Z9nc>&K zv%CloCoyWYB&o6xlO%ft_s69KCe@K{d6(ZU-$S*gbna9IO9M5b%6GW4)92-z9HVF_ ziFVAB@;MS+#!xBqKK-i=&S>})y z3i4bf?$9D;!)T8M>8!|6r~-{*D|;t@G~s3tmPImQMHGQD?viNfD8me%l+kL_r$^8J z!E||rcB7Lf=;|F=N$nes!%)pZT51?XR&O1e3jsbitR-VTDb`*#K`jgfSsO%kOf)!4 z2(ws)jbW+QK0BepXnV&Bn>klnY@H2=E4(k$8l4_{3h@Q>;>43HO>EYLldRvDf5weS z9fvby7S5D!z%UzN=b+@no9*V7d9~KbLW)Q4Eru7MPQ-@vh@wcxpdB2IQ2YXVGwuv~ zI*a+}K3MXXZ~7w>C_M|Q<6a+&jz?5W=&T5)vGVpgXymd`xQkJxpaWuJYINJV(6h!(P3 z*&qOxSpCTFy-LG=4(pL>xo5COQ)rui+|O7Yz3bQ1jn|zIwZcQTC`jaRP#mh|@z;J^W$Z`^T`BoM`nsRuzEuMImrw6@kSN}phWn>kM5bzwY zFt;`7ccHxi182AY!MvY|5B%-(FxXOxExh;1Hg$eDo!;C_sO!GGSDVQ%?n!zg^0yGee(En)vA|rKJ#_-*3e3T2Vs=N~2>imO213<;{ckXiP!oDTZ0jtZG1cr+;fzMR`l#cVr^@ zFL2yjCYi$Rv$mue7-6LG7Wc&XsDc$3BqwMb))@*#d;3xfIWYoSOyqq5D6Q!BvyL%_MgA62D zH#6glJ(`3ZnHX7pf{FEhVC?P~^;Eqc-9R|&8Rg5({FlPgp-&$Aq2sBORL{jWQB>0D z2G3s;F=EG}T&wk)eD#H~v5Xy@)6aS9c(+SgY$|H;KM?lF=2V@hYAH2a^?c%2(CnYM zGqLp{^wI9N#>#gq+Wx#9O<`DlMkIU*6$oh(msbC(tuod=%`ux&I>coMH(=orKyBix z=*Gjm(Ij~4(KI|kBpjH3btGM@Dgddx&BH7-JiRFN^CR69-sjD zzA}vwOLqz^O-Kq1X=_kROH8R;69K`;&L|2A-=(R`#wQYEV|e)twf$%rjoet+mGn{6 zY97ZsCj6Ucb+qT$lN(DYV;d@HrOLQyjT)#K;_l>;Q=Suu?khR5Gc-+KQf5_`-}wp1 z_@jD(@CG|vGtq6@B79D3;nu6O4UzBd>*)AnMNn)1}Qd>J#>P5=7 zeI~M-o7c(6ts2=%q%{;n>EgArBW!$1h16D=$G5(Kuduv^aB>LMaPf!adR_Dc<7pLp ze1@H?ZKg=`Lv*f#@?_#hn`al)L_t80Khh0~j+OSFa;M&%teowExUA^RchZ`c3H4|G zzjv74w?PQ?dnlrQ#%Wk3)|qKdcrcdsmmHo#-*(`kdUo<3xzypMoU8l`&~AH zx(Nr3)g`tU)ss4I@(Kejuc`+rGx1Js_=)XX;x)rlht`UysOlcZfd<3pGx1sM&eGMW zCsZod37lSFS-mY}^RQ*TjW92B+=sF;js6JV`-d@LYIV13WG3D-b^>~}x0$%Firk81zu~k-Ze?_}hE@6^p+$KP< zd4AaaZ$+Z|)y4UXp{(8y8-sgRi!{lM_tM^gO$!CJxL2J%b6KibPMy>|6u=bC!mhgJG_U`YToRKp$g&d7@zD%v&e5j;yL&KN;znal5eY;K#@zyQpI#|cK z(&elw(}PU<7;g@1<=yN=93~rM1NcdP(~SIBS7WCnePGPlB~$gdX1yq@&*(Nf1D4gm zW_|XjRebz_AJLxWSIoaIzE=j0R#3RI{zL8+MBBWirB=!MoK8p#cDdfEy1-oNbqYtt z`<)V8njkt^Uh%#&0Z}344?mSu4w7x zt|rQgaFvj(@WeKYXLOb-ECOh%C6o6EQR7F7{3AQYZ5xY!b_JMi=(9w{7#tAVR#usS zNekbT>pWHXeno67**SPKYv%H|%%>PVN238(oty>*Zr1@sEK22Op4v!YJG-ya_k#yHz(0>gw6bHiywD6DVqjf7N-C8H$

    75n`j3P=9>kSc;gvj?HgcOS4clv`OY;ekFqARM=>eE@t!=IK?G>~m zn^3~+h6LgM;IfF4IF*uXr%I)}BB{FTuoLVC?$^-!zN$rItALBPX8t=^dJ2p>*`Pd|&_>`VsvH|uOKlUof zkT7nzYtpJ7kZJ3l;~MuBAw%13#UXw5cT+e!tt>!{324$SV`x6_bhFq@pJMoMrb*Us zyXT@pC*nxBhnig{@PHl#5W(WYb##zB!z6>IOp4 zWl9`@s==mEt^WH`s?5)k<%2ntwA`Z1!+V*ht8#7?Z3cMGart({ZTy~IBvH)PMlVoF zBbaZB_hoZZOvj^{Ih(>oZmc>%7OIqCnW?GUrsb7&`ipW__v%|aHG7IuQ{O+B#?inf zihAciDY5|JdSt>@y5i(D2qSclN@XQAClc}3Iy(bNmVth&278+a>+cl0)zt~=BF~3^ zqdpgg8V0xpH`O|=@eP2>n;8Oc^8`wWMsq*$VWeVYlm;ntw3H_X_mj<>{J{-)!Z}J1 zu!WePJZ3)P{hsP9tr}=>*IT*C#yYsv^seGB2c%{Ya%@;;Bh1g;e&6c-8MK)4f$0;Q zxXVfSf&!Mpaqi%^eL=a&WjWq0BAN~j9jrX7zeVBkpoKaoTK5y3HQE2NrA;YW9ih{e zsS0-oKtVff-eq*Sx^ptBQ{XbsC`AngWy;T*L|Tm?gENMa_Q}hpt3QqWBtlci2S>}? z?n{QH>VKQ1G@{{8zse-i0MJr@%v&bN7vHL}oT@Gpw_c@BgKE4R0(CV-SnAu=PsI3+ z)kIDDL)O*eUYzRfc1}AlHH>v->2K9L1t46OQ|EGRMyC6WVGG>ycs{;2M-N@@>&J!I z`^7;=)#nm`>f8PD#3LwWOwxN;8M1FqPFNUjk(iqeMjP87h_lxtilG7_U%nov0d|wK@l^6#Q+! zfXqN1xBBCrFn4x~3OF}XAIsYnEt7oU3?JBQ4#(xEq_Z=joT!nb(m#QiSOx zvo*x*2It4>GM*NlCrqn`tqpbwJ-@u5*6>0DMyXqp|^&_nSe7#qAin+C@Sj>;G--LGf2!P zADyPA#HJg-`~ge?P<2L>=40<9=}@4BV+9F7HP{Nwa1n?NY|z=u9v7mp2S2~73%4gnfuFmm$2L4~@= zarzhzx?{Xub4Fwi240<03IWK8Dm=4@U$QYUBp3J(Y=0d)j_?;c;JfbEw zA2@OA*nF=~@`jwKFEeDUA2HLlgo>ev;I?%A@{cbbE6udqlRp+$IsZ(@YKzOU(YKUW zcYUa8ts@vSyA)>+5Laqes)Gn_2F}p)i~AP>`jg08r#X8F6{h*_F}aZxVY&N-Eu_-H zeL#IJLYy~f8!XYr^>ERXixe>x**ye{_LE9w4B(?K$hN8xCvZ<6Q5NgRDw|obh<}T& zs{l1SCWS^R630t--Na0h(xR4&NMVL#Gq<7c8LYY=)+7@J7h(Ztw+nDmG81`_tcvDdZM_a9|A>YrG}WP zJkXL@%BF3dba$$|{n_pPQ8qrD_{e$|y%1#b`DK#M0SU+iW1J(pBMELGJE@i!-;I#w*JiONNh_W<}?m zeB#YHd>=>l#VbRsu*2A;3$s}w{%caSkA76%HEIb)i~)U)BPoS(Z0Eg=ws>>h1)&y` zq7Y~Mh3gAo*vpHkFwCT?vRJMh0+l4Mrb~emMNO_AIebR%b%umV+p(=9D_rDzs}~#g z&uD+g2G%t62xzb9_!T#utfu|&~hN%wTvH{1Zbc08QJVQE@ z{Mr32{)s}LD^XK6%<>(A(Sa8~TCaH$`!89fLU+vuJze#`7OZMP-}*Az%S|UUZDyLL z>W+TeMqB^Nu1aX5hiN-|;F6J%tW#m^O8?~z#Kc-j@QX&b-6|)!h)1Tb2+Wbho5own zX6uw;|E~48#sw*rTt92Z)^6Y67){cm^kmDl_d@}g^ZAr0t?mo2tIHM;^GYt;T;5Ai zwM0r|bKzDkkK66IIWQ%p=%&~&UiB6*m>0LFaIO68^nZTx>e}R6m!Z5*VWW+6|AP~s z;Rpl!9b8m*#_HeJ(c?F7aCJ>{a4Y+g?n9uk{10Z^PiOzf0>r@SV^!M&c@o0m5xX&uGyiw#|fo^eww!6ekD zjAW9eHc)f6X^>gnD{pYwezG0+cYvnhZ>=RexUR59Vqa;i_M^XUaQsf}V*;$R(Uaza z=!iHD5#ubtp?InDVTHM259y`XAkSu5HhcG~1#=kusE3XExrZBZeOJ~|u&bE$6D$M{ zXx+5k2no}p?+fV(J-Vy4+b~yLyb^E z`b1`VOI+jK!-YCiG0KJ?aC;fYXK-^8n-q)q1$+lZ%*nTDPJp-S>W3S2?;xreypYLX zP#-QkWB58JYdI5_{!2)# zQr4Ww#w&?koCUjWl#C4a4&OfTQ`%B&yrmz$=cU(uFVscex^y$YQ{~gZ5D`yBWZ&p4 z5E9;zSW=5bYLiMsohUc9`kVswZ~Pe*(ymL|dBF=pc4#{7k#OiUE(;9`Ow#~((@vc2 z0>Zl2IZ|myQxeE?vkoz%>s3+HuNi8(Sn6f@z5c?`yii= zHBu-~IP{6ykb|2gT+=i+p|eopfr z47f*F`d!2on~@$|N|vgy4rshU@VM0=va=2?^k7W=M4R5wO00H8=&+~kYP)HRjr=_h zqmHTp`yWhVU(hQdbee{HuBV#jw?KkZbi`|z;L{UDEwR{4IUoIo0;~V`h`IP^!1E*9 z+V>{?4i>kzo6ED6*St$W3ViQB7|TzlNc8k_h|2xs;g#UYA2bcg4B=3`9$p%9=Z(`@ z3KHeV)hru8Uc`5M;W%eEZz#7#_J5O^pP1jS%^ZJtI_ngD0u6l4mu9P)puVAg3nB2x zI*DzZe9^7E^r=?o38DnfF~zXY_h$U9; z?baEW(Z5MxDflXC8#dc1ijkvMa3T9+hoHxP9=}yEX|l*?Oh}Q35P&SOIspT&qnmFQ zg2_L6ljqoL#h5Qo2xxs9z#~UJN|ZgQrL)51^TNkiN{z-X2*?fRqHmpRx0 z2M|0}y7u&Hza(X)8S|=rCKPi$>Hh>w?JufXNeIZ*uO_>Sj1>OX({8n}^1DdPOnY!V zZfZk%H5ps2&H@}!9XbI6+gB%hrL&K zPCa3>K;bA>w~7+(ZStA9kiI0VPLsjA;D9BJaN!1fUX+9?tG09btp;uJ9q9U;*;%z? z>I+2v{CO!yhnZxSv!6b@pkvFB0t0JO3u!U&0c zyC7V=F{aQU6*_S7F4Ww~uHj1Sch{$TgFuxvL!dC?Lt*@S_UQ}9Uc@*=L^IUD%s!IL1j#3E>7k8MqZ(7?gUCc z7`4&V5#J*8j!&IBF%(}uWGlp-BopZL&l?F@VLKGVXz$IMB|EPd!oXlVQWG++pHIDD;w!I2@I?#0xWdn zt$hCYT>rFjrgdyldu+^NQl+J9bBvg=Hc?toniP8ugdRRkTc3x1K^$c{9)N{)+xhyI zkWeVb%P;wIeJxHg7YtLWD3geL6pn@MKXH3q>`;na`5PQ1_etJBsHO&mG5KqT!=UJG zm7Sds8ZsVGZ)yemTO>%IgHuUp-|a@$X>+sd$-M*ZD4CA*;3f$BzmcIANdh0jMAZ`jdjH3yIwzwBp!X3 zw9qx80o5g0{_nsVyuGas7(30MpZUkIKP?pnVrga^^TP;@3jeg6{|AHC5G$x*pw#>` zB)ThrtZ*<%j5)}+!%t2ENfJ<}q0lThT$FZ1mct+9V`G1~Phg&t&XD-UzmsS+{rBu= zUR6;US<*V9e=tGmds_Nk>d*7{fhE}c0XLNcunj(kZ`n?BroC4qF65QoUFhcRTNO>3 zRwq+;Jf)3gpObllQMyBmekv`pr%$elFzM`znr~!e*(#h7+TrXVN;IT_v*B|c=;xDH zib>5D{Z=Uv)$wPYQ2*+Lx2yiqd8ymy&XdSM!@-t2a2zw_Frjx;*yp6~8g#gTfG1sQ ziUpsNcAi2+y_hGNLJ2Lg1{uxp`W3BMXf~DlX!7Hd1KV^KF8Z>Cim6cb+3I%};RwM# zU6sqtQXbUa84a-psoF2G7lS{pYfXZs?}fR)S^d7JW(nJhsvrfq7_c(PNPb1nBhpag zM{9u#boq?pw17t4k;WnA*YxQU{j4%iXy)uvx0KNk+oDQwft1PC9@CNR1n&z0JxtGa z&c^vSOf4$j(fNmBuDQhe)=4i&%uoeV@L+Y+omD8S&KD`WhHn#&A9Rl|p55pQLfaCS zTn02)c2xB(4Lma%ce9rd!jS>mM^*WkyqzdbPli`-+uKHQ;2YZdC`~ z-q@G?0-U6qAwaAr+i`KQudtXAZ=j$;(BG`h!#+@UvO$kpVK$5QRu zum|HLvykF`-qEm0nzl9DEsvNp@x4|9_Zq2?WXxx#OTsk_7zP)Ye=vNy8;ZZOUSPF_ zINp{)Q}jAD>442SxlAqQs;J{`!}*k)oBL;<>yZKoW?*GOCWDk<0Py7E)d?#;5-q~=>nF;;AjXLnXuyqh`vI@U?x%tIut z*t+mH>G`lU5G%@onD?2B4y`+zM(t6ka+&rI?Cs5eGKY@#tqYusxf`}+0^M1@}cKf8;(4J?v`+!<$`VBWqCnzPH%DP=GwG5XZ1KVus+zSfxhNPXKvd>bvXlHd-KzmB~z zO{!?y^d}4SG9OUOc_X{FhmH18Kv-?R4X&qKeH%~9H(@GkmS2SVyP*6HrTFpU{NVBI zS;Op8YAC5_1MprTng-ABC*!l%nfzC88UyZ7C&vKoxr~}wA0WN7 z7(&8W{h|T=^}O*fO(WX3pFfSpXPQ)n34Is0l>#O`#gEN^fLA(%oX;Zds~2r9DzFR* z=)W*J6+-R2YD_xjigtZ+`v+57fPt?uf19nU?DKDf3ja{sEOOEvXDt}C6p#MJ6tI* zJ^D%d-7(%S>3lhU;_sAT&YArJrRf(q{VZ-1A*UOI0m}cJz{u2hahJM*6ELdF`@5y+ z%KqJ2bis6kFa28Grp# zUw^YRuVQ-BT_%eWv<&1O1igtRS!LKVd*iK&mf^P~ZLHJTMtS8%Eu;xx`~xP%vk56sQq}oa<2&nB z;E>kYMC2<|QC+*cIwd313bp)T`%~arn}*=KE;!^N7;1g7trEW~yU2uM!~%3QGqnF= z3wGnJ^!sXp_|)T5$H8m1=>tt>Rme@|n#4`=6WVM<<5u8>I5z!5;_q%rBbvcZ`d#Dq z_yum*hyS~b0h&kI5(1oV-j;7%W`x9h{MWr95Dt+08^taNSV%lK6x8*fb*moyQuA-H37@|Jmm!*pnL1N$6z`=RIN z9dvS(HwANW^TuCOJ8Qqeq~yiK-r1$4bi&cmV%8(kVb&wqA$b(Cs(!T=F|cFM`4)Y0 z6ZM8U!#*1b~> z=1JLm8LSaN^u%I%(M4BjFZUFu>t$J`+BlBha9J^AP?c*h87MC8E>Q;~DgQse`k$fK z!ahH_??uUuB~MhC{O+kAULhC_?FFrMe}Crj3M_bkY(SDoI6Eq4iEb_3?*ZrT-*s&N}*&Z|RyYg16?1A&CusywK%y?qtGURKqLaQ=j4jsl+ z`d-uOUU&8>Hby8MnGOai+`H)p`%@5gIBc)=?C*TummX>OS}SZ+ueP$a~p zK94lO&jD4RC`Iw>19I-Sq6W{a0rtT6p*v+qg=hRCsrSAQvnD0ZkC8p!7T!xwp}_cA zhX_s`yv^0xcsP#uZZR>R3!f5HHq~0TR!a;oT4p~A#z1hmGP)?SSnRNJ8n z1Xw*;Us0)VnN)F4`N%|zj~We@{^}+j5*aN(U&JhwyqcPjClRWGbP2m+x6L^>4YfF`akrKIh!)IJkuD(WQ#E`Jf-C(43uC)ov2 z^X9aGPo)}}`^bfI`wYg6FplL28+9NJ-Ln+I5qWMl5=24^ z)}%007C)X(Loa4PLF9j zB7UaCNX|f}(|3};G7l*8Zg_y(S#vlN8t-?`-_QOcL`z4kWT@Du3?No7P{=E0VC_E` z2(e%n6s+lVWBml3WW#hQ!apu1AkL?5+1l`n53VV$G?25!EIM?0u;eUNzgBMpD&hMa zSr(WT!Y|zQF$3dRh**lV;hc4k2v@A9o*VV_kHG0&PO&0kJ4;nZ5#jkzpMlnp-AB-; zcsN8)&lGxQz>>7ov^2Z%?rt}&vSAw;b`kqAY{Hsznr9 zSi&u*&)pAp4SG%}&9Z=cgi2s)$LLoMWWoO>hZa~we~@@S8AwGPT=vRyvI0w`Je)Ue zlG;>#cOjGPztCLtJN;vrRLv}7g1EYlsvW%=)Q-#=<-Y8L{7N#*K z(9*?F7V>3#my*Gy;%)f5bH(7b2>FSa;q*XoX2RHw6d{}+dePnZ_#a8O%PnLtq^hFz z{#}d1uk!jIi554I>W5GT?k;|N&D4~dZuZBr9l?`S*%;b@3VtsFZWv}wx}gOPe_oj8 z91}V5qED#&_DMa%X8+Cu#l2BcqS%*iM58ENRAX&7t8u2@dldqKId?>9vav26+T%l1Y3re+Tf~r%0fa5CLDq=9YWXeni4Jp zCJ$7VBFT{p<8}KBqZ|j#Sa?(+Q0cESQKQG->5+~T_$hiXzMow=?r_OM=a z1vOq>^A9zc2LtwL0n%w-A0pCDy3sz^ZK}Z|y^fkvD+=5LPxtqIe-#^@&*}pG=?YFMTh?x#ElG zAUsG&f3g?*LmS9iaxFFMhBd~6P=shiqtG7B5f7O;<$UC%TMmq&?G8&|xo!36J9<&^ z`wGs7_{FWn+^~x@# zY%pewZC?s6Q#Gm7$EBcv!!(hjgSasVJ5CX82tbY+`9U~}9hv4O1;Ct*jgoc6;`Tbh zvjS}=euN&~^~u8X|1Rz7hvurT{C0Rro*Dvn=>=@`_ES1nk&@v;&Kvcy-5$pc@2%Dy`{k(d2)bNp-K%2y%zzcN>MQMs?wVwqyPfaJAz1)uF{*-fGCKF zR6$Wd#P09q|K2YeuG&qbV13dcm^q#rdW${bi*3UO!kn)rrS z-48PF*Z6W_L)HT|`mMquf$N3U-zwR@F@m@E+V9_xZ|6gXe!y=0S=;*iymWe4;N~| zTo8X;@2K^Jz86D@V7{1QjnxmVb#JOnKN8bS%SlcsIhJOtnjZ%syZlR*U!+-N>ck&y zg>U|QhlS)44%OE*jGgviWhp+XOAf=%Qv)^f zmFOpE(5&H2_`w)B3tU`fU~rc^^ID>{o8=wM<9*4_oR1I1t>12Y|E(&v-c~wafC&6n%3LXBj8?QDa6J7n z(->hpx=djTR-I#7g@2#u^2)TYkiJ<14b%c1?4Z~Sf{RMP8*#s1UD(_}6Ejn>XSV*F zjx~oRU;-Ht6Im!RP7#w(GiiLM4U%&SEeE_i`n}v!~WGNHQu6= z;^9#JlruMOzxT^efjl79XNe{qz(Bv2Qva7apVw#koB9-{0=pt!nsM-eczKqU!UkSi z-Nqir!GF?>R-Q}G1*cw0DxzGjjV|X&XS*m`(^u@W@E+e7O!7#d*)YDUP)blb@~p{b z?43!uEE$B<-l!zC@YP z!9NVt5HCn{5gL5lj=Ctr75cIkSqCPf`5QbzHsFqpFVBe!JTYIThi^nr7@d-0)0Z}m30qYi|kAq zKcMSwZhqGK66UG@kpBSAGuNz*h}T)ki=dwPS39C-7%h32e@B-@`@{*0cp|@en1s}# zrDFyJN6?yRk@Q~Sws_8~$1xw)>wOS6Fc4GXQ6jqm>qwPp zhhB}EI}WMUu(aM+5zP(rAnAQjfe7k%7eaqus5LiBnC}^Y@x7i%b;x?2N%Eg7$9*nd zxL{a_Gf0N#R|>7!-Kr|0;1A)NiJa_-u&veby<4N z^x*w5UXregtfi8aBoOiE+y4JfhqxJ>U zXTHSxu66xL+Z|_!8)LtwC|qMwx>kD zPGsvBekNyO8U%E*b&i$Bp>yPLOn)ByA228dBpMss8W8fNEQh(@GS^iI9l3S7 zbvs{u8vB5q=S-$Du>LpbX_?SY$?ceq*DTC1V|~0Mk!elZNcuGzt^MR2%Q3wg~IMllmsfd$Jll>G$-S~lT!?O779Jg!kR?_pXKKnB}>=!}i!W*n7 zV2uto!~Op{{qryizp0WH^>IuoOO~hzjmXSuZcR#542djle>ptfAV{vkz5`v=nR}C7 zUd}}>I){Iv%(P#M;)n1n2MT%-nFbovmQd-%wnAc<4f!J6M)VhyLOH=FmC-`;ZrO~* z`i-+OLH3JyrE)wYD(sgNOq+S3jz*wZ0Q^z=+~q?6t8|(~gIwjoZi$=C7=D)l_X6U| z^*1e8=!p`YNv~-U01^5FG*GOU{1R}^Y5`Ykp&udm@w#_52~zf@!Sn$TX@8WcP(#{n zs4!Wmn=c(%GVy@Uo4!<{J~iOox6_cK)`%pUmUpI0^m|=aKdQx{<{W27HTFGs1L6K0 z?uGD(@-iDye!PFZ{(zqQN*L_owxn|mQR=>-fgl-ui~q)dKy9KUgD83w^Qm|^ffDCZ zE8;e47*HwudhY`ePPU$v)iiWvrc<|i{agF}Sw(y|uRl|Eh@$g5LFQbbJ&UDohz(r! zu>Qx>nJaeR)V&q_RIipOWhnCWB7@V|8s4EA+bWh(`BMI6UA*pxIp$Bhc^m3a_F3l8 zgWU%XdWlj*3r5A5eJGu)_@BI+ewRJ#|LJ%lA4+9Liy6w%NqrPs{kN@3a>g+7>t8x? z{Z8F*ebMAple3-}SM8%tAI_bqX#|^`eoxgLd&=ZWu_#^#{6^m}e?1Hd^Cmx!P}}J6 z`L=41nvo!E(X5PCUp2O_obywX&x)e6uuvbaI7i_Z08vc_FeQ3l6s!1?<{$)vddpZ#hyl+i=T&kx{KdH? zG}Tr)X0)7Gl$psiHShJlUJlp?rT^30(ET-c-pApSn1!(i-!%{=gzX_Pa2w5L3}DM| zNIu6-OyK+3{SRHldPm%$Uf7P7!*_!5D#Yf$?UT%yjikO#KKP&Y` zpZp>~+VGMflap+`mj({1Wn?%20)19xASyIOW%pEzR5=z*s)K=?8EO|xRz}|Isksb{ zTD0lQm->n%=N~w#PhH}$H-Kh&GYuHcP0;B$TNK6Rnw>tu(rZMdSL>ouSfqk82<}~D zf#@M5TcWf+Yn%G@oA?P-Dc3PMktxq0y&}^LmwRCEiTi1)uYyp3?M={?1|z7wWo(CF z3Hefm=b8S*;AFGTHAsHJAi^F+J;n3&IyeJE0UX_*M&06nK}N{K!DBr8kvDnc zH4{{Vg>{XNA2f(ood@Ss&NwxDqz1nmYU$JMnX<-syFc~j0Jkp@3`8Q$J(|Nl2$x2% zyNvT0rk{?AyK*OVW#0a@m3Lj+yLgNC`Hqe0_ZLZH(#CIU+M&+#qcz82buh;Kn*^Ru zb6sw)m!gsgTY&%XVh*X>d|A45PZ%Xoj2`{ue)1glNUkcdJ>i5Wy*e{#zO+l=Mw;pd z<~=iYVnXvMYqL2s3!hfjq&EN#h5_rpht3A==QQ7I>)5Jd!5{LDC#9zTAJ0Djj%sDjL1r7oC=|ek@w0{)E3(1#T z_|Mqa!9p$uD8N?Y^YZ!i0T4yozrxza7IN@&bGV-)NR zyBFh+&@0X_wh_x3tzZK@xdhK%l_bYlJ<6KEEb=|RuL|mjXm-Ln<=oh@dTSTYSFQ2 zHor}Q$;um_8wy%Iep^@du8e>eQ&L8zac;e*q{_Aggc7L|9h z#=B!xKo9&Hp?h(Miy$PV(Ch%AWOY+7-EGih&(|>?319Iv2kQ z<^5ssye<2k12UqS>d)6WlATj|Md$rOF(A+#a`342JgSJJoMQQAW5q%o`+8l+o<#Vr zULWM#fzP^m#n_W8d>tNn(L`GtEz$fH@j|nMRM|e~#EJkihFhV>oW7(0f7QpV6TcMS zR@QcH*%-GjFk7+gNMG=S=tVS*UG$&(L#ujF;~>6Z@0~#QX*W zmAm77!~1jE&&&zGUK{A{s3wlNgsRq6w&DtCVMBbbP28nL0+gXO=l)B zlKykQ#GS7X%ioDW@ItrW5Px|q8q)N~Tk8-!RY!s&T*B{FtBggg57V&yF#ZUWH)fwe zaZ==k=hL#zI&x~r4~0Fj&1S|- z>H65g&LzHjX^aaKj}eJSBME%Ec+mJhL&!kLK=`D+(|JcqZlY?@iBs|x;P+v}T*!#+ zS;?&Rd_$*&`j&>3l9%F>7-kJW=4E7jEY2yjqK4H=O_KeR`yOQRO!b<=*TY<}9bi8)u6$`pe0 z)D@h~2=!Gaw|mXg7^0-T939j`SH~q{qq+89l7?lHx)g*kjUc~Am55?P{s|-=;Oz=u zH0foHy&dq%Fl&o{tsmd7BGx;^l;>{#%v-j6LS5&~6gOLL%41kKbJ`D9KJS9!hOtOY z-o*1w{m*j9rN@9(LGW5kOOC@qk=nz6v^NKT7vaaf8+gQBa_|;({O6h}$Ou#Z#wyoe z?{5jFRa1AOLXm0jDA1QzRAKb#2=)`&D>EAA$6)g>T~?R=lx>UFKOILia|ZJ$M{9BYa!JcjPFJDUvos{G zZ#HxJZLi!+dg2)}-P=grJcD81|DA{N$+Z( zMwP@pfBM#hd9rK8?`1FfH->y+Ad1DmuX>nKOGZD~gIbm;i;_Q4RVgpvw>0A$=md;M zK`ZCnAsVA+2Bc#f1dg@qmM1>a8(&4ex0{SM8Om_vI`&U#*R^YHig+=DG z~;uWJH|feb3H(w}LwZMdae;5o1czB=nI}^d-qG)7}&|+!6;Loix_E`YP0u zF}hoI*AQc;p=aI2vE=DQp1bE-EZc%aBhJC}s)PrpVx7WcU+Dbw8&AbC+Pes5G(%t*yzAAJ-{U{#?8U|~kHq%ZXch@kHjX3Of3`$4-Nq+s!`3ZswKvGbD88KqcjH^3Jk3`v@p;wvcW`v*Sepg z*&~|2O5OU22!_9EOLx+*wRSxx&Gf!OAoPu+rKC(yvXp0dE45$5E9t9V9g?}B@uXDn zf8)xaUpR?;P3fW=jzi|jOC!$v_#4nAGUeT9@44QTh~}ncnY~vum9-mvuNIm{n_fOH z?&(?F-OL-kADXocgAEKIk!Tg~M~XwfO}J|JTEe64PW%WmD?fzo3E=J)YYZ+Y;?mt5N1I${OxP9*Qg=x$sw)uh9_8M~D2O5swNu`rPEHc381X z4-eGc4Ni64{6*y3WS6BV6OA2eP#aBykZ2FNqdn+xWPAWam=b2lHDTtOHR1@V4po_0 z+VFqUZN&wyKHtgWzbHQ&sDvOR(GmBo&Z3Ge0+`NRb8i578$DD)R}2z78nI;3WPe^H zWUS05zQK}7VO2Rk;0?C%d>aJ$!#?K<>V8Iao9#G47D9I${T;R{AmUJc4J>w|R8V!%0JS}698ODFasm-ZX1t;0s9lyZ$aQu1ObC8eKCe7!H93287Ml)oAN+_$3Twh+GzRY;mfRlI=4S&-;GP? zd*$*ZT-uSQ@@DtfKvV5;!y^uvhvthh#>34bAzZhV8S4esJ_a0dbhsgZ@mhdoIOs1Z zTG0C|=1Dw2fJU9Qtds-O z|8&}~=RmGt#!y2znf(~C+W@nqz#SZhl0=_mnW4!^onqs*^ z)$yT})!LSj=&JakkgD|}c)8HB$LWvt|LyS%y}A1r18Yo^6IS@Nn;4~cY_&r5_k@Ny zV)DtS@I`Lf)D7MbCXlKs$E2H%hN23I2JrPSI=3&vTn;n z=hsK5#rl-s5yA2_KeS4lTODCL-0O~}(q@ecBJg7gj9+Rv7?bk$caDAXZ-c-{Ze0tC zax0lk8cs5Yp7C&sNRXU`Gax}%lYP>0z;s*e+nGMozZ&p9`pV7Yl?P){+;acI7uRi; zJidIH1@qyH@?mqP?iR2Wq!MtX{z{tXGo0`2uT}kE$kOEHF$B$|Of?l_nfpJ(acj|E zoK3E3C2`g1cF7E{ry?R2xf^ekpur{d^Dw!vtgT(RqGH_W*-5x_cyTT#k`fc$lXLx9 zB=!5N8;+j5rh6D7EaxamGGhjOcD!QdyDt!1Al*ip4f`XVGz@X>mFtQRWfU zamGf=qAb#J(&VQW=djiIJnTw1p;v0ikMV*0s>@WDx3=_P0nUP_q`n1aXsd44qXj?5jdFTa6gt={`-uLWsMpB?-B{KWo`H6Pl3k0U?(Jz2 z_*i7>4FyM;#_OtIu|M1S3@Kwdj3{MM6D2;Yuz2rCDVQ9$Byj>-#vX75a1ye(|8D3U zsIG>)iZp7^41NJdZGn5W(~9NADCT>Nk%UZw95?Qz!X7H@?&k9-=5pmf+ypkOw1Ga! z@tU&}-5+CkvYy~Dp90*vKDrKZmY}OOvZAO*-u8tX2Z8$0(>J70GIH5c7dVB>htNo? zkM-dfryp%#2j8(^gOL&O^3bGG1%|SP^&nBml7peDmhpSC zURVK+Rz@;`An+{rs*Jb0l?UDebKqNL$NRCXZ3)QnN5eETAZH?~>nvZ@S*AdwRt9+Z zjcePxNE7o;`Eg?_9|YMEO*Bk24+`gE-QN>^lqcqxCwgSgy{NmPkkrt{CA~M)ss}T4 zW%G?z_oBtQT%VV1oAGkElj|x~51LftbI0p_Mr3wS{n_G4<8PDgTNafM3y~kj`?hlj z0QqrsP|jzMC3cr*%}c7W%omzF+IlLMS91tuOoizavbyh5`C$gKwus3ulUsNnG%|Qi zQF=x9*C*L2Mf3&wVq=yV<9os?!$ejV;6Yl>9;d^kcb-kzc@@ulT9X{bM)##3Z9FIs zDqpZ&^}k&0acr-v`3t){Ze)dV%VvPpd)p;MHjQ3R9xmGY7W7+sJ+V|%oQkFnm*6@9HjLRJ(guT=z+UB7`c$zdOY zNz?OxgK=!upBy#P^|2OZ-82jII%m}Xu-GnR&h4QG)jfQUrd`t!98t`f(Hl2ahGOB9 zAxvn*0>Rm>`*?Qh?s>hPl?&$|MLOCN=6+az*%cCf7Fm5wr1L_$cqsCX>!`E+%&}b} z)5N>X9;(00Q2v}d0KnD({<5MDPHa`FS_UA!B9FJ=FiA?(t>0l*DdN3>AsmHtYnXgp zHJslUfz05{mW0g;aR`LW)2;5@KP|sK3I(lCb^_Ka(qhYP1>NGJlx0i9A0B*y+pJ zV^C}v*5?10G(4j+`5qHHjr{27Y~~Zmg_YJ@$JTgyv}G`AL46g~kx1)N^0X2I_h7+1 zxv1qs-OluMf3i@M8aMTA_CXhPu~%UoSThgy^&fr7^+z$kUkDXYef&iA%id@y!xa@_ zQ#zL7KX_dgUI>>#U>SBOA;jrF0EGK6CJ+x%Ze^-8l2#n%?P~$-M-9c6g-{6Zc)KDv zcx*V&=Jb1W<+!~i14HDfkx#s$m$SLC-p#PR5yN1aF>nv&PAH&TE0DXm#l6ISgz;K>MtEfKvA;4h(+>61K%-f(Zja?{;htU3>eWfdfXep(AC@S+W-WKmso)9*u82eP@fC|5a~?Iup}&3?z<4RQt>$k@=oG5n7T#an zr{vOnbcd0f?LhPwxVM7GO)1*L$gXzl*ffI9K0i2I7oiW+cL00KTMC;0P>Wk&M%fj+n7= z%<7CEE8CYyF}ZNFO-7*;;VtBSyUUZ%zWY88Y0Q0ACBK7)#s- zAgr)gHn5^ZwuKhl$axla3r4}){H)4DBIWk&IHk_e+bBmcH8BJq33B*S;bg!FtaBNJ za~Xk)K-6bVrLGylAX39R-J}5r!g|rW$6H{vWn%XX+0w92g3vm8af=Q0IOuL_VC1=n zua(3pI;%V!?9kFdk3!WfaL_`vOTy+*a7`c!zo}A586!?P=@MH@dr)O#0}yPn$MS-Z z{;gSHe`iOtlJ8SUrpXwWw#GY)%G1R?;;K?&CV5-Tq1(%opc z<$Y9F*e{p-n4qYOVbtML9#$y)#AnaiS1lXe2Y_6n;7>#;FuKH|z#^K?T(Pb8|ctX1pscJ{XIwCNeO zUg?!!AMMC+)Ndy*wlsB+c))n^R2RUDl0(KUMkRyrVt8$-!3;vCpt`@M+HLa1SQy~hr!@f}M zWU?)$^-?fD7kAay+7BMdb&BW@av_e*ELj~MLpMg>Tj+Tz;>JMKX&Ih{ndQJ;6pIjG zchr81h( zZgf6cP0~J|}y2H%5+)XwOJQIKL{b=u#YKh>BRudI#OR=d@bC;&Y%dcC9 z;vX2uQ4{;U8Lp6cCi&`+5)eq#_`txCTQXjsLzNiCLh4Xer@g34L2A>-&gyuS+4_-Z z=Bgf3AInzp+=jE<2u1Vgbao;VsycZ%Vq&t`H*I#|M+xOl>)s^BShbhWU|B_$%08To zX!_dVMjv0>E%(!tg;HA8zMyy-eFj}-&dxQ)?x^In#&|!T;9*J>#o{<%Rvh*yzwx09 zm~{;=@9#-pJ)5^3kIWtz@ahWZ%f^IAa^!3;@l>c=2PMn_0LXgs5JNADp&Iauwe@=o4Q7Ph7S50!!3m|o;2(a( zmsnEX`&@0^e@Dx24J^?X8)Mg1+y{tBSOB|b)!WOUnV0#Q!#?T{CGxtWa;6=fg9ZH@ zdGSiOhX~6s{5kNZ%d^Tn!23*81FgH@5B_w_->gUP8-*aBzI@nI*CA_Gn5sr$g!uTv zf~a%Ao_1ofVaq@`t6>S2$qi&p0ST?tr%u!)hQbusS{R$|>3D|{*a9e+wdr9NE@f&T z7xa%%t8%>tF_ij8%e^%qpZci1C_o4l9Qtp*8Z8cd zEDEzSHJS$;1k<&?hssKwF8XoD#*h8qB2}o(CUbhL&+(T0x=|PwEuf8jH@4rd-R2pN^lRJ1hl=Io6+DvEPLLp|3`-`uGAV_I>O93bN zX#R`~1k9IC`52q((>(#xPu{!>ikFYmtFc+>dlW!HxZe2}=MUi?vD6c)c(lo#aUla- z@^T8}?4elT4cCQ1!6}Rsb^W3&zilVtpq@&o(o~yigFka<-m&h`tpk3ZO00vo$w{lrXYAJ{Q8aM$mZNkBg!`2hg52F!T@=GEbgM%P=7Xf^U-1cB)1`=a+? zc#w20Dq5_iu$wfkLj*{G^=kl#44oC9l&l!7y~&%k1?m!bAbPPQ&k^AZB9Ti%^cXB) zSao{t{v_)}WNd-T&4GOYRPv7h(3B43%B8ozA+4S>q8M^#oWjZQVE!L`>G&op`u!W_ zCO`s=0HpitoC(L+6nK!d5HYDMlc&5(o|DGZw(Wn=kS3*4PHu8zWL`pdRRzjbo3sj7 z)Y98xKfjU!DLt#eNk|Cv2E0{n(Pc^}7xlJ)CDiv+!0kMkACo=j!nesr7bY@3Ykv>r{MJyR4&U6IF}~e#Ft@>hk7(G%VBC z3C=Vp9h)Ie1QUiELqNa(t(tvKnR6%956D62-WPf@%eP(Rj;x!KB z=0uKzfL>0eoA=m1r)Uthc^FI*=7=PWk+D=)(Tl9m*+k%i0;vB8gs>EzWlu`fzrPq@ zU2mZAVFI#VsXa>w(&B$)724W3#TavfL4u6l=ElP_L80eB`=BdGLgqpa-%(ztOh=~cK zpBpkKQCE7{D+)Fm@DioRKgpBkpw&WTQy^~mWhG0KJ!~a3kmg$y-H#IdQ8k)2ztDBE zdMr5l1Zy7aZ2nm|x51tKMbONf#eJkH2PBxW@`YvE%AT%fT)Aby3;w>VR~mQ+bT=j$ z|1H(9WWOhWa*daN2+9B7Y?Pq;Q);UAMa)$o>iA1f>kR$acJ(FbE}{G%W5%e6{_8JV z3>yAM200zVa!J$eI`|XrYi(La?8Cyy2i2U$;bBDb5er=fw%YFvZll|VLsQCGH~G$^ zXEVejD?{-fI$anqdXh7(zcAOJlE}t!c*EhT-ktN4W9)9v6l|;0$03#BS9C@{i}cIy z2_@eW)?Q3?7UhEYcM?6w6h@=qS>x@xwu@0_{62 zxWC>I65gl8Z}fuw%tyC%auzZ=71MP?@YQ8MerAQ$5moTW`J9F|h0+c6Je!Qjn?JL= z$N2xZORdUHwtAG1r)u_7;wncYao)nhu8D-VfYXI^3;r50*uv1Tw40*}y{Pq#vITN9 z-ZOH1#$Lbp?UO*cNqa|*?tabuU?_4pZpY7aiTqdEXmQ*k&w5GkF%=$PNLG`&2^pYo ziq%CP)NjbAU++*DWBz#Q!+Hd-H3nRu#+xwwa)FVeO(MH)3LHl9+CJ;v%}JzP=mO4^ zBYEc&y)!~Zy%XUaB~XM_2Um9i+x6=&NnypmQzJ`r9c^xwI|NE|u<}@10k0&nUuzRu z_aZkw)-|6-~^{Ud7ax!*VSE4>GJ5Zd)oR~_(>(L7%5{>wl8`4kx1%gE!B}VL)U$AVN zHIQCw7x43MnrgLT?Dz?}smc=RKjKb@KYix$fC+SEhHk%W99b=S^~1O|*;K3ZzO>5w z3_wzXEi#ft?isV#lnF(CEC&x97;NXMMJ44{Z~Z!>w-n`%8C&YU zAXKBjJc6y@6*K=~2Y&xsunuq_aOr3HTAqxYm(sG)$>4M#J}Y#i4ZkT-T9L}XcQ3u{ zjg~t{kk_tEV&*gYIJvgv;h4=m4m?zO;it*3xA(| zg~YjX#=@>3Vb}ZDA#PzK(cFa0T!V@Uguwl>OwA#wag}J%3H~WAb{wcoZl2M?F-CVZd0Oj|!1D?kl?`|wWK`J^#>$X` z_11FsD#Pn}jSNDneyn{0UnbbZPAc?OLRZw!Gl9yNISpL-hq86`oS(N$U#h+v5x-=8d$@ zRf9}P;koI6t~G=Il-HPrljgrBuftp=l_L|;!XB*rxkS48dG%(V;z#{ZcL6iI zGtK{oCOa>+Tz58$B_IQpTY!+Y2$Moz+4|aMpBQ?sh6XDxu(-noSSOgJ{FOaD{c1AH zKIpYDVRbn*bb6qgH8&?*<7Cl~FG|M=12G2mP-z`qZagfLn>bMBRsf5|I(CM+Qu?6s z8K`2RR5DMyV3cawZwkF>^Giw~1w4Xev`>fp6Ri?Sc8AtndpCV00h)ND{NdHP-K@Bb z4V1vO)HIq(*l*2X5gG`LY7qkH0(N}jpY{a`8Xj~<@`NZ&Jua_#{cKn@I7wW2?j(`$ zQ-zoL;g)`IAIMA}`4KN!cNyS#(K0>$0VI8w;B2w^bQ}Kl zE_Rc`dhdSVIWjp*130CMJ(wx6Af zO$s$v)hfpR1Nb)OWsln0D;r6eLYy$HVn)A5!2viSWag0J!J{Fga@1F7RxBmf&j{_}CuVcou(K98D z>(NEOUkRV;WO9i2@ZrG)x7Dfz(+avRS$lr&6-lHQ%9Z~=hv{}F*Nu#;V$rFG#ztYn zX+ILhBqfsQbF|JlSwrtD>G{2daXAs3t zImfcnJ^kgcdP_KU(pbj#%B4fwgdwek(fJOI^nvPO(@92K0-nulOdy4BKS(wPS65V) zx9?!9V4GA0;1!vsk?pqnV`nr)qSEYL{KerRf|sch_nQ=iUBvTmsm@nCp2#W(Yd#RD zw+9q&eXJOGARE@kL0^N%eiY5|ruMV+Qq7A{pPi@(RgKqMi?*`k*3AY|N8o^EWOB)c zh5)}svh@4WFUcC5ng|{jjcp|I7x7n#d3J@1!8f=qp`m^p*?2+V*q$QO5G8O6fe>Ii ztE-S7FE`6GnHdEqT+e&VS^i_tJL^Q7qjhiSBf0btNe%~1&^!^i$3JVZx^e)Nz#`JA zXdKc9T2x~rYP4AEH;BwcZak_{xV~XigApdVg5x=iWb(H&evGcK*B|xXJ}A|c&I!|E zQWoVh^j*l`grLX4+Ph;&M(;`WFGzZt*LAU+;(Q@i>ma)5$yUw>bFqa)VK*;Vzk7Qg zY2dS#P{~1x^DC~*IMp{Usz-GE9SAilWyDw800guWO-hwcU>dBlEGBf>XOdcSV zy1Rht)lX+Ed&{beRw1)YvD~9otY|KKpX$77InUO)7iYoX46f8xLPstT9H9+(+s|n- zA5_Vv#82om(ZlJCGgRBRK6n&Ry_aR6zy+y^$~H$PNG{D$am(bVp z5%op9#v?df6wa5z`J4FpM#f46Ln|2W%~3v6k}+!i8*Zc68h}5H9F6`C-M%_hWChXl znY#wp6S`d)T$jOvv1`a~{;~8Or@S;osMCPxAxL*7i91py8yj!Sxft9nR6rD6nS@tU zI4R}?*AXg(I~%mdE^gu6I)$4+oltPf2zfJ7Q*HJnz5G>F_-1P#RR2m8Ay8>ooff&y zQL@r?--kuX|0;cp*CNmmAHnO=?H$5sLefQSj!8%e-#A0qeLWK+aSIQ785zP`riFtS z6Q9L54fCHc+y-6Kb)5TuAMApe?2}XEHp`!_7)m?W&>9EahKm|;{Ca-rJ>Bl`aHODC!_6Z^iEc7;X2@q zq-VS2FP_!WZ9eo-;YFQ0c!e2#*6xj@gVPCFZhhE+Y8&!|Bw)xX!~%ea2|mSLEDL$5 zeg)9SSMLL4GnFzZAWYU@UJh~gicWyX%#?tiRcDE%H1$>9%3F9IEuGepzMh2E<}*I4 zCM_NLvu$%#)HM3A2s@hc*Dff->#g;04*bBYXa*-dB5VC+-z9my!~C;YqI_4^x6I6% z7bP5Ga<%~V$Hqy95AnFbmwW+9U@(5HFcP$cCbIH&y~pSs@GAynsz_MfdDhhT^G)pv zj$x9A|CclN;~u|kmNL!1-&fn9%r3w=+X{YWjG6vah5SJ_&Qy8Oq&cH-CEe;*b)2J+ z|HOLd#)yvEczQx?V#1f3zt=w_7Q1`4Xz!5kYqhwQ2@tGxp~8VkXQw;Taib;qM|jzJ z;4?&U-_ch!cslEdM}Bq z)XdH--;(g09PJyb9Rm_SQ;;{eQ$4CT?^HA3zlXcq`sD+dg--9(wb(v<%X)f@Ioh7j5AQER?J!A z+iDeu|CVXgy|DBFh>*eMmzIUubELY(;?eS=t;wbmn_tEUdq~6*x$ZIBY4nR|`erl6 zunwj*4L$lq>ACxvXWLd*lB2ambMf205d)_3ge~-M1}~A7k;6L!RP*A-KV@tlmm@PC zFN+oU{1Zzk>(4(pKoTx&*8S`|Yb%lUh0g+Bxv0vt+}J5{bk;cm+X@#s+RFb2^gph? zWX5wtg!Nn#c8*AswDUbW=Pj@33pmpLL0^*f1hKz=(s;ccvZB9HJLy%->4)Vq!N; zd7G^Z7H@JZq%9t1pryWy-pzhM^7js+w<|j^pop;_y3~~bg%pF<9_GpkEl$6GmD7(} zy6<~#3)?ne-Tn_{U;Wia^Tr$8-CYt~iW5A+9fDJ&P~05?l;W-lT3m}mOK~U-9-wHE z7Ax*;u^Q0!=KbFL58PjJa*{nevoo`^&pyvb)Zp0d87Y`B(0RdJkHAESJL%eh>@N)? zv>~L4o>W6u8c2@#*7EzbP2a?bf^wWi>r*pr&)(dfyD=Nt+dwQ_hwk`I&uz`P13ogZ zB?ZFa`)BV#MP+%^2^p;HnHzlvCN1@`1St(F#yvEh=@g5&OB_N9!@e!%uPpleKeQYs znNu>q5zp`Cr^|X}Sb!6%^;au3L}61yk+O5U{5p%4nv98c7&rcz|Cu~(7GSUFhz<#< zjW^k1DTz$slt`L~!cg&+ZT+0y^y=m)k#+aDb3ekVMHJF-M?t3nB4INJaG=0v1X1m4 ziXjIf9Y5J!*y+M00yNm;{=BRe2-N1PRD@7DlU9zE2YhLtD@g3c*0D6Wh2B7?Fj_{oQAAn1J z03V=F*TwG--O=DqEZYUZRfU{MbHbvHpMAO5BdiTTu)G3;c-D+R#yS&k>GrFJ71^@`tNnA z2gaF}B~F>{a>p8*alZSqb=PVpBuDYNc^)K&Lj#KU8AAh7jge0-Q<&C`P4qYZN?!{$ z>%lkLgK)y0fTl^leVhL)R3}_zm3^}$Dm{JpX<%x9Zy(mvm2K1T<%GkdS-@Vz30+Kp zT7JtJC%(#`S-!m!=R{Bm005S+q@1*<5E;va+*E45)*uv0aDNJCFf9z}rXfdYH{-$f z>F4UR+ZtS)IQbMMT;_qNKgoiUe4^X{A;i6fUZ6Klpi^Qn)ujB?_B!gx5P57QZ;liV zif)qF<^}z1MQXCb&>Uwd)@&H5M`w?L4-J>kxaI?!S@+&HZjs}r=dx8+?0&=Y*d=zK z;l5b>q;tIP@6)WlGFs6$s|F#$RoR!c`%}d(f+~4C2z6ho$LD_MhW&=y`kY^(1LKCm zD-rrIy&%7ra)v}7)==!+uVYJwGX*{BBXtApl(ET_{tj)5@DVH2jfFkFvK% zh_|bNJ2HvUpBriXfshU(CQcsgh3i_MqYg6rxT$_zt=%X_o*=Bl2LQ-V(c&8nUKQ1H z^rJY$TG-fS`O%}XxTcvR0g6dFglAJbiWWO{F?{o_LnG3BQ&6N14n`_!e}WII)}cn( z$(X0Lc478YF@gL`#Af+J*{w3EHZ8m-%c(o16dN)n908yUkjHVN#muqWj0!(MUZ(~{ zcCc#iRc;z4p>TkFq6wH4mz2~C`UfzVQ+S^kkWt>U+??}AnBQ;ZI{BUC@hX<|a<#rx zz#F<{26kh{sk-D5yHz6*PBatj@^!HT@v9vT0v_PoM2q#1lSRSU`o0b?Q{YQA4+nou z%{>JT)qB~p%BU3I>R%{~f;WZ|Tofk3qNd<2O@jVYHB9kU_fOV-X7}Wvv}P)1`uxV2J2~(aK%%6gH#6e4KvGVUr@PCgT8?zNP6wW+z5;oNN3tFa6 zm#{&qz8^<}zQ@-3erX;n^z*DoGefu`^73zgR;UmwN^GFlHO557gBGBGHNN2v_<49KE8~gHCTI}176Jq%*TxmOFzo2vK3il&x9R4Kv^&A#gJ{6E<%4mI94bW9sGH7orVCYV+VoEMCkvc@ zpoe1ZggBcnH#f%LKt{T0nMLW97GK<)UIJYF2`GM5Y*ieA!(0fZbqQ|lNemvyrh;j4 z!RCVH)Jaqhq8nPdFaLdc0r)PQJsK0Er_JF!i)?tN#ff23#=~?wxDA+RKyVdowKzem z>DsBjoMoqH#Grw$z6*O1CaM2%Ws}Q)f6^GM;pTxAa0ZuGsoI4VQrk))2$Mqae=#Wn zXr-!s$Z6?0vA5#oq~-S*(hif7RY(YftBK99N?P{AuUzEvYz!A$l3Qb>DG*hfyLz7U zq@qyE5{rj+9TH2*Xoavj~Th zFY58LwpS`QmWAwON=>;{9W82D7@7CW?uLV%sZ9<2&_d!Se2VEthQ}H$p1}9}(<`HN zlCCi7M5Ys|6Xdne$jr$J1|Pptb`YG@Xv_dz*d+YR`Rl54TuK};O=E)d(4xGK0Vzb) zjCnAb<{AuKw8nt24$0UqJUz;TNS`OjXIGZR)ntr!br(YU4TFnwj&$tO2a{WizA0W& zKP~1H07bnQm?$U@C&eJwjj+BA-p~G#;~KVpUd%RYs=rhwPPiDf&_sl4G>bm@%Ea5v z`3!Ha(0;l{5ZGV*sZt^iOvf3n*5Z3?4%&NZ%JVj{^nH=h=5<-a8K-{WSz;<=vNmzt zTCanCN*O&3!F`hxlzE@1d%6=a_g)7jUy8qtb!B$0X(5Q-^3=TaSc4QFnF8A#_+q3u zeGqf93(1~^Q?cBoZuUcR4Gt+=wwqPnXf$I}19x?XZaa}YZw97TYFAwqTc$uJk$ib2 zut7ihl6kQA6KbNP&C+rs%au`Zlrya>*ULNjK=aewSvQVP>nl7krhXQGmOZy5w=)pqJ(tY9KBZGal3stV{@e6=E7dg%OL{-TO2&t(Uqd z@dAVb;o&-vuJl^+(%i{W^@8W!fwcEU0!vsYQ*}N8oj$cSA&}uztJdP1D-o+<3*t{x>LQj= znLEpBx|}EMiXY~My$uaIU+0`yHqZt<2ojoz&5p+~&dZ}6(++Yhbg+{IKKgr#kxVes z8^fKSX;efhKWnJMn&rjP-zmS*ReYhZYZb;pe+0wp7au8*ljCau7|@f*#Q|xCb2DuX z>)L=8KiWu{I#7!~nja1KsGqlkn^&njjr&u%a`;UkPqA>ZR5=Ke$Q(bJa;3`%!YaA8 zS(Mn8HOV^YP#io~nGiEwDoTFRc-os_|Q|Gq&>2=-%%~7~=xUYrxx8B55 zf0jc5b|Xi+0OkU>Z3vLN7MGd`g?kVq8KW>5QuYTQB3?~gJg_AKK)G4`JTYNAc(xDoRxTfg$#JWrkN2p!O3 zD5XX~{|bKVui zvhd3(wFyDu{~MXa#xG?ewMiD) z>O04kS05~bqzB*Q;~<8I7NA$}T|lW62(Ae%X^^gS?@GVKY?Z=#)6g^J=bs2NhO-7|vj!JG(Q(QVXP0mm!sq{}s0k%t%io!M zm9Q0G?@u>fqd9F&QpCHYJq$vWiUB9R=@3dFhd{>AIKkETtOMbOmMu#P8d9KR*PWd# zcQ&`4`7e|Q#NCI|{g*n`T%D{w3~Y(zeafLd)#+_mWG;dZTjK=u`tJTTk)%*dzv>R!!(9+j1 z2)l%w5!pas!vQNBu`I$OtLejI@lVJI#Wn;qHe-Ml|76w^KisKz-3M?2t#y)$C&AWk zt_|@dY3fs)$oX_Guj8`p9G#~Fo@y@9%y)EZ7@6LWJ(F+p3d@o#^%K;v8KbtbCTEwx zmpa`y0wJ|XNEsJP^G!DiuS8kY>8~OTpYIUpNC!!bu(OnTXKW-@ng!_q{~~-c&MaX| z4RHQ(J42VOSwe2C7=@02+|T=xDT~|&`d{Gy{xTca47Li>L&kh*xecb;oB>^Jc9_$r zwA=-Q!;)U&Ke;Zff0DOv(!Ahid1DRvhCq@aK6JpDF`&hxq-m5}VNU zbi}35@i0x)`4i zeo}3~ea2q6Q*DqM`#!gMyHGB4|_Q} z5B~gbpq`J^l@WyC(qET-nMY~TL=CKzBvi$*KbEWw8tFisnJ?#);NNIt-YBr*vAMp< ztjZjTmJv6UXv@sea=h|wP16G_CoP)Hq?Am0T9AH{n= zi02k)JLS)%l<;bpwgK0>MmKgb9+j4*RQw*mY$-QP)|=Lur;pgsU}jTmi8IP%8%l9Q zkHx!N6TnGFE7aVTdbdm;lgxOyZ0~*uetkTIFfq5Yrl84a&OTF^%$|Nxu3VS9+nzf0 zRfelqPX#mHE5_Ga0LBb<=2T8IvX_zJg?bZ_;k$SyUg7$_SbGvejF;&zNIRTfmD4_b z1pG8{FvA;#&rgIy=OZ!w^M)(+BSl<%>b##+dXlL&^wL^)cYrNshTLh~%9)v!jsXBi zumwUiLl+-FZ0c!nR3a6MPN|hZEurO|QHhuwIoe^wf#1a$@i7D*Z z-|V#`^L<||fd_*5>%m!K&x&%Z7$yny7ibcTmGh;8*t?YM9Dc+b_1*uuKbbVn&|(Bj z^xYbpO(qX(oS2{COnURI429|E2QeaL&hhIuw=(y!@|>>Br?^?*Xx#l&&{u$2Wv5Cl zHK;Oxc+06F4St>WoC=rKbizro93482p2(!5C2W%{r36Q!wkAaC)@n8Qtfd%7cl@}^ zOtWL(V0UIT>@GY4l_Q&rcjaq2yaj6E`;rJEg)5+_;t8tUEp>~t#MOLB?a@In(%8W zFJYH?YOHPk@z)kq!n%#6m$aI)#<$LW*=_=N>H_%n{)_82^x{wqX>H@RyGzLQPKLy* zGwxRJ_30z<1he}K2v4LMz}==YkDaSC<9-bjVx@L*1Y8+#fBV+VLt`j^=y>s0Iml?Z zomE3yV%~kv7LIJ}@4j$6O%ob;_c>w51R#`a#zbH{J9j~6uBk_Z!ZMVo{$WS{othpLP35s{WEhT<{K2sF?yXsjd(YP&8n3_Bg z5m2pCU<=7b3QR5DzXL5WA*Y|>rhlP`aQkdYsrb0RgRnW6iV@foww@zKOeqGfY0_j> zrGL8q{QX{yJpmlFutP9t8|TY?%}Rwjsjn&qm8hv*KJcJ=bmg&Hw5Hnqvn z)qNs265!jTlkAeT+`bwmPk6jqIN*6XGsgB5@!G<4m9ULyn*Uvqpav;Yb2vZQ3Yb0k z=G!=v)W#e*>}d5V{FQI{|(!Zv^(yhl=f<&7IN=z z$Crc{fx^Gh1b_RJ%A@+7-WeaA3q4V{T%^0zh@$%c|FVkb&B69dne*U0>c#JV0&tcH z+r9bm<%#&`mY|S)Ors~5)&~g23tcVCs-L#)0x;-I$>QQe5sZy3NgV5r*c6D;)13b- z0?No8v&i}ZqJLFy0Ueem#$}S@o3onjqSW{A_zj{ek6-rOB@NOEknc@2yx55_$JL{B z-GeYrwd||uSH^3_($S>)d^L8d4nVESmcL_kyVc=U3_hOM6Efh`n5cIua9V$+Hi%BYlN%~(6NIznUM~&*-%uB;9MLvL${(ICx>(vp*;gTV-s>` zL^7_@3bE>x=1Ay(%K7Gon_a?a&x$9h8jbLq^Rx@r>6fV(z{^`ALs?%;dSPm*siRKC z;oXZi`CC}ZIRp(AOuatN#0J{Zz^eaB`jQ~;6pZpaqIadmMySNA^iibWZERKOU+gD8 zl*(SLWJh6$Z#VvS=;qrHHpMGB8Q}*IL0V8M&S!bn7%jrz>({aYH?(JdClv3p_5@e= zw2i*LX8i%A@1H-fI!?1|eMkxHPbTc!?`I&};wZezGX%xKv)K90>AXXr^y5!8yq#b; zsW&|zE}RPNPTBW#zJOU0)f3UZNlNKqG5B~!)M(2XCfX^~tCuMWi@Y34Nu9f2TswJf zzf;BO)R%3qZu{x-XX7a=o?OoZm1AW}vFMu)rbxG`xfgh&KzN3;zj^xyBY(5mA8Yf_ zS;9!xJ=uQB{EW~MSVE&nskFM&5e@uv@^AFl&G3ZhB4SvkTHKrz4QLP_87bi9Oq=M4 z(d?VZuaWbKAEiS^vRyH6OE!ROj~EK$g*H}h<`cic6sRtK;7K)I_r zd~@jcoIPC{q5zP~$M~U|ShuW@450>4=A+DIEo#j(pt9*dfTw>sUH~@}m->f6vTdDN zRjX~gajGoYY#nCh@Hs^|XE?q1Wm;T-Wn=3|xKG0^&4?5oHS$7M^d(Q0f`n044Vcxy zHnTRs#+^!Co&lH5+=V~$z+l7}B8Uoxfw}UiRC7)}Rtdy$Zc*bHL=P(l(ev{^+O+Jm zYNmT0d;dVfT1HqTdxr|#v2lV)IM>xE6}!a7cTM@lPmDQGec>mGpow9`;w!T(T=saq z;r6QK{Vyg06KujXZp}YCY{ndS3f@IlT;i*d{Swr|Cfp_yK=<_byJbY>`!R)b`V!-L zT;r{*rh-gAVtuf<_HGk77#8n=?}>$Ru$GF36(~W-4wg9?(%g$>0GD9y+8j?(EELPx zon1x{y4Pxg$dwH@Mvx`1{3cJo?!9|GNHU~{Oj-UFQou>xUY3=~z}YKNq(CN*JSpN% zss%Dy+_etc5$#CXb)AeM2!DZRP=vqZ2NtWJE4gZI+l!wxt&N~b`eaWhFxSC-a z6*$MQvEL1ppRAZ4H|g%9pF5ani)>PBvS#~VmT!sEBV8MqMG5y*3h^IdY;!1aPrRee zz*a;#WXh}0Qd9d&>^vPXFg((v(i*A_rMDpB`cO+vfK-x|7G5%7>y!HklrdKfw;I@( z0u+l)rb4uZ{$pS48A}{9vZ1hI_`Au=R=6cHN@Ecgh?Ls2XdYXNgyeV}qtI{8j83;0 z<+!R4&;L7N{=MYji7iq=V1B^KbQ$@Of?vT?#Uj(XOdGALh^bS)&Wh-1N!s42H0a5z z2BVMrRhS?JJZd|ixls3b0+<<%GMz9+jJf7{*ffSTQ>|CG)vj;qYnB;g00 zM6l@~@ryJ;VUSO#+PNXJH3nL5tRYLyfP4SpLw`qxZ^?0;`YvMO)Y%c^7&-NV089R% z>*mw1juZag?tTJ2I!01P^OiWPRuL?&Qh!&c{i)#es2#NR4~3f;*_~1xT}waVMemF> zLU}5I>7;cu3HSF!W8-?#;HO0gXawNdbezAu=Z+7xf~$F!XjN@|@v9Jv7x=ghqkFytA71p&kBQ^#{7g~o z{Zm&Rz_tlAGunGlm@2%aNVIjy?-`t3oqQm23%yj~Et;OHictHGFd@fvXgtLYPuZc- zV$6Ku>$RJ_sfS0B$@-v=1{*;idjAQbwo1tdGEH`4?{> z4p`qD3x~R(ry%G{wOffmmb4@vAVss1h*e?@#Q|q)h>kmZe^oct(q+N#?oN4vUu5Ri8Cn#TVr%hh_0pob zil$SY?q&~CPD8a2(WfpeY$N1sv&){>r){{DeJ&Z4^3O&3pXo7Q_T+w&KCvBL6n0B# z&ZA(-ma9nna!CEyJ@4WNh)h`vpJ~o>3Cg+$jBAr^NwqDL`SeZGM3WJyS-zO@;P{`u zbyP56@oW`!Og^<9CZJ^IJr1SAVod2y33xrM4oOjR8-; ztsA$CTB4u4D0keR0o=?DW5m1h`3GdiJ;J6yi(~ATYJ*! z+TXNO_qK$j+O1_+GR9r^nQNXptLFS6r8Xm-Oe;05P$_kN0N{#XtULBlnSa)C}t52*g&1ai~)!v5T=NU39No zmZK>%q?dIO+3Mvk-7Dn^FOZ3H!)`TW%X-V4>QL$SrO`|=5ZFgf5p0%Ql)wNw3y2BH zXu7#>MW^jQcHVzXA?txN&kNp#@|GXt6W~sPps&`$G1{xqA3x%jD79cbn7}83 zdGOoFb**Ja`o+GiOyx;e#Ek_t1{al+=ocBg!9G}4q2hu+?USAM(n1Q!{OF~gy8s#6 z9Or^nWL8Be4!kyY8`Naudly@#y8hms1&?8~*cRPwXg7a)X{NKYKt+3}VNttq$ISQ& zCqfQqn$FA3|FJR`ZzfT*I90Mb6r5b2!I(7#b2tw&nMS-%0+~`iC$AIS;|rG_V{eby zU`UZg;aB#MiJ-H1!#lG@4IWwGg-kJ`5X?DcFQ|ZnP2d5B&FUKc0Y>wLk&Mxi?zrVB74e>-RlcZk82 zhtP>lgO6TEy%_3)964G1yeje&Q6fo@s0+*(0H>XFgiwoQQp>{NRp+A7&_1 z^-%p#QYz|?E|NNI!bg1BOXI9pB`tnYGVEh7;(`MC@fZZ!7W0b7Q5$+eOSWNsOxm7% zFq*B$8dW>eJ0@?>ru#f{Vl?9)^Nu%UeEB1LjCr5=2XLZvDa!(|IWOz#AbIEBl;W|~ zF4M>Rc+MVZ0C$?AI3;wB2sksU=HczRenGlAH2U~0k@xw-75%={mO`-f z0yI7~_GxEn3z{Axyiavz6lmpKrC%pyX3@N}Zl3XB#@f81yGZJ@HiIgaFsWKLa`+bf z7w={R7;ZwLpLB+2j1ZvM2NVooPel zg>#)4nen;6qYsSxZS;c;m*LLJSO15}R^T3Xf59erRV&1%33a3TQ9}QL+vvmqq}!qW zoCRxeZO(RWru#)AzkKUgXY$tBKvjjoL~)LhW(c#;u4I`XOt&>8%y(xh5RV@Vazght z=ix+dkk}99HFDHE6$;Y|qF-b?{ouOLk%RQ#eD%{6C3)16>p?e#K4yAhv6oNc z+drbRCCh^%ekxEk+fztgD(c$A2-ljgb2r4BtLklRR!*fhCnXG&sVqX@XM##4BIurD z$ZtGJw$4InX8yuEy?JeKK2*jCdYJ;Oq@AhHJU?*r1>}V&ky)Ik>p2(e&{%4=q#g2< zI0{F+O59tt98tn2v*}F!(G(e#Lh0G?G?iGd8MZWrDeGtOtyloO!b2PfW4hR4yCg(| zog0~&8y0DyO;v?vKVF7r>6vV42x@;AaVCADo{$5?U6#Zz%X-%J^Pz>aTkW#WXU2km zQF?bj!2chh#UUcO24(;%xEdpumYYKKf1V9gS}1qUl?!N-8Tkj`lOCg1uj|F0))1cO z?G38Ok56?d)6_S59BNNjH3-zYwx|K!^bY6$Zr`vQ&)>^sl=cWlZobTt3MEP-;lJ#dy3|jGG}}3OkO$}3zG?;||K0`*qev-cq(hjpAY@z$SW#4Klz-K1 zYwy~8gLlFnNw%dfnZK7@sX5mp!Q*0GS!o_-QK_y?>mp~`o69Y9{eSl#Zw{K;a$0@N zA)kX<4C6MQ7WdTguKPOoj=3Yp7JAF^{`fNkxpSV!dRvWg8H~vcepnNh%$5kCU{tWCC6z z59w|;jb!4*rPSnmSbK6P43?*45y?Pa|Ak#C z`|nH245_Hv@RSq^E|ZT_s7);C0O}c}Zks1A z+69m^Er)SQ@ z=05{Cm<`t6^T#{_{>_rl@N(x-&8{!zDlE`M(Hi1*Z1mTuHyt_SO%MU7vJ^FJ^`qv) zeTts|mC?H9Smv4lHby$anHeq=9k+z$%?LWnBV6~%bXGaW(=A82zg*+FE+H!sku#_4 zx=C%i7b}L#d>$9b61(HMi38jzb&e6-3r4P6Ew0SudopunqKoz* znV*|r5ikTb*%J%lwn$DG_ckQiTiXC&U>Y6YvwZF(OSK%-CFjzeKa?q_PHRXzMSwf3 zv7MNsxPoD@lIbhHs@4)@xOt#14Czah%u-mP`VVkgDB0KW2$*hj<;~=Iq|ucI9VZC@ zUXYoNut(M?B$Im~e1mNi{?3D7hr*9^g1XAHbk!6!NN&{Y4v?B7OgGX?e7p@hXbU;YOT>Mq52y+20Zf#q1bZ9Gs9jcV^6P|*HwQDSbOs(FgiD5z;$G^Fu zz`dxE$%2UhzfZ2ywkk754JoAZtr6b@*W_C4D=kzA_r%GqVVieM8Z{jwIM8ABiT6$Y*HNkGHU>#hH}DC*5Jjg?bS<#5#?niLPH z7NFZ?kB3tC;l;9Qo6G0TPOSRtnv#c4DBR7PQ`%FaX&=x7F$SD*LY73A-p z6(n=gV$BF>&Rb)JslLDSl%O}`Y_9r(UpqG^MxyYO|K%-Lxg=9WVu+4#W(;PLNWGGu z)R(|KW!Nu!GVI1bV?em04JKkPj$>4)m8}k4$S+Xl{(HBIDJm`ZclEhb%pD$&P|Kcw zL%OUfcM;m4#q`^rYB!3uKH_fm(?T)Yg+MdDi|341N;@$%=}1wPb+XF7Rz{700kxo)cQy$ zQogBP9u*LFi=xu@XIM72L}0fE(N6u5N(Z4$e5 zpN5eNAPbECTP?`~=u#}|ZI(h}jV>b?rsmgLguDuq+m6g7x)dCfqms+$t<;cqnuUff5pCaOw%DrQvsJC&Kao zZZUJy`VGvAS9eQ9ur7OAZ*6Fsv+5{e#}2;`DXr7*uPKm0a~FO{+Lq)pyi>(ZjcY4A z3&+%$!~dF;+E_y#NX&;Pldj=&!%f%zezp?_P|P$;8p6E*Sn8g#N0`tSxCvL7p5$3g z+>PZ4C?ljYu!n^1iN_p#VJLwP7AvPJsXS;IuqUXekQKrVtA%nOkqR^)n0&67EiC?e z?B$PjJ5f2bMMzw$M~NjHz@|B<>^Gg2c@ANBA3cGjsy+Y+R!40ML%Dk=_0^BpIo{d! z1S2KuFErGmNdxMQsdVh=2zES?pJbY@lGc$mJpE^L_xu%;AL&A#U8RDU7Q`6$f1iDQ z5dOlvZ=cG2^roN2$hFkvG5m)rONm1X{<-E(CqkIgb|7w@C)&Aqpi}3oGe1#&DSjKw z=pP`o){5$#mCF3Xiq|s}{5&_!dSsiQdXSh{B`ik=PA$;bz!c+LN{;Z`oR&TM4Fc0$n0rVq?Lt*xq6b5`p9(R!LR?g zv_6?bjQa>1s^U!A1@CoZEOP0Hy=>g^?bVhA!!2Zbi+PDCmH4KPeri9LYsNUHH+n%Z z5b2?oKIj-eG^hBmp!^>|9m&1ZOTi&4{3M~YJ%axsq{i))cwDV{=2WD^9~>C_EV-e+ zsIoJyEI?2wp=`%cl9Pbb0tNZ8Cev#*|G4;4A=RN+%W@NKxYvb2N}Fu;OTDk`&cU;@ z`DJ#AhsCx6`hjO%^q7DUOCQ~A;N+5ff3?y&d+sa=;O7YMlo*5gAMUDsHdFm_pVTmqDr!h!tbZ9!cx z1HBGEXEk#4E0O9qhinOgg;=cGcbtNMz=Ar@cz<*4oe;8bN%4Xa-T*50IKe5m9)oBg z)<3{!%c|}07f`qBkFbvQ3)4l?P~{Cv;Jdi>asFwoBz_gFW}O7Y6OeoMjq-jmGElT7!&qE{cTB3WX^&OO;=xr`CjHo=sj)et&eVwAdaT{&qp7 zL^`rM8qgl>HKKLIC)>|=y_5}QqV4$p?5;DzZWBs5g-G@MNagwrmp=)5Vlr}RyGexW zti^KANt_yL#M8q^MDM%S@QrFG4i-Xr}*t|;e7q{Bf3Lseo-u=9pndW z{{S%`Y?^?o#j}mrEr-J*2zG{N!)y$F@&QBlzLT6?LigS z$Mvu9s-Kh9&Ur4vb^;jjC0jjzuyu`P#JnJCl^+wpASgBzw@WihONw@2VT7Ov4mut*(3_H47*pf!Vte8q`B;0tp{uQgYn%sP2-0d8M+;SZDi zHmK^)U%9-e%cpg{2>`)J@V1M4?0Nx2$G86zNkh$i)d|%fo<_b!muj+xSi$KNrmfZ= zkydBX+-B#@=cof)D5b%$k#VzTe_7s*qmClvov0{;cK)+ z-5AXL?dDTC7=TM#diq-RO^?-LG1bMoYzh^hS4c6D$W|U1y$pd4>VYmyXeuO7B%ur? z9auJ?5l%Du2H!yBqUvaVEQif_5RoKa-o=-UHB!rLFGq=i3UFRED#^rACieBo1cYEe zVmQY}i1WlG9L(5u1^Vg>i!&*&p!Swrkh;Iet4q_GOx4&6njh{G;jbKvDMAK6PQsAWdV#BkeA{ zqa?q70450c@{xQwb-^p?s&y@aTf-(KP*{9sLISkL%zS`Oe53y3A|#<&Dlk}5onD7x zraf3|ui)*XN(o+|&SD6500vR~_sw#8itr#??3!&a$SYqt&-1+2ytd89w}2W`9Fj%{ z`qU2OOQlu-KRv#z`rUXu|IYk-(=4MuOAF4nM=U9$GnGM(OVSps@4u~_ov&Z*YSy@a z6ICHncptaoL6{b47t6EdRVW(zTJ^y~G1vZ-VzwO9gEUcJ^}frLJs9%*&#*>iuM7)L zvt8i9y?JaBsRz<)bNQiHt}>6Mf%Nf=h7lF^gpI1Lij&!^Edx@Ct1L;j=oQPP8T(_| z!+ERZ8)QkY$bmYmRh4BkBlYqI2)B@5YGpL_@wTD3%hb5rpYPM&_H(~9+KGx^zh!Pe z&Q?YLQLTa>Ig~-0*!A^n#@x}1jZ$Vb3hVYDjXi__Rpz`v@26Uy1%UJnWl9?;HRyHJ z_PDE@=vRFnU=L*P?M(MWU8Aug-q7Qmkv<7=Up3U2c9U2afQ95fzSb}z%o6CzNE6eW zvsxny+EgLXwE-{fY_!!7Gge=p=as?G36<(?y4rOq&p)kbM~|)e#wirBf10bO>l!c3 zE&EAy{o4MdVn+9;`d?={^c$}NT&73t&}x-i?#=TRQ!BK=n;~twj_BElpWvv~?=wTz zeTmZEE{%2gUVS1dX@vJ7mOx6;D(Kt&mnh{_^$u z)$jRW&uPaHT95HdLQb;)j{-C#aA{4{4i3#sBGj+&Y0j&^ED;*Z=(hwJ?8=5AHDSzs z#OJ{BNO4Ec?a@(l$?;oB?u>Xr)SCoPcINT;|s4^6Ronm`Eub`lhJQx;&mwWyLB+8 zOwBy90^=8pF{97)8m6{+zNThDmBOPVvU&aiCPrTvRLW95C=yxs5AZ_n?XuByL6yGV z)V%Nd=-MNrR<3{%#az=(mUNQajDF^xUIvDr-*D$OI@1P+gHwDB0=*6;}E3(X=@liSk~0I zk6I_1?sd9qctYMUrDcoSaVc{Ts>}PjWEa*9HOs#F-$84AlV5vVkQ2jbvS4w;kzalarReM@+!TOe8Z@fd4h#YI$t*^MXhH}9A8GS3*I2gzwkwG%4x+k!E%F!>57?7D+K~>EeowJ^f@h=q z%_H>xj*s*Fw67Gm3Iwp$H}l(nElI|~a3nu*D6Lo;`(Gx8XMsEx8th6&6S}?W1 z1)astSg`manM$n_q;BBq{ZRU#17h~0xLT4Hx!?a<(5hTBuKAF8JBmw{<6eqj#$)~5 zNtO9za=tv$riSQ_T&3T5Q2Rhh`!5EEb;DQso!oImjq$%;(<0O;cHI5Vj4Pu`Co|&y zyX@1G7nE#DpN@PbgdN21!?T%G$+W)IjKxl5(}gTkd{T?6j=>`*U^#DCIH4URMI=p% z@5jEE(_pNnV&HT~A~Xx&!$OxD?>>f<4Xehh(-{3ruJ*tj{;9RsVmb=}SQDSc$ zWwR0+X_Vp69r=nPVvNLg1)$Bp7WW|g@53nJ%)SazB*kpt&svp>y(uY`DSZtsRm`p_ z)X9+ZBVSCSa*a*A0j3rUOqMmKo77KXG`Tcm#O}Wu>Q6bcr)C^>{Bc8e=L{Js^fzb3 z`MdWWj)3l}{UnUQ&=)ajaQEY_#YX5qz=frh4^7sqQT$3o_4DswY0o9d^NAmrYQqm< zuNv^z9E>1z2sAi1_IB;B%HQ$AP(qz^7aq?&)VoMv_TTZ?`q)|hd8|JNDnIp*QAGK3 zjk2*v7gZAds(nxK?1VhB9FrKIDqWF!9~!%);DB*z7s@I>1WW=a5}Jy3aOC*t!iWu< z1$UPv;;`5yxEvG`)!?i5{F|>h1=%Af7kyZl@Fcn+Bk^MgX>Zcqr-%P|LV0lU|QuU0?x9+Wci81_8ZpkdigNX2gZQFMt)pC(53(ZDgZLH0kIWR+a z;K7T8;xG@+fHR%TAu-)Vlh3glq2jYN_!h&%!|YF&?gXN#%@`KYk@4C0fOd?FSaZDS z8)|nP{kEF@bepNFZ1WySAiv!d!wC%pg|ofd*m^Zq4j^CB#;)KctS?HfvmddqPlokW zWEi!_w(0eL(xa7|P#LQ8Eay@>=x`Gkz4@h~8S7m@ZN4>KQ|49$5wSEmq4|i^e{wF} zpoOdL?-GPE&Y0av+?=oZeR7s%W!J@cKu22d6C|7{f{-U*eX|Jh-g~v{f3T||l-Z#s zATho@d}8&>S>VyGC)}ktifNI#M)r;NA+REE^T<0)tQqS?>zllQ>(xH7lfl8EXX=@j zI&DjlCi*5T)A;@GIn0BcRHgV>(*ER0?7rKub@=TB+fB4US4 zjYqBlaA#~!raFx@K=3X^nl{-lKq#*(Rhe)fx$GnX`B8h4Tax!#qprQGv17Rt0q(p2;=QDG@!Km z`1;3eVA-eGAHT0PO{!9B0mn=@QalB0lx~J}8sz4M*VWB(GDg#^)yMit)do$BHsaHQ zqOj<|1XE|jknz)hfa;co-k#K%F-?!w@;%I$GvY4EY1bdh%D?BS_FqzqeVSE`=7PeSlNlC#hDI#)sS39IZV_J-0ttXCvC@NRc1>`~UFv z7Ep0S+1h9m+&#gyaVNODySo$It#NnvKnMhPcMI+WcMGn;-Cxh0nLGErHSb?{uKcT3 zoi6L@TGdDP*?WKAXCtbo;kazWDobtcf!7@-RTPQZ*Eh$BE{{rm$dx9F?}=?^MYnPl z8QYzD*YWxJd>;dX^NObvd2{Xpm`}_N?ljPDZ{q#!@XssO{JdYB&Qgc=8$qr=@Az`j z(%WTcbi~NJ*NcUQINt#(y{3M-O!o_zkH?a<*xQm6XwrET8$d^4WSBxJ1N%8veQd*V;~$l#qV8( z+70;9a(LzN#>m}DzrUb?t5Io8(NQNDiL78(5G-3+E&9p^L^x+1F>s@D!$PWm2p0rCt}YYls3w zZy490_j;+>%0a!}KcMImx%YhswOY|ODD#i3>xG_Zp)d}Y(v7EvXhB>dJHv}ClRHti zCa)(E$==(txL)Ln3wA$+M2!>xHkWX5C*Q~)w;DD43RofgSiMhGlP$P|yMF<<^QN3X zM7$H5?|b_#e$qdVf2QSSp&BK9W09s!h*f#;)>xy@+`*skXOQ}h;Zw~H>qx?2g#%i* zmtGfkE?m;i3Bj>-XB}Gi2{pYT+B34qEhXtL99xK!1|DVLZyt8&9#sW4#nHrsnYs%K zA?u`zU+{5CPd!47?3drgRKoGtNU9Wr#U{*pV3{;E_Q*7C5ia0K;E3Jp`lp*S5mO|G z``R7Zss`uJD5fsvk8Oj5pV}=?QVLi3LuU^yvs>wWD?@V^WETRrj-TAp_8Wu{hNUn7 z&IRni!12Ouh{-cBnv@MwwpWvTu`H;;e60UKQszUeS7)t7MO zC~R0VwGB(-D;L7AoK4)V+;YZLH+Bwzkw!NfIMd(6qJmc+H6Glbqqajp&1MXm90D;(#RsxxESN#n+tQ2-uVun2xCbsY?@ z^ON;4R2)Ah-F)U`^CGjNR3VXE)WkmDO+;^_;yh3`@p?vw1xG%>aa-YnFErmD*elF> zJfk*0YN~T70ZSTgNuu_voCe6_Ju0hN22qbf068^JtAL*5<}Y1_sEV1MVOp*cXBiTX zppRCS-Z>s@_ zAxAUF=Jg4XmJ_E!poP0SnG9T9b)d2f5v52`RUAXL-72$;&B(G{Z5%m!ts(rf7rvaQ z*1@i4lOlNynP_P``J;{DJ0M1`WwEI0JcAJf7a>wpkDdK3(j5b9;U^Wvnk_+laK&C{ z=JY#2&up+$TX1vz|Jz`Hb6{qi(le+6Zf&k4AFQ|~d^|p}JB+ddc&AY_!c&2)GA|#i zP78vlNueIaRLIb;$A!n#Yi}?#rDplipi9l98plYJCAvh!OclVIC*jjc2Zc{)YTtH+ z6cRULcA2YTg6Og(>6b8*EOGPiIdu=`rKCvK5E`3XvrQf7EZe~px$A4irICj9)tKXwSGEEVRP*+}FAhbC~ z2S9Vu-nbF6>%9p+h@!yK0|9 zqf_k6;puCmc2CCnrW8ciO(b#Cswh8Lnq;I>;0>XJT_NK^oztbeaMx@R?NCR?74sdG zCg+as3gYwwlx;P>$*nTG8_Mz~@T1Wcyl+iKP2){RpW)W_4e0cW*nhdrBI&-SvD=2J z5{|beZRggv#Mvd1i;WRum#puEG8FP!#X0Lp7B#P~j5$iXJ=Az#TmJU_vUB}=C*HM6 zkiERG@S%5MUkiOrKuUuwwy!S_X$LVr21__xH0U#*TZ#XJ`+f9i(mR09axNWB@DlY8 zX!)RZj~hd%GFWtT%=xBCjx-3Xd%a5v>x=fZevQ79Y)!)=`Y=;jJ`Iv)Vo_o^E+Dz3 zQcp@mgf-_EE`^r*R8z*3%DU{=+gNqFbXz?&f^^RxQY&#c?!_E?*x#U@+|E+FHf7S( znx(tU%NnJtKN;CJywuH~dA{^lBm8^^_<9%Q1a&aKA&g^Z2y$uu#joBu+xCK?*@nUG zvH8)AOYo$)OFG1g1o$IPrvG==?Iz|Mq`@b4=hShd)u925ip_>#elG(S6=(AbOvW)w zI8dnGAZ4^Mw`BzTh~@`KHynT*U7zCqn6A?!_EM>R>_0r!>4S0Q7?e-vX_93C$hYR_>ibG^JlhJ%ybtv25y zXY;ADRZDk5APJ31T3g6zZlJ~5RE|GD?v%_phHQN-j1aGnADIF}gO3NHMF@Z@WH&+F z1uAjj!8B{)!aNgcyL66hRML0k3Na-gigDcDegw-bU%1b(do;>oiWsL$>jQ&TM%cor zW`E#PD^M*x@~}edj+(2&(5^~kq$|`H6-|8Maf@lO&h~A!x=e6{#@)>^aXlOhqV7xW z2(cGGl(yDx9OE)FjUqugyOPRog7lEl@GtDn*~lxev(Li?b$>9!8S@<&pjO91G_mDaRvK3h`o2 zlx&=Zr%F6|sVKn6wz)YVR$b=iVJU;oyaowO2(6}@*q^Qa!TjV*G+Ped22-3%skV!a1$AXhhPH1i@T&U1O8MXK6*E(w*Qb5k(Z64q^6DzdHEN zEHJhgoTA{;GqjDp_4^OeKc3_g(_8j)i1LQKcB*zZJ1MJIB>pi4{n-J8(6;m;77EfO zI7>(%HMI8;yB=|_9}P`jQZH`^;|NJvTz?$G6)=JrppcbluvfU{pIt)qL!+60xSs)6 zj*}UHQ12zuss``&1D1vqk&re(zopr#N)ENLS%|NbNO2#pffXK@h$iMrK!DaiNAatC z7(g!SO_?8=Nev0T!iAqs!^|8t zMecB~v*9G_F708_YX}oB#2eV1Ii$~Fl2TRKGoZT3a~hBr1u5qR(+IKMzhm1OwyRj0e-3TE&jM6{;lxu;>feOW zn9P%1_ohCc`{Iq5S-1CbN$zUT;T0iHs1)n!gq87gdB6`=X|TMt#ngSfevF&>(=&b? zyT?yNd>2g#a=Xvpon$n`DXdo$PqQVD@!6~BoUac(VNF5{d{geOyp%h2^g7UWS4T=@ zuoBEn{R|AyTs9#e;p0b z7HJ;Uwp|5Z#~zk1JJ8D(lt1P`uN=Pvw5qSpA8lUR-@wjm#&e0IN=Vl`q)DOV*u@ z%wdlYiTqKuzL;*LbGWp0fo#9nyhI40po(_I!cRfH2w5Y7OA}UPt35Zfqg5g`QYJ6x z@k75xWj_~`WDFbnw0gPyG9s`^MB}dY%?ei#qCMoM2@y9M2so+**8Bu zx3lzTXd>moHdcr`n+pHV@@`-?Ov{Ud!BN-VkP@%%wserK2^2N?BMqf?l54w&(jq0? z0ixiK87sU2DGp6ecS$`U9_V(J-m@Dj$-k7%uGfREE%z;CuBq1w?#P{+-6P`5P_Mi= z-8%XG&^W0JcY?VX=&F7>X3hnTkeL!%G!Gy{EtpS7A^ zs^yGso6Sm7=nS11^pEzo89DW>+LJgzabmT`v#2+-Tf0$G()3Q^C9HcT3~FZ|Z+)K+ zaD&n%7UaEE<{vM4?^bxV zoDYsZ7wt|G2a=a6e6|l8aPwQz4}6*_BDmy?ZfJ@S>jtG1UIi(AC;kk0D+$I9aQQ_x0+Kvt7dSBVp1?TzMrnIYl&~)_p!m@XT8(o`Syk(yxr{! zOL|d%)7cA#dbwpk`fp%sPcrf~Hp`?_E=6<(Kuj zdM=BP$cI8TsY;Oa9~o#!ul&Ku`I5KN3-H1U)Jtb7&A3F`PBKW79M0>@%r5}1Q_99d^9J(D~ee>uCwkg0dZmZFb6YfYIW z3!^oEx|S_M?!zlPc6Doez)ZE66KA4M>1e<>O!rATq|wV^T+pflgMUhPrDp{2E|r!T z60$X3{giTP;johHSJqbLL(0EdpxiB4Rtk$?(b^P2q;hDuQ@d;)sVu?G>;@LbMI5e+tx_M;NhQu*BB4QU|GUA>k>M?Q zav~EtDvck*$_%EQ@72|p^3aQS*d8m1advkjx^NWN8CKO4trkVO+;+CYRGcS&fx12# zjeJy@-lN8RXd&Y8aexB*d0vR9xo62>aPvo%gQoi-ZYc6G&X<_f6+RQjHVd7YYKF@< zfRpaC=3?^@L16}(c@m`qg9a=sZPuWsQqncHyZQD*?>@#6JaF3AEe9u2()`{DMdSCf z-By%auO5aXPq$n)ut)?_M+}H|x`&h3wyjuOpDnG@ISM6cX}dEl^26nHq^y4fRZLc~ zTa~sRZ9K)v{`w%896CD)IP(9eK)?kio+?3o$R&|7 zY8EZ(RHmE9_~!+!QzSV@8AK@)d!F1^pyhusB_DE99X{Ha66Dsk?cEJ^`2NiWxI?`- z79Y?~v@WuzO@M7?1VW#(3E?Xon5~mZ6_up7#no~P5}@0?8R#ZPLGk=<8v7}lg$tm0 zVqZv%qIxi!Vk|g)#I3OO4uIDjoQ&O!HNeUV9=ul(98GJIy+@EOZZ@Upj_JWk2z-DR z=K4+*cgNcMJ)ovx3h}h#yBN_c+udi}#`Tj_OmSPP_&+v5$b9%3r(b}XpeDxST{ky37Vz)@$D6Bi=4nsiptgh6$Aw9qaADY=IhJ3$)r zQg8HN@Lu8MLNE$c5P?HnGyUM+-Sa@Vt4ESy6Uq18RW195twUuW(}ABTx^~x}s~A_B z+-S6~Cf@t`KfWXKXqIm5+p*V^ll13>rsqT4t9WYI+bhjQru)L3+@6PVq$Ci+)85-H z_?n|uiOnE^+VZ}=(T)ID3SZ}UfR}O-dY|uaT+XrW@JdBAo4D?`pMv%Yn?cNKQHFtz zzY7%(D$M^JTu~BZE$w@YE-s|HP{w4#31AX!X(Yl;x!u;DQURa)^oX+>>Pg@7|E@?ziNt4l%=cNTX{$Uq}qxx824-N_tkv%wGFwp+;4#S&usPN8SFW7ySdC4u$-_DPMx zxPBeW`4sZFE-sM1=&qcgSFR&e<{elHShcB@!X;_2mEXl7CmgopfDC_%hj_CSvua!T zf{Z|3D4M{j8d`}N_UGsGDp?q@AzZQtn{6$QXdw{aI{&0OC@X@Rgfa#HR;#I zryZBB-qTOgrq@GYeD~EH2A0p|04;e++9%rH7AhKvf1_xLi%kXNNxXb7ZIyV0VCqYI z7hV0E(mgN#eZPART$KjMP;&%X-t zQwv?&8Swki&Ht+l?S@6P7S2SHgpV-b#q^s=_!Fr0FEhFgw^$C=qiXGcbt%_9iO64Y zc0_;O5~TTUv&@m)GCY66{y(#@FN`$J9OF#cnEa0Iuzfz2SeX!=rY^}Ui0FgXB0#gg z!THle6e5T}o)Kq2$qkz~Z$~apOB94mX;g#!)+)feVUo%W3il)0RzGScLV6!j>oTz5mDR}6sGu^2i~E<=1t2^NG@4KWod-U z#~auY>)CCeYb65!P#_#w0H|9H^N&>aJb%=}NB1UuR6>2RxUTg`8phDlZ87V&`Wb=v>(T1{rTAaBrWy>G=E#<2Z<GB8lnIpPC~8McTou-ixHwmpwW z29Qh}*?b9YgTE;vxY#0$7J)p!DjH$Ll9%&_&v>#!n}hMATi|`2?)l{{2omxyR(`?= z43<-&>lPM>BURsJH_HSh2nqd;yt=i7Z0lEuROz672b?9vxHn9H5A9b91?BwMRh#-2 zBH9BKfw(5Z=iCt>Y1qH8d)ZUVBs7*Y)(?%9hk`zLENy zCe~W-!Mk%fx?(B?QVe8~HV&rTo$_Vg|LHx@;_t`Pq=8C*Wa8H@>Y94OEYx3bSy|&C zZ5Ads-)L3PPtseCv1I4{W5|RIVxS=8UXn^!kQ7n)yFL|ET42Zdi8aP<*zO79 zvhq>k#BvM%(5+f6ty4wkR@!Es;-7Ekx+hsN^VkEXxszb8@{&6(-@pMgQ7V_kHlN&k z*1X7!s!EWCxQ@i!6Z5HVj7!K+)ov1}iH3d(w-Mk4LAb))YOo15mb>VT=C#!|w zeDQ+LEIbmU(W3G2J~wFaVvky$%CWiQeoYT$VOCfx*lt%r7h&GZnR* zsx-sp!yokpfr%a7i_CsrngL_?#qm~{@{FM)Gx?MiLFAJ^`k0Yb+u;mDY7-v@7|NUj z5V&}}K+o*+jW5Z><%3H8Y)NWOV9 zp=wvlQ6D_*K~w3*LgpTr)i)l{!FMF61c(@o41ewyu*^Z*f~hTMpY?5^K@Hskv{!ev z7WT=9P9x0=GAUN*k%|y##}Ajqq_i{rGM)qzRt-!n_E3y z4H6*qUjuVAB_x4vAr|DF6WTzZDr_6(KCxCrD{JFqw^3VwF?XC?r6g0 z715HFc+)G0jx!JRoS9%?wCR!#Sah7Vz77ULvQBlyR+CGAAI8^euuy(-<(3fazOi+N zd%|{On1kP#DyfohNu&&H=7KKSuq#yC!B`B5AD6jj-MLz+7d+s%VoM*uJ|jU9no5na zX>JlTy$jU)=0{|#GSsLoYCo&PhfYC2uqSwl4Uz`GslTKJsgJ5Ws5f0#P)ekXuLj?)tp$csrz(yvfrbhHlm+a^UQvH>5YAh?#+J7^89Zrc%OaF&iIZx z3vn1WccbALmry|zvOD+u5rjdy=y+A$CN5Po8s3;B%>lYIktIdf{9m>4}n0 z@?DH3m41rwHSyT<*z-RsFD+Igj=ecK6rS%Y4JFHPz{>{^zwm4$YYU+iU{+%)f;_f4 zAi$)8sqkydrb*2NdiQ(^hSQ zfYgpFT4+uhdr`PwKVE%p#LKj+$6aHY0PJUg*+F8;A*aN-$Fv7rIn;?RqWiP!6s~Mi ziS@Q6p&>>Dt&Lo?V*-FeLMR}HPbzI7p2tRz48|s~XM&mGt zo5SKTT;CJ0eM{GE{yh7OqC4@oDza5UP_ewek*q*036%&_&c$*U?j<3a@ZD%iKY-T? zi~8RNd9{0lLny}E<0Nof`d?mM{GI3(gIEiRH_)8Fzcs_@#?5J#$^KdV@2~nz;EBiSwL?4Ehyyt-nx_V|{^I$z@!ZZz8BJcpQ(G-&nvWhYjc@wz z00#eb|1rb8-&c$Oi6iq_UUve}`G%|28B^Ru2k(H9|Liya-*?{@MO+)(IDovstCMET z`GZ3|pAN2GR_G~%#n9yoA3Ke0{u_n$VGTydW?(4Q1j*dlX+VBOCUO~XNgR3LQ=g0O zmyOxR$s+5O&-AfNv>sQOd0Y>)i&T_GlYPM(MEh%g+Ley}U6b#CdE(LP4~n02BF|DH zFz-x@L{(TkJhyg`7PF==#dMgDt zzRRorNaOw#OoIyr%7$jz68Kwl4(Kw57|FjNy_xjZBxt&_@_NIT?2IOyCpVsd5I+!K z4j~%uR=k`4wIYH#rTEC_mNJBw6Of-Vc~rUd$RvbZKs6KF?t4N19So_R|HYrBV!!De z@Z3Xj0TKxDljkig5R84h0q0AA$kjAyOJ)ag0*ikB(40ef3N%!rJBIcZsxHC4{qUbX zq{f%)oH!T^AtZUNHLOiMX1|C3%T;f~6aJ2ZWwf(rNf%`|_u0IkW-ayOSISV>ll*ea zpn8a-u8$54$*zldQ4p=ow7=$)PDl0Lr(mwSxJcT08BsgT%Z1tYZ*pgLqnkzMN6 zTVbGgDOjIv$U47aNXv^J7FnMGMYQ^rCsrZ@E)^X)Rv*;#> zopxK2cvz|#!jx+`VU-Ct-=x_9$s_;03S=R-hr7>5O%Z_+gH1#Z>%7(7Z=7S9LctH2 z#2=<`%ky+cK7bi!|Bx;Xy#qFKth4rJ2!7Fkp@Uc7CTF^0Fcww`Pjl{{hfyk~L~W3^wY#rAGw35TRf@+A}Wy2dsZtZvSs>)oc8K5l>H2|Qr z8BZiWGYr-uqM{Fu!Q$Z#?91IenO6b#aPw`#_nnWQYQO=N!naO!AC9{&y=?#F&qzSR znXW#s-8?G4qU24c_`ko<*s}tEFt$DY4BIGU4@Fsg?4Chyf}~BhMs`56&eD7QL)yqy z*(kXaJ!bWxzQkQOa7L%2KF_CsLW*$D+QR{|p$5trTJqz@WQwb)&fKEC{W(|wV@hfX zjxNOlO(ES!rB%ZLwq62vcJ);wH)ebx)L&@Vfw~d8V2m_;Q!Xgqv{tIlU>BB~DTvQT zLA7;UW{GN6=CmDq;r{pK;^e}O|D8{IRXm{w*_`sWTs&XuJQ`Xd6Z{wX@^`?e+$p|( zpS&xWKLLb-0iZ)EbDK~oyxSCTq=Dx3WI^?Lv7-3CT3hklpe|>l(_FCAYt-NCFQ-}e zY4}J5C8@BjQ&%>CHX-9qrT^@*e{z?cY0wh0pyeegORvE2LX+ZS?7qt-P{u%-V3V3a zy4;-??j2z1r>mM!R>rE84NxC_^yP(mgdAU&FiCL7bC$1Mf)yK?#Dw(lh#lrHYmPOE zV(9_XH~oi3_;9zuFU&Iupc9bu>?Jvd%+f@je+O()8t)F$G>`G3(n?fHk~N&M=a1&G z0~9kGJJQhCsw8;`%JYp%|FC`i%t`%041U4qkiviu?x&g9FuyCK1Pjm~!Z>((hQx+Fmr>5vt>y`v@FmUs07KCAC+qb)< z9OA!6(D2u#-T|~a%S>x@y}K>K7L36>xbV*zmTg;%2ctGsYHrQmclgu7Y9+S2K5M@p zQJyS?d0(R)wdNdcvrxiRgbSmsr{I>33>F5V|2oCD+GYMW9ESv}^XPU$SsdiqUrgW% zEf~}=_BgpCJL;jconXdsz`kl7_R}uKr0Zb^@xX4AQecrc`BhBKlEKtvX539MUXaEB zovun~W@7$$zf*6qJoDDYpvq?cmse}GCj0;Ckg6Ws2cWnYd}Z>R=|l4R81)my1hw5e zfd6H}k33eEx3yb|E6Muf87K0BXV#YmSmIJbiv!Q*oBRwn1b)nQlITB7hIPp)WMT#D z*p-d_{*D4nfwB*Z@n4jViY%&?U{CPnw;_FX+>b zZT9jtF4%!y-kW>@n%1ivY>YRAHhw#f6*;K>@B>HoM5oE|QisPjkE+3%-FD!#D)%Oz ztwap%r?T=BLC^s^J~z@O^x6;*T@$%VR!qLkk5tqD>DzO122rblD!G_xceE$FsZ%qa z>0;H_V-3;p*l-wCAR zt*pJ;I0y)~fuT{ZKP{4HxN-N|mN9TYt(4y{udItZQbul6Rq_FGiUDa@+{{6B zU%h4KUjii4X%SN9ko9}(N{)v&txr^O)VrL^)Q} zjFx&!fAG{~cYlXK57_oLqEr>J9qU-aw;F`dQi=~vcyX!ZRKh*@gC|y!E0H`--yX&# z3X)Z9^*b-zePyp@66dD4%->NndntPY-W7c1Mb1uvYI9W)ViwwTbi~r@qz(A2% zV!Ji=n-m$Om&}$RVau)jzSZ9jR9BFHJuI=rDZ^4UGGLKt0-Qa+F`BWYO zkrFr%NRqj`JidzW$yV?hCop;JS=7`l)Wq?uA}EgS%zkWOxMmQDU#$XF@<O% zA#PYSq}CM1wGA6-V!fDhYLs4Do>V1w=k*i2Ar))NS(7s7Yf`Cu=|Px)N@oMC6%>?; z4F7a}M;B{F&CPc%pkU-#1UOm%Zr0aVvBSeBv7FCfS&H=PyJ2iACJONA9btmM{Bx5> zUSc^8={)&BkafM^V!ltJwk%?pWS5xRcEkbgSlti<@#~%n&wL;e)jyi`rt!24TLaoi z{^=U46;^n-GUMa6^hpt3KEsq($FIhRc*rubw=J95;ABH^DjkyNQV!a{1vd5cQNfKq zK9nYOhyL(fA1(OryDuoyklIxm9rc1^@4s@beza45QkDzV(!_*u8+Zw8Giyv3Fcbis z=r_4&s%gZF-kl{x@pBwiDIQq6q@{Tx);`NSdM{rkqFUF6ccyw&o1g~n*YC)+nMDqY zB0RPI>q|5xx2YWKxpMnRG=aUm^2 z6P$y?K(nfcHE_%5#ZMch9Q`$Tkzt=qW203K20SaB7E&jcL$@cUP)e{UPa!mx9*NY3c~%{IGWDV3M{ zRWA-zk3d`yxohMe7Pj39cnmQ*DRl`WfIGb&!6e8&o*+*^J+vf%{1LoOEVCkdcvtA? zN`;DkOuo@VVwX!x%lB8XzMbVmRX!%9zH;}tO_imbU_ACrncUUP z3-4^on~ZWm88hJ8^Zu(b7ISc{z4g8_TIQk>i}y+1%*PwlNo$Fo7IJhE9u5vBJ zbO6DYRub5x8UdSDf4e}1P?5e^mE{C@`8Oq!z+n={YF)3}R_aTbGZ`wdGRKe&RSd6N zy3A8kb-DHbR8ci&Z9s`DYPxMU#$=~6)*v}3uba>-H7m@JIgtTDytpwQs-^^e6ozmc z<wd}{HtJSJR>t0{M*&0L5 z21WdBw=AcNrSbNia^7zL;>kvpJe5pY^T>TDJ^he(fQV{r=i)*mCzYO`cJ-6T%jD-A z9~59FF<`B#j1Wy|evvO4+vimU?~z#~QZi3B%=is5X3s3P#(MF?mSi6xiU4IgH(-96 z9%x*G(#>;Zh6rRO(ZIz$$I2&vCh`LecWde}3tYxP<0*)Pf!q04+x8n}qJ=47F7w!6 zV1%REZ4@N>SdYbZa3mE#C5x?+Hk8k{vgKjAD3tia?8qSf}7>v9i=*r;v5v^J_oWoL( z8_S=pJu5*-3+!}s39i!;BdMJjKazh2;CPB}&$C0TIqk7v-I+4%brJDPq{99{5(+ON307 z>w&o(W+$!+LaapVC@W)B*34y(T}r4DUv5VhTH4a~U2G{6l8@#*ASmN_Te4o+rX_%J z7JP={!!iTs?|^&?T|R}oyN6f$a5npy34=g3=fKmb3tfkC>kBJOox-_1A*3&@Xst~s zUTo$ndB#=ZJ)VSRGiOu6z$^{ct)Pd;`z&%#NMLdcSht*=_b~8G-L-WeKZ3RD_%y@j zBn|AAZQ2s-bYG`%-;jJgX?mmm)26B)C-1XF;m~TcuOn^9y6)QsHm+P{PSP$ikK^Eh zUJlDzaFW;9MTbB4=;QaG7G+kt&2pbT8>%m42HE@Ikh~``FKJ`yF$18*Y2sGPL@)N) zKRhbVlIKWIa@S`PZ;^RsJr8*B?>NMws@yI(bHpd`hC{reT_j%e*T!D)^hG%pk$q&r zL!n>d>RDH4$7KvURVv*OsRjWulSF(-)e{Eu!%!u*-l|47;@pmVj&LFQzi$`FaeqbI zP3($$nO2I9OX8tPI6|FMxayQqu!h_n#6m)28DDK2{)__~Ib`%)8u4*Do0iXrM<=|G zTxJ?*vKGrfP&$-YDP0m^sgG7BrpgW5MV3xSsyRo1l1ZfT7Db-dep2+cq-adhHp`UX zW*d)_7A3nnbpHizF|2sA{BY-4#@;M1GxSHMe5c{q7Ly%F7M;4Ae z$9(!bKvAX{&2=auq5=$&cs-T{?Ll~Jg?m}0G)zlf5oV*fX}$yY7MT2Baq0A%*BQJk z%^ysvp_^U?t6|c@ffRc7kzT*W6;9YxMp4)u&GWr2@MH^O&1E2W4mRAc3kL_dh5;mj z%6jCJY_+WPv~a*A&nkQ1R~pG9_FD%-joVvAgR1%CqE4x2w`F56fX!Ve>Q5wH?am$D z!J6h|ds^2ccw!W>sG~hd?MmH!U3w%<4y}Gp38sVQKq_vD_v5v#+7FHyx|7z7;wZj@ ze-=dB_$~SXZqHk^U#`TqOF&c)vb~Zy1jf;0UXRW~PAXnZnAZ0VVQk9J+o@l3Mbrb7 zJL^^K@tdj73hnZ_wuf+t`=}l=l^~%Kg9#um!cd9ne&*w4*ptRit40Fx5T>Pp&Q?$f zE$8MhBZU<1vq9t^;)W&#ple3ko{$?tbOFqfK-Sm zr2hl|k$ydch=UesaanHh~Twbpj5NE!7efMBBg$V3>* zktBAzRRYpRpmn_-eVg_~V)Zj$X2StdBL9~>-~gpehwnJE^$y;K_S(oDyB)tAJt!CuQ0^DXK&O zAc>Psy)HH4be$R1BvD0-#PT-rYxf{4inYfg^-4!8c}J%78YWEP>Rnq98yJBk${4@Y z_enOp>GJwg41nDj&a*oL=?;*hEf|Q;zrwLO-ztvlSJjOfXFZ90PC6Zf)3&3B9X-JJTs1V zSfhg+!LcNl-ul?mW?yVj<|FUT7qt`^dHpQBJWcPGB(gx5I*fdkNnp%}5&~(eP|N}g zmE!BfqC8wrbH}p$hD_PR;0LxgJtTeSC2!Y8YNmD)q!3;0LU% zOhpA=?-X}~3uJv}?cIwk9F$HrVP17dRYK1#*&{e})Z#9fYH6s-ZuvAgtS_$|b=l!x z>Z6vc7A+1>24CDQ#;M0X699OQRqN8Oh!q?%u(`&WFF)q5UK*yn1K9Z{d|uEq2yOwa z*2fyD?W`dGkPe{dVWjN06fSzNP)-a*B8ykw+Rg2+#>s{FCGlSCdUgaTg%!Iewh7EM ze2H-|ac^wY4ja&z2^#Fsx)t_?czFAg^x7^t^#N~`$v6^9-LX2gi-UEnYCGh99z;nV zGopDbOSuSN&Q%rZ2<)8pvWUK~L=?+A^{}4cDN0ohtEqRhbkuPs<6~+vmEnTof6Vvl zn>T?eD;Fe*dNM3XtP9^$Xw4he3 zm$@C;vlINdvm=S#v92@$n1;{aV*l{J1G=Tz+v;D7!Y;8pgg-rjHlHWh>93@E)P;_K z7uCyjTk#%-og|{bI_|X}nv?=xji~Tt^lR{Z(R`v%32J2GObrTprj@l2!UugQkcZc>9oq#z=B#top;%?LJ|9VhIaIdweWVsh=!F!rS`G7^HUoqQ03) zyCn)&ZU=;DS(}RrfDldt2^RDR8%u<%D1T**@+kJrGFmgsU5U+63Apk+w-q*><72f< zn-NuI4`_M(FTuTXApE7Qqf!bhu}jLN7zMQ`*jpWZu6#83&q&{m`%didu<^Dh;8^9% znxsdBmF1`cSEm;saO`_=<`aZ%?7L7Ewkmryfs#d3NOFoANsw500jvb*m0uBdWx0$% zgv~5Mv`aOzQWWrcO&^~jIUy*U%Teecg9uzVVN8=XaF9`I;Ao%b<}-5;c7KT?MzYe* z)x@p93p;fu&6^(eW(f})i&*^{$TCVs6W z%;xG<05yu4FBk=8QOfzO<4azBYjI*5lImzR>>>PrXnV_`IJ)TFcW`%i8(e}0m%(O$ z;1)bsu;A`)gKL1`?h+)pdvFi#?j8cXcmC(rJ$1jFkEg0@S66jcbys)q>b=%_*6&g3 z%Gy5MRXKPjy55Qz_4(83YEJQ1#W0T|jxmC-zJLSH5`iyhM zQZiGh1E5F8?AGFs?#uS_>PGov8>2OvYiUq6p80nT zsO@<=x&J;iM$;&148Pk9dfwZl#t!Tcz!!VyHr|wf6`&w;GYvt#p>sOk%MaBUMvM}n z3B~amp{{rwL6xc~<_NkH6Z#K;AQNNmxhAD+f__T0k>wD?UPja(ac&+*-L){Hf`X}w zB)khDyy#Y@Xo9;9`ewzP??i(4m8~>gOW+&pDX#bZ>v93wpk9@yOno zB)MC=38o$jO#aYdBAEn+4auW*d1eoP2)j4@#xis#dSJ~^-Ik*QD+~g6+o}#7_R1cs z%IC}Wots1cD0TU;6LTkhnl^`gvfqb1^d`@BCtB*>jnIr-jYwcI1W&z<&2#jn+|NKp zx0-e`W$YhqfvZiO3?bZ5iN3?Zl(OwQ*L;)hAm6RN>1S2gGAuSAi)JmsHg!96kOp`6 z6vvD9|NWJ1#l(}~>l8Aec$W>6hq)FMB zi{7aq9%Qk&$zbQ={+B#hd#nsFO-rdd(v`ijxMB2v*kqu}POz}>yTGEI?c%a4H#7mR z;J`<+et(A?<}jo$PH>yA{u+FCG!0BJQu{;vZ?orl7Qfr?%*bU!=|XoJ>8xd#@AJ5H zdbwr5J_5fAv2XcsPXlot43_?mfpe?-Nk{GI&ECk9?;mMx$YbTjtA2Y?6sM=I`~Tj! z9=)T`CFV`&F`S*B;fR($F!zx!!wM>AuXL&I^9}K_UMRi&9ar>%ojSh zn1CGC*EaSOQg3zO$7LHMh=tFo608ekqD8CrPs&PNp3B33fN^8h!37bsM!A9+r2l=n z|NoAcc>wyy{QtQZPeI4dPRhS|Yj}l{heAY)FlCKjZ?sVjO@k4dco$CO*Hu_xIGnnZ zG>j@(JstCg05Fxz~G>!7Mp{z-4Bi*Sz-C;Wkr1{%i0Pi)X2Z=`P0;EH-{11 z4Yca7C>ha8V;pfM>R<)_BXA_??JaeAa;eC;@T!rLqT~ZFmMhJc#5X_TeN+}dz86yK zT*^#ag@1<2N?RM5`*lh75GN5gMOj(Y!mr9$5jmLry_*%pp<(EA3IY4S5$8{mEe z79B!|$vwzR0v>DWEEDY<4tDJdcBAC;&g$~~#Gz-m%eZnkcuFUO5qMc(aMOa+3#`i|Bfx)Fk`|_!w zzcoIK;zntZe5a!*gSs*nx9G?`oYH2sJII&U`a|ddy%5`=MZ-S@=8F>Y&s7e#ka)e9 zm4s_`GI;slJuY#F?Ocx7VecS~fPweq&DM->%X;swCe1zmbuZ%R#&`pyax`D=($8wa zK3EwSjX@-jjpPjYo2~Cj34$~w9FxJa$0UuVhHt2+M*j?ME%MIeBgq`&n_)TEa9Oni z@E5|M#xYn3NoA2m5x3v-KT@On+}C5!gR|Q1lR@D>hGNpsg;LP2Uf+kK%(GsGz(ew` z^X_B?C+I*YfvSUau_uedO#wqc7pxen_&A3h&*8IjpJf=Coi`(MvE))d88v^LzuwJ8 zSsXRUn_DmE#CN$?_DjQIp$G8+Z;+hKHwH+ZXX|Gy<;9WhLsh5lqapkr?9-IFN*3Ghj%553MEt{3dIwsGUfG3a-r! z14DRHn<9T_o*MNU&}AK*YE~@dbPdeVy!=>KW`^}6S)m#ejLoy26F%EjB@0fxJ7`Z3 zLspoZ+tZ7_*{|av((nSSO|KjPHmVI%Khor%(%SLlSVvpH^eoE-hdz{6Iml576RJ_P zP2Pbph0tD=-RFXLEsQJOL2l|YTk~`?7lpH%yzzA7s3J=J0z;366Z0iyCXLfu3BHFy zziHk{(**5BJ;kbrdHawZV?7tBe=JVI zM$bY(UB?e3^aHrq!M^UdxL>J~CA?=w6t_(cCp-uTWlzPa+{tE1vQj7RyCdFYv{~Wz zsm;7RWK`dT;Mp*vxvVn2n$$a$ZYr25ly7rK=%F`^_5p)?!r80LZPgM{HeIr|&5H4SLjNqSYSgpLqw> z<xS2&gLEBn@*NW(EGV?cVr7_qQz#{e<4h|E6b*ypHQ` z(m@qPGRSF<#9VXTg)y;F1&;eXws0D%ssskKA|a(hN)QuF>y{k7-whR-@T(ljib+-V z+4vjnko;X6E{B}Ld0M#7=5)|Y=BG-5`4`ITV+3&-LL3q@ahTJKM{gmrj>rjb^1}m$ zOa!g|3Dbt%VJ{NVc#}&q+@*l{@bJf!ZRs*^s>34mTipCe)12oKy-7r#dR!K#GBWnr zaz_R+407vHsIZK?#T8?BwF8wAZBfI`^ZA$#NZ2;BK=}=Ef$l(Q6xHT=gukXWaT7_>o>ZTVP-HE z#5;DyZj(j!8LP=#Q<=LZ_}Oeju;KMRXHz78_y9zRq+$<}zZXU+{ike;kqEyfC z)usrdW~|=DkM6h2LNJON_59umse6%adB1=Q}HVBA7Dgec>?bJ z^jQPu(xp?kZT1wl_r*GlC^({72Llp-Veu!h#gDFBZWWz}|-7a=#Z=f-8#F zTc2nm1{z$qxkUQxoPBq4b@t(#%8U&y+xY>FWH`D;jiDBWVoUK#t*gE%Rs*NK+)iqK z-7%{^K+>T4hGJjqe*mif_&sMXhG-OHl{=-*3P)z~1rd}uM+(SMJvxV_e+oR2@0~`s zQeD{xvj>(!Zeuf}GjHNw2FvHR$9l+zFU-Nk%4m&rfRWF`Y?toddV8cAIFz$t5;0*c zg~~Dv40EJd2I_S2+Y=guO6UKo5*y~PT2_kG;tRDxZ} z!iq*bqV&CZnQ0BEAK;5+HI#}HGKu{?)xFF8hvnCIAini=>rZtIXzN%@2LgEqMMbBv zN}CsWM#x#S|61~rGGXM9gN|0xFkU>z_<9VbJNRC&5gK`4biVh7c9Z%=WzUz1N4X;& zNf1fBbw(mJlu$C{t~Uw$ByY#Z5N?QwwTTuon21se-l_U$sdrImFHM%1BR&{=2~&;Am*lMPXkjPY z&G`16{Jv*ns3kRdNTzN%%E&msm>vkUQ2Sv(=C!GGj;;n@8H+?EGv(qZyJdVfrv#T1 zYgJIGs+xMmz;T=vDGz z&Yd-1Qghsya}E}N4lGVieAneIJkeyx&PEUU+MN0*G+L)JH4Hj-7oBagYb);gP^MC! zk0r3|=r{Y$qYgi(WFzJYC&&FJw@YgBX3TGEv~sN`n4&iRn!nSYx(j@z=DfHxIi{`3 ze{%6`dvx<%G3)@{G8pc`HwK;efr`kI3F>0@ak!`O^mWlOs1cZp7g**L7@V{bfLRJ2 zw+w!y1T(6FK5NtmyX({NW3OeCqb@qEnL1sTXG_NUVNDiO`v{Yae`&tRmI~tM-Fr0- zaydlp&b8h!(jOvH644B*s0HO-d?Eh=qDqa`eI|#lD`o*%jekCzefYmOXsp?r7>2*t zg0;{@`eY0&4aiTOHxS`Im^70Q21=^F{XY4W;5UfapZugo{#!(6~Ep3^pQ zou1Fb_y2FuOsq;tSyI?k?Sxwp)aZT@t@qI>a)CReLK)IoD635URx-E8*56RZ5P;IT z{7~Re7Op3eQN){OsUpNc=Fp2;@@eYkPYU-j(1tu!ixC^XAnRTErRNveU*2`rK{u~V8P-I|4=$B}!`R)0^Y>m))S zgvsa6+KI72=vf(wbP))Zxq=GR5NPmG3&Tykxi9m2lUa5E4)N|1D@i>OHDgVxTF*mZ z+bg&`7`(do!;yJcV4L}-Z15c*NwFLTevah5&6z&@743}Jz#MIlp-d-^Uc@{^9K}9R z^!j14{;5sc#YgzZy^H6)7c9k5==S&h-ZX?=B3*_@UIPf+(N)*K$PE+d@13ngb)8b(_PnI|WOG#p`Or*gJ58R_6M`R4u9-hII zqTij0IKTO4W$ZG$sD_e@q27taeA`hgV*Wu&g6ECTY1)Z(xT#rVvp(cDhQ?mjv}|2l z-+2^8->!D0sWxhsS>!Jx;DGgud7vDhU`JtdeHQanJ*>?niKW&+fv&6NEob6O_S0W3 zoG7BpgIA0vagg;7P&~GL*?$0a3D(BI5&2bKp4Fm}q{T`1e$)+QXv3lvJI-&J*5$iS(5Zw;=vCp;KSdvbrhxCASAjsLcpbd zh+%6i{1BuM;hd?~OixXyZvZp)FYIx%mur{oL{FR7#o$T6v1g;uG#>TgO5uDLeL(L> zD@lxR+?8|TqG{);%eYUg?Yoh*E|`zE**6Hgz|Mb8|5-gN32QAbfpe%4@OJ7EpE^5I z!DSx3ao{o!#+gA`tDQBG_1*nyHt3FSs)039eor0;t-sMQWfhn5UARHistUcslK;bX zgw8sZZ1!omNQjv^UX-=7!vn=L)A$4X7u^d=>-hMKw6JNPJbiItHqfDu&kFAqhd3Pk&pP zcA$N(==(6QN7IdJ%P@mNWPYqPfti z*~rQDSmj=agMmg#oW?i=lXNCy3_|;s>+g3HPn?(hEOu`{A~{`WmR~P<;&4aNn#9N> zK=-g4BaV7MN>5JSxj0uWq~v{XH;b$SvcfD4)v-h{cYFNw*Em_>VaXyzw#>lw=9NU7Nb zF$oilQDu$_7qrReuSObUNfYws(^5}7zpX97SSkzC z#22Z2_bRJ^%On;4iJ%vzjIZr0+q#oZ){ekzI75L~#MyTU;H&_b-xIx*gkF0AMSLODKU6(+o{&%7vF7A&d1UP zlJVb`w zoY8Evu-9)_$@;u%&_}z4NlW>Q(kepGnLb^4n*PPArs--9Rja;A2*O4H>Q$=yJxT^%$lF%(vSX+y~AzDPU@oLe+SLSCS`Og+3tPONO zjI({SJ1@9WjdqCgX|MlGKW&$rQvBl_rvUpNVvPMmC#AiknF`Lzs5M= z%*f#aw9O4;J|^7_Stxh8}*EH2a_=s79Epb!U!jgF`Iw>L51YMCijhWeAGnR5(_4 z`7^&Rev7Qq1}KN)CRM2>rwD?<8}j8S1LQ;1D}>X=3cA@pZ^@b!lkd7GCa&5|@C$&FyhM1V9Cf-SxcOjf#>VgUP)J#5KalDtRRBL!JM}(PD5CrHXEK)r$rhP6&OBqHoaC4wZk` zM5D7J^ZKYN`%V6RC-l)lu5ByUu6<07qzVJcxm}bnMJmek-DsaR%_uyT$o9=HY*%3; zYJ8{@2HyVw zgtev7;neW#R_1R=ZexD^usZ2#U&c;(1Ot>1y;A%g2X1iYsje>}rrAx|*`!f^u6fD3 z(MYuIAIqJ)u8FqohCG)DK$29UFS3NfjrVb(?4CriRS(Hzm>TfLi$k(qN0Ru!QXWs+ zI9(`V@Q|W+EX@4lSJue=8Pas}FW^E{UFd959`BwKLu`mhRH;Z@Lu%a$PV;Bft- zjj+V$*t!`b+*Hu|T-)31E(i}dbe?rRq`(9@_~pR<>X0t&!a{tH{h2&{Me09*0(R)$ zCt2*XA>13W>yD8(*WHIPT9fWb>5n}FCcI+)`?`iHW*u71?uhD&L<^0!vBg#Y? z?w%exIQc7uy!aNYm=6FJxD>>0-E00bOu#UEgPjgPLq+dZHDyrON?$K>)F{><_PR#i z2g9I`BF-QPBGr+AGcAG|qnY8&H%&}Y5PE^bE6zW537t*8=Sul8D+#*8vl}6`O}E(H z#x5l+t+Q%nSC!_$p&Z-0Y0HW-OQF0RsJ@sCJ zin*a5i@W&Y8zNgt$imNJ+@v@K1DpqwzskTS2qbOrTDQ<|B-9I&XS}G%? z8}4x~XKN%nB?TV28wyj)1jl-qwV!&!qs2R=dj96~amj7mdl+4rbW{4cU&f3PB7hyy zw<&pUUrHP6Rq3ZIq$M}T6og6pZ1t!5YJ>nBLpP@kJ_d7Kj(7ED>q?jR5~0l|#CpQR zUX@Ty6_}QCh@V~FuT4}y!$CJU;e3Jm?E(THoP9|-*FQ$xO-5g;2IOmLAfnpotWmiM`T%cJ=yTK3dwVEuMU3SPyqz>c+FJtO)Rxb%yytR^)kxss-14i(SaV|^RKJK^+Z7X!=7;LQ!*S&J zgv%Dok%P(*IJ>Ph1mhH2i> zw|?^0rUuVxW9b|;~Kpu5Q-pkb&?u$@-Hb^0P) zK`%@1jT-*M2mrfL9b(pUD#_(hWihNu;=q_-BVm=AF-9#U_d(HB`G+sp(6i%2ZyJGO zxj_e0#*Vo`ILF37rY@-%sm6^6HkQ*@7XW<%6`ITrWI;rSTWlc`ub&d$c1K45xF3X4 z$fhB`l89%E&{`lu>5Qn|@+IAlb-ZI-yg)7aI@1W{W+z2&TP5Yq#_-f|;m5U5LCGc` z*y+~OoT348%hBuCW%vfS=6y-29583XXwz!2#ybCs6fn#o);(JNW#U~c@D+%(8_74?4@Ea5s=KP9@>(y5seVVz3L@ezIJNj!ZQvm;CY6aTR* ze*vqKf)mu7`|FM;Al_*nb)q4!2f6Usmh42U$)%H`^j!Z;^Tmp)M!7Tnr0AMKdJ?=d zJ#wxX4F91k=TUcVU}*YWr%sJ5;hdmQQh;TGcaMn`rEq}@Qx~O>(M0)ll@ZEMg$91Q+0V71Jb-jnSrKr`ptdHqoeH!Oj-b@^2 z2mZMKslFSc5&cR6-|l(j&pjM9e5VIUEK@x4P}oMXS3nmlzr&)7s%?{>ztJ6wgHPBN z>n-#PQE~VDyO-M08T(#z$UI#}*4!Mx?RR(gx_`~tl!BeA`Sgz=cU<9$IZJmA-nPnR zm(#IxT_hu6;3IhR5OVWYP& z>9jIsD?nuc zJ*6DUU%*L~OOYpa@_~8;CmYiy_}qqdUV616kQ9B15KJ(c$1& zoScvtlbhDdwykBO3prQWmc~)*E;@-^J-HL%w_nk}r+n}GE2dvb>P2*W+HVxqwGs_% z^*I1eerG8R6Q9)8kt!yT&mxNYHmWQWO}`TBfjZ)=J$~`+8+{8VKMZ4CxLvx#y;E7^ zFdCqdi^zmH2G6g?o{kE!;z4A45M(i18Zp` zohd!fII-|T%3L^V_JSZV)6%SZ5QnZaCfaTtiX>E|DZzy0Hnp6_e1+}O8T0ZB>NR<1 zt22-d+V5xGuioTA`Q3`Th+-d?I4sQIGX=+Q9Xzyx&S)w8(kpvqWor8m;aMy}mhVWc z++Y?EZfj~X*a<_UbcsvlTD?Fdtt#2X(k-TM1k2qfkRGFL544@c5f6{aC`+pBQUotk zp7h4eo(yg?%-xEMgo)*@SZ=+DPXr6fI|rC*B9=}^`lOTzzZrx2CNwJg%GXK&$yYcL zX7G#EKBWggVx(m^lJMD64_El(0CBqlmpMkbq(Nl%NCvb^FT~aPshqA!Mp01pW4G7c^Pam=#< zn8NKnAFcbHQ=bLK=TJG--}`E7iug8Myqn35EzL35gaPxpBB^yD09SZDOx z=x#WYFwvH(uSf;%XK6p4)btnbSZ{pes+|MU+fM|LR(x1u_DBD#jPof1BFw}BLR*M` zuoN{|7m1_0hFjL*JvYy@pgI(A_XyhPL&w34Y7ePf01IpkRM#VF{z8z)&stnr>E&)Y zf|+hfk=Gn>uXXn-aO`U(UQ~bBQ>M_af*?M9pQH8M#wPi@R9Esx@kW35Guw+dv4I9u zZW!~kV)&=&vHG>zg#0vHD#wr)R5gpNcuk@fT6`sOlf7PH4gUG+#e13;W{g5T3~n+3 zyJ!avjX$!c)_V4d9tXO+9OUK1U>z-^ArIM{Ca*SkK_Q zDYCJ`XSOn;(PRXO`1ecs@}f~G3Kt6O6lje#&i*=H=n-*%T!xX-{|7m__btg zmE&Sxv(zT5qEiBHNKJ`T9lj9@!xj{(feh*5%m|weCRmoOT#V32g*vzC14iE><0G8k zAq_Z3C6Ww?F(;|zT;odSSS_8DI3MPT#ynYJtXw{Qb5+9U8O4-eVqre!%ucaIO&^5gF-{{ zs>^q{+q+65X+wn0{@45`aryMo$&PQ>QoN|f?z2C^O5krbhS z;7t4Vt*%v*Y4hyN#Jdh2M#8*LCm^1N%-GBw?EMb`V41<2ZyFvs*Q(;Gq43=v#6B=; z{3h^wHmvnP%wj+QFNxlHLqDS``{`p1;|lrs*VWwmb?!bpE4gP>B}iO zvoU)^3wly)B?b%JBn5=K<|LtP0m`jf2z6hrm4J@sL@f;jf#RQi&;&|J%L3Z>_XltP zNT&CE(q8Y!YE>o}GCuxw*r#4$^;HOf%~bno7wHn3Z&Q@vF0nZ28X|$QHvEz!$TR)%S^@(*NbPNRcjG8iv1m!k|OhnH~ZIlSwVh`+A8D&N$LaJ ztZ0qd?%u(~g8biiMDe7*(V%NzOCjDs%MuA$g?6ET=|AEo%A^AYjCcldWfj@5fel4* z6Rx3KIs*jNeDHM(yOF4uMf0*d7P~#|58eba_>fI4OnD^zKdLN?OZv7`r)j^t#}(U{ zbnL0)y}thNvb^hZ8O9ck=5F(P%VMBTzhtAh5i1w33`9n5er zvYHU}hw#6dM&!4Ad`C4K6V0{~a3+g~tc4<|{4wzDFr|aGfd)1=qVdn%v`*DEJl zvZoX1+hY9jhXN`pSuJdu-V0MaG~dyDPbb0tS3QlxL1=!Q^l#ngrvykI=xYRPgdhEVbC6BF4XsQX&OF>hG!R^5QD)vN4upj`wBgy9dnKQcuyb&PpP*^`4+-?Xan7#X5|t+{v&g z^2!+ka*N-RO@>po*{+0#=#%IIu0Aed;f z-V<84uHfy<-Iuy}Z_1^;yR7qWNaFnB++_~(x{zNl;Xp>wThnv$T8RH_V6+yEsT}}n z@5o5R76LSnKhbZqfy*qr-rAen3BG$hoR&L;5C4kl={1$oK3LjfrH&KeANo)ug+H7; zKlPpDXKQa9;em9W6rACmi}qNnrFHY!X6}f`Oo__#A%E}Zf{x33zr#i^NKv$Rn6?f%Wzs^MkM*qLa0_E1cJ4Sau{fB z$u-hH|6Qj>UjP>1U`O`Go7mO>`{Ws&K-;#v+}rM6H81QCgPn2P-}i#GTk)+FDKAlP z?J41ly|?=+<;ksMbX&l(njaJTgBAhnZrJmhANMKod~h{`uK!5Ft=<=*!0} zA}eM9v~PgvjYaCDAv|3WbMLWIPron&--2lnq9KnFrgwZaBm!%s?N=DR#g>lAaJ_ zz*Z~tTR6FE#A(G;CXv?%>;C|lhLjV+BL1ik-1JIo%S-R(No9P44RFzDFq77?o97)_ zi#v0#=hx@(rf4ok)V3@BNF{;J-?S*@Ct}C2ygWc_u0ytLJAX$O9#mUt^&7A<9(Ne? zV+Gq6m)BK9jw?69j5`oZzN8Q|+mpppQJlDq-r~<~czS=Lt4Sh+&Nj{cr)=}VmmbX3 zrYP%q`5`_yYZs&JnEp~#z}=ftbseE+Go;$-Kvn5ZDidSwVy3WVD?i+8;?M19u{|f@ zsCMdOs7~_196cPH96`{s25LC%Xc8AFdU~uXip*!kl!%_5IGGo~Pa38Yx4~4~_eY8X zoG9}7o-?3-!Um)!1e_X{UhMtGFAa! zFOt%w6zzQ{nhW3ru?U?@BKsc^|AYcHgfqNx@4>4N?6&<#s@ppCe!uQBeb8<$&AC6V z+@oh#{0Gof|4K`c$P$8HxaVBvu68sh`i%2WN*V4QDb-Rnth9Wc5*j_h+a%=n1G#22 z{*=1(jB?ts-uN#mBhagl>TAZ|PZUHstKr^W0QUvTJeJhplRFUxi#KwQ*+}X3j;fho zVb19?eR7Jsr1UYPu>@+eMB|rBFiWP&{o`D{W{aV@A{ceJd&t8utBHcxYkvu-e*7z| z(b)sVY+vw2Nu8DZP(doK9kb^Tag7;XnWLU~@tlzu9*P(~U%r}A6#lEFr60yBq6 zf)6^Sh1c>In_qmg=fUL>ns{*WI9_#$d+rLPP>AZePkL>NA+EH*_*UDeosC0(hx;v5 zY{C&=Nx0lBC81vmBa9#cX2K*FHuJ}RpRBsi@-j4_XZGjEa=Hpi>BxG_tb5DO-6R;g zl4ELwF+oLD8R7A_l-FZz<6I&Iy32rvGB+lFDc_qdLPky^vE~xa+d=xAh5RWamQ#Pu z;vn9pCyV2<8ZwQb_rTvD9@ z`5dN@2%R)eJ{uXo66TL6`eZr15^WI%;~e>*-orNO*kbL@1GuUmkP?U6pgiJD-UG0* zG6Q5||1b$HC+W3qj9K`+(7B_uwWRIeYGg)hbdjWW^-pebKUVsc9v^SXrz};v<(8sv z++2ROGc2{I!@E-S(PJN&YydF08`K}*8P9x9pZ?_s-Mv@dL2aYaf|bZGh+Abjz%#6IhI0)t=w*jDjBzL2>$l&SG<5SGz3 ze}Rf~4ETS!93TDjhW6!84*)|{1-1#m5x)rx3s~ZJKZHbv2u5ej zBa}2jo15eDeYK@-EIjngWP%;wW|n`po+>^p(Hw!!uZfs*)25xmH5am>TV;; zE*j@0PSjfsFEKha7&@O^TAhi|pKZxhqrSKkj@)=L*8*Thg4CEBp1T&Sf5Q@e@KoRK zlnt0HaEgH&GiVsu77yAjXSu3*^Qtz!eqcnRB)H<+?RYiq+%}0#CGR~1?3@!# zb3@a53QArPulbJ#0q4$TgRSC-7Oo!Xam`$pNg9-A87ESzddK;S?U9I9b!vMW40M*? zEI)sV-(_>tjTb6hxK)zFj`jxg8Y--3<7X!uCYAp1OOo1_Px}WJW|+j9n;fEjztYHV zR9uatCLy7g)h1ndrY8-@2(AR`xEyz(NU{Xyz8rhkn8&fnBq3GP;fVqYJvmSz{~#r1 z6o|1&Yw8t%(?0Vxr67ReVbcq5t=my)DqJDA=Vd{M-luI{<^=vJ4(#p%mD6I%LZUvtb%aL!h3Y zyyn>Mb3I?UK4&!eN;{q>_R4n7AKfut5RXDuTcbUDpmDXi))T?PLi$h69ePn_zZ}IU zrnNU`%;pnyEI?BRj0+YLxlIw|_MO1>c# z8SD@o2uu^_7_v5OMF`Hlt&{HN6^WuR5%z#GMiH#%ql2ovr`U9Q z>FqP9_P5akSs;#kEP>0axEUh|r*k-Z1tCfavvlVsc#@gZYE(?Yw_h|*9=qHaMNC;_w?GK*z((Oo-7e)3xyk+LVUwqlb%+V+2kLW^g^vvYU<85sz zh;L<1|B!gp6dfs^lCrVh=}szQkjO~aMPWaonia5VQ7*-h_5Gz4UWo4`H7gr&g!3aV zb&+}P>Lv-~AL+qrB(8|94l>~TSJb;dOAA6nE`=D0qBOI%U)=kI$Y($HxyxT z4@JZHf@>}9xxjf=n#zP+8{|Y3{WyLT1y4gHaReeq!D60OY?kaG0~ic7Ucg>BLicYR zII8qS3ou)kx@cQan$FK?b_$%w6f~`fL}{W8eZ7aEbGG}%8Sx7ZiCHQWd~bq*aJ2`y zQB9YV%ZspfWs4LEf)r@gMdTB;E-R4JzX+a) zfxr4#-@HErT^k6!S=j|{Jgapk3-@YMF(uwes~;6zg9_%CUxk*hOJcjVSlrZC7b(81 zj1j;pqsvel>_=spzsN{l3~_k!c%I_!?z#%Kop*=vsAJPcO4Z|8(0xRvcDi=*xl#&s zO3e$Rpc9PY1cY4idkK{n8q<nXdu()=&|S#A_;*$h^;3tB&b>Zib&kfjSvnf)SPoUIbHCJ)D^e0Uz$;w1+ zwW2sO;~uJH55ZdwK+*Joi2@pk@R@HH)NF-!EmG&*6uT3w#pIZtn)f)gzqw+LJJ~KE zwuc4qOlgvn%&uzn5+_S@ck~r?ZFDggT)}mwXbzKwSFx(Cql(zPro{;!7QQK0&^70_ zjJ$0ab1W|Gsd$I5KkY1aN7W8M&qUA4xpp4shk*)zMKnwhts;)fhx1-qJ#_Irg$B@{ zJv=WllRP+z=E{C$E5R`s$_mv8RK{UFKqq-?Q{|?OfS;09{t)o7id$%6a!xKc=;lXn znDIhReFQOsbvb15#>c4|22Tp+VzK-wb^ZC(Q%K}{$c1-3E~m2ojB7pMQRvFF^)L4| zH%ni=#wcH38KOwG^V$_N9~TuH2?xJba#qy4O!$n6j@{6`iBIAH+12Pv6XjI{|DU?v zI;ySc+ZIlOLvToOcPmbUOK^896t_~`3lx_YcPsAh4#kQDDaF0G(*gxbq0leC`@J#l zd*i+P&mQZnwa*zND=Yi#Gjrx##DCd;PtwEu@!uF)HehEcO^6{{Qg9WNefjMTl?JLN zO9$dWIm+UHrqB7FMKR=u@T19hIppyYpuCK9zkCfXet!TNuWYlO2@M%XlOvhB%ZhK6 zq*Px%Dn4zwM<>XGD|#vZkgv=CMH2d>N{y)}}E_2PaIv-?n(V3Me>0sp7 z>h?YpAyP}ZJ{@kp_AP=U$218Jt0P7u1tujq!Dn3n1eUwJZXktqd>hx3qYz|>| zCYMeQMWeHlF;)`A751vpT7#rIgW6n2?>JmV?#=Fisyd3U)B<|_?tTWCiTY^hc6XxO`5TO3?fNE z;Rnfo2-oj{dlTtx9Vh80WowhavhsGze5^z}evoWWY(T;P0I&Dtg4?Y$>hsBH=MqVD zBc&`hUkNcLIi^Luh0R%7RotcrW`c64#MmtB>T<6{o^~bBJ4^2>8QtC( z2wz>rTn!@6;BTZg3sFssk3+0Y_Cy2#{DnN?*zO zNa4(i<*$MZk=+M~qw}u?D9Q*AHZ}_bf4>AOhRX@WX?<@__oC>YZ=+l!*i{~kco zo5W|dL9JX0Lxd?;y;r1efj=uc3N6^qD~2d9EKkF(tZ6Gkp;K(1k9njloMftKgu%6< zgES&YtzYZJlQ!ftd8uF0rw`r=Z4{U(3=ssPYi-oSB|(--^ngI%u((pyEfm#B%_dYX zVrhFks%6lcX;$ZF6)1V50wE|NEGetF^`=^^^Q@koA@xT9H4Az@nyv%iUtj&{1Y7(u z&qfj+t;Btr>p0uZbpT$oBmO!JS&$teR~YAqi^bg<1E}Kt+gU|> z(Yz?in6iPTKY|;i&oA7!-*w)f^U9E;cbji)zsDoZ$3=gC&8|@^gDIEC>p-Adspf1XCL=;z!`PC+VML~o|m~~u||_`kDtdt zW7%ZJo5ij@;3Nm3u78bN)sReG=cVi~A^8)uzk=YV4HYc?e5v)O>jXMs^YFDzn|fy% zEQV`;GY9MzI$b$hp|1Cb&gs^NvC}*Xu|XQEB}T4_O6&v9mKO7v zu{-%1BLk)jfVJcmAu%~9cha9aVP{UcvXMSkL;IcPKY+#k=>0#yZ zDs&yAJpSYr#dv~6rsno^Z3QhN-h#4jr%pA8r!en#Gjf?WaiF8te}Fqe?T8+f`Ez%* z@1}1gg12VRR8Bk5IT+_Ik87&G3j||7^?grDqogmm@o6#;+34P8wXyyOXcCCyS1Jm} zn{|A6ONnEqyT1H$S--9A<#2zH^&hBC97p8<^6iKN{C^_=C?Nod0zySa2LVw~P|yGX z01yBoM4?9|AmT%#lh!6C;pLaHV9+8Jkaa_66lB&3k+ZaNZ~V6gzyyMTKqxqwLh6ZBkpR)-`b<*(T|jTax2+uA?*rPfDc5D?BB^6^;w6gW zSNNYfON*65ZCtl7;t5)stncGDqJ4G5H=#Y%n#poY^!k>t_T z_ty@o9IiO>MOZ);W)S{aY$T`pEGqjrlrqRGRx6es<(h!Mm{@&BISuz8z!Ymd z0JxH2N8ugYJ_}EP?Dpm#p#zbKLj-GcmNr`w*zV*bJ&ZczkMg~itwdoYu@{Mrvn}4= z!mp-rv>_bv2J@(d-Bnt!qC(lhg5ewa!XJb-+48em&T%K_3FFezxC`m%Z$la)#K`cBTUh1>$M-ub&6|!_B((pk512c{( zqm6eUXUsl_h4Je&S1*k;a4|vuA3=hbr>U6a`>b>_tD=%x34b#z^Z!61&TzPgKmzW$ z5kS!2c5LMXer(}RnYkF*yKxkzd?d5#t$<3{klVvbOQjKu8@Bb<%?wT?Emp4p_GVTT zKAy0JY$Sb)?C#CV24@UT#5Y@Kh0Iv2zl@kaFZ7|f#OLnV9VjFG=V5t>72j8o^r$`k z6XV}FI3tx-Twt2exsYTpGYnQDLN7)%y^pBlbM!FuBxN>o%q#`F@mN_)B@ep4+zj@t zo$(PByrRqi<;iRbXESX{(25I@Fq=+$=nN55Tpb`WQiV;Y5WFO^9+~vwqQr!`-iJOVVV* z!Wl`*?Wo?N2Lg$KL?=n*2q4zblA1I4q_tH>BT~4TDE4C=-6k=Per=BOzIP1U4@|9E za3vb#FRE}igZ5up2Y`yr^ip|B93sSp7>={gp|N|Ckh~~yVXc~Hfi~h-(u5%|Cge6l z_NIWSqD`o%7(Cmc zkebcQRLRq&?%)tQt7gQq@mhERb%>bB4qnK}08}T)x5Q}!qOf8?q`#!*a{2_b5tsaG zGR3LMjr#}S#a_b9WEq60(-UB6pb1LP{8&W?*m&dDsps#4s=m0@KA*gji-u_Tr-$_K56Y(h z!T7jK#-(d{!Cww;bL;2am8TeeLdDw0MX}vEW}cQVwp6AYa$sbYF<&Z_OKwGe3nJKF zt44I(7_5!rG85BD;W50P40ha%#||Tu3o6D0659$2>~GyeXtsNGCdGe5Uu=ps#v|5?CtOKD*d#2KkGwNJRemA+L>ZuLG$Tym zrKR7bUqk+``}@uF*JGfEn;3#eEJ2n4V56LcNlrZeP-ou-!X4GlZ$Q9sOnj&3A?gH7 zg&$+E$^&%F*uu84Qz5c@NdSHpkYm1LFR!wipI^oSdDoghCWaS)(r(sHg%{aiw@~eS z*=W<(;l8>p(SHCWjkWEGzyYf+?xQmM^nxc7C5e0?XSkOPw;DlA+Vx@Lh>Byfc;xIp zB}Q^YCUJ7Kvq7#b0EdAYfT3BcRyfYj@5T&SBZgy+Cl$ik=&|SpUpvP~?~;nVz=_%S zkANpB(lhlcDBz}=0HlFQfVcDR*fi+$(-U<(yb%1*OkDkWs0(Q>pWaTVVGNhi45o>Y z7Jm%g;O*Mn9?%j>6_1SjkcOdu2^=A~KQS%{ z9#5+3WF;2f2M(^YMoc$*%0*D+V?oq;vLqC#imzTtaurtVO>R+S&5lMTn8e{bI<8d5 zal1Q(6;^U!|MyU$)?Z?}Q7$M{RFYAHrT`(igLFosxvjknW=;~-VPc7ae+ff}Cs=KZ zAf|7;u@YyaMh}QF$q$)uXX!Q=aXV>Z>0B3+@Xm(qZOFb|%@}P>4%^%Av@~C?uKGEj z_X_)%Q;NOB{gfFs^M3@wDI{SxBLA6%9@=;k!~fAfs~?ix?b*7DKmJ;T3@d>(sSko! zK>I9x#q5}b?9avS_0s#BD9E~vj#0Qbb=(YR(=CEm=Ap?!tU|4P>a|EW2z^<@CSP_y zJCI?{=LrV*@yQa%AMDA3THe#`X>WsyITfOJ(rA7b@eSp)o|l>ERgT*0RQaQi*N}-rWd1=Ii^C@C6;k_jHktx?l%5aM47M-UCK48>)Uepdi6mR$G3>SBtT{z= zMjUUm(iv}a=*ACOKn^@f`*fz~%!f)&7IbD1!Ho#+#}|@R05!a9_G!FLAcWQe7v(Mo z{`DUqVj<{LD~;9=ZAujBXJ$W=sI%eX)^FPK=)C8k|37Or-vCaoCzhJ4Mnk`VLUE<5 z?Dq|ivO-(I+MWqVnOGOF<>%~w05pJdNL8bbbGkv5{|#^c{3q9wg4t1Btnwhbn1@Yl zQS=Iq+cs)OS4HFrOV3C#EN#r}@gLbIVKEQW*c9(sIc|@xT+1Tv^3L9?-EI%DilB0z zYAy~i4d^+bo2?f!u{Jgi-ZU0QP0V!Md_7UDTvoxBEGFA)l*8BhOCRYwp?4w_&fl6a zsdWB-4T>UKVZ9}WX-?Pi=Grv~A%BGiw#5UA|A(u3maFp^5!-pQVPP{5gFo?Q*^3^I zTbf=+Vq5Q^3pz`w>aGPS@rE>WBy@=Z-Nu&8W(OwHBVn(NJbTCz0LE{ z(Nj(-Qr|IhDSK7Ck(*ZaU_iX~UI(c>dIN+9NKf2Q?Fegy%wWtn=FdN5K57<{lpKdr z{gx>V(nO{w1q~6*AyK(p8LZWy+il1858$Tm=a#$x+bLEFMjkmR^vPXE28167kl^Np zqVFX?&mV^+HdwWpOI9dE$1v-Z?Zk{{5$T(h9i=C7@e|X~tWpapMhUCDo1Drw(O1Pr zhsSL&$yPjR7=W7q;yLPu>btkWY%=NkqIZy zmX*|&NK2;*f4@AGkcD+zX#gfL%(1G_(jy}E6vBt{+QJ6wQhMiKHh^j*6-Xcx zKA{*j@0N1#8g!wpM5Z~o_(t{9P0Zm!>CGS^Rq;AwMjqk?M?aB9IT^>tYKQ15Hc?;w ziFds$<*kC!(weeMnPg6$))~1t8x)H%!_DzHKgTzM3|a*lNX~*?7@KNrx>M=TC0vut%2aF`WB>V zq2H+Q*xJukB|abAsBiMM=7*HF`@|<@)5@u9Me*<-I9et>0bX)A#YG`CmQ_M2%M*H> zv!#O!uL?#cRv7G4O%skJDYa`Cu=JaRgkYuPY)?v+GI)g##LJ3IK}vBUXPeEgT!^J_ zj<@k)wmFcBoU5n)(sBWI_e^tRo1r3ugzY9uJ1+n}l>OKn9D?}| zFx-HI0wf6mAP^9Qf{OJYJOBlVgaSYS6hc%Y0(w3)VmfIO1|$@qrEOtJD$A(j=8i59 z+9Vi~T=eadsc~@UzW@Q0{{jS_Cw0nrjz9tOOCbvtFRKo4yGIVk$%4W2r)Qt(0}={v zpFimJXZyE3eSxB!2KRagSnc&Sq{dcsnrSr#zAwZJz-PAe`P63@)?Oc}_==Frs!}B` zyQF))`n%JGxFC;d@7KY^8_;~5NaozP4VL+-6y@g-UNEm!N`B4zadwP~X-vk34UP|n zuv}@afnom*Dn+&_HJs$UFFIpHh_#leKOSt>Qv)I4GnBE?6_puATy$9^v~gqNie<^Z zLEQ;@`!bf~=>`qsS-JpvvN+*9=`Z8X9z>UAC`WmiWdanvY_1s~nek62n>~cmc1H-3 zA7g6aR~d8~QJfI7LIv!_6b-)T>o$Wk2vYc|-MQ+_sun6?X;@$s+q(dnh%R464V#?ljHuts^R`fN5$@@?mML zZ6^x>YV5#FnbnLpKn`gT>%HrreAauP(4Tw)#?r-im0lPJoPE_B-)Xd$-&pC%iPTy( zL#z`c3^+XKVX*WS;(WSiPNKQ#qCWFv7jLs-z4Y|;p4v9$@vlA9-dB~nC1AP)a&QQA8|C5`l=$l?N;HpP0}1hzbmv?&ZvDODf}CS!Oc>EDlp-IO z0M{ASFPYQV7V~vd3SI4vxEe5eP|5pL(%lCPMqEG)qEbqR0Vx1hT7~^>EG#%nWrHzw^xv-;ZAKCW%Z9*Si zXESz4RAXDpriFn7sv!p^E!i83oS6HMmnD9F@9oOzIj~U=s%3ag+wZ{PK=EQR z`i%;7{pu#F&##^=;2uVKiY$dBq13&!st5AN-15=tzw7ahnW@~Dihz^G{P_uDND0lv(v(qj4qJ?bPF2u?&i;HaPDmY1%Y?^jB1E zhuA<)gs|FL*h(MIVb*&h#tr~4f)(lz%TVs-TAslv1(qc;!f#2xc5Gz~-2`~5!dN}V ziv}|}AHVK%taiF43}UjA;&$2bEtHU^b2P!C+IXb-2$N%|MyiZ|jx1A>4;%4iD+3>P zxyRFmf|MDY2-Eu<(to5^g5|sk6R6TMNUX5GR1cuk{`74W*0`^i4}$6%H4UYp{)Bw& z(D95xb}o*eUY9xc@E|+TEfMo_djsLy~lT zY;6~nQPS!&ytlx%O$)?F1FT6o+<@2SGcCsTB=NCJ0uY!a&kPbqB1VGt6PKL)c~xn5 z>9G@kVl}F3qO0vnT54KyJowjWN}_4DYGlD=(-}-2==z5K`JUaS%YV}8#RtcRaHti4 zIX-|C4Va>j57!ve<-8F`n^`xOCwfzs%E#moHwHSeoZ{$SJG1jDgT&X?5<=Rm(M<5*Y zrdH&A7vu})HOMHg8Y)1e`ZiCVzSqOCQDh~J`sF7VrJ@XqkWEYmNL9pWAHt-PM?XOx z`>_DsNO|Jw&iAkMr;2CI7$Q9Qyie-O8dpBd`kRN?n%OqV=3g{2 zMpfe<4e*ZcN14eY#0ga!wO`J!R=jP;3aE6hko!Vap`^^p8Y#?Ag=Gz~Qk!SdYd?p( z8;eD$iL*E9)&{iKpOm#vQKar6#ePZzT{$bM;wm^hBR5c`XRr(g9u%Aq7I=XKl@>-e zDo*p8mao!jv(ilXt9#m?z_L5zM2pTpSouCJ@=mgQ=|!Y?_%Xb&C>E&W(AO}1D(jG# z?jBCvCnX>AJ2Z}PF8WX0thBup!nr*#89lPReyi{K|h$Mcgvpzi>Aj$CW7bEFuaTRQf6Pt>0;-9x(O7xUZLP9$$Pz+!=8 z(cvG!2%)!)nD-x9soe8be#g#8#lF$yY@_CTcb$Oj-U~$6kDict&p+KWvz5|J8p@Yu zdM0f=u4BFWSN&u%DpT*lej_O_55Y~^t~4I6?`quS0bP3Zpl{9GU^JTYu+4NO8#A`| zZAnx4^z;pqqKq0!(WafW{fF)x9V2AZQav((S#&qum#46{4w1Jg$K40LY2E|cG+rW-V=ydv{~>Ddqh;`1#t4S~DTeZ*TyYFj@F|sL)o{H=57rXVp>r@h=OwL@ec_=81mGBY9CKU>(S5?>n=e*4I)X`EuY{#oh zLlfC`Biz)QPB~=nqht2dMcN? z;Yoqj+-Q1P8Qf|L{Pb1&u}wr59)cGm*~x6q%Jr&s-i{$1{*p4S}zs(vR`-m z;5eloJ(^bkAy9%5Hu%sLM07vjcpVM$=&1o`bp5IVJR^<@&{R3m(hzwyE{IUtIJE0qj{r5too84`$o9jW}7MLSBZdyB%P0ih$p#;W6!Kbv5rn z9OYRVPa7NtYNm0qZ@;XN-3dI7g|GemNy}Z@(N`)0k|r0>UbCQXQ&=+JG~sE!J)YNG zvrJgGpo>d%QPNHoqOJ)45b@UbVzKzmOY?Zar*g83b`U<_KoYvz;+9KmM_SpCu!(S? zP-vD7R?yQS#(=xKg{%_!{gahb_G}g4NlCy$CcC?Zcn6F@_q{m7&xLs|utyq;> z+Z+j>@hf`o9n8O_7czwH%-P94M$O?n{a3?6meT&1seuwiiYwkGbss~D}Tqf$KaDI6~t=plhvBM}Mfdzpy5yM-#n!Y=6|W zhNn!=0`4Q1o^XD|jl~)jgA|u}xtzARa2(``S!y_1j1s1{DCAu7hUoq8OJ=Yz;5F^d z0lqouhPJVy+_1*&xvhUS+z{a<=>;Auo3$;`DH7<|S&j~}Fe|){tziq*lSWqMh41gU ziBYJ*x)FI@*{FuUciM;cgPl=-ci*b&(O(5mf8Rd})&gLT!D2(6`6L^TZf95%Q*+&A z*}*9{H9femv(6`9^sMtUcItDJWxym!t!l~OZV2#rHZg;ZT5K{u3;e%KRVofhoH9(3 z1R0li8z4^>%HWt=y>62nooX7kU>hLh+!Em%@n-v?8Ozo*swb_Ih4MXRjOiVrDN?)f zWfDkcs(BkBTQ9(={%2yJx$Rt%sjhavSd^c-jxc|h(=LJ(Dmln$zh9U=KMjI!d^hgv zeYfV~T8p&0`dd7M><%BMr*Cs}&qPF){tx%nPsgtQ#+1M|pUPVB-l=30kIg#)l@j^UhGCQOo|dJBg*gq|g?2oO%FQ8XcSL-Y^{w?c-*0TUxV8f^_n zgJ!0oR&FfsYL~9ke|n5J#syVpu7qRTQevmLnf~Hgqxu~LJvoK&O||#Jgl>rHr0aM^ z?};7>EUg@W1C$RpnSHCR-3~vqsv1kov)lS|J5KzaRv1v&`kavGr2Ye9rV@urbs&O0 z!M$X3u+l+s;q)L~zOix$;+XdFe4bn0I_O`l6X|?itFlz=>xurVx?a}nGC;Aa6`wR9 zy4E7F%z>2PVhZo`*;P(bHkvr8IiY)uhK6QTk4b;>=BEykwTrhMmiRD(+-y_SHer}1 zsh&gyrlir!7JJ`(ojw>?Y;b&9USb~qYb@cXu*wYjx(_1ScXLe&;N}ZyZva?U`SOIb z?wooLz*2oz+rDAh&tP%;$8yoGxzsZvb$Qq%$^vVoZ!U=bd!2teENk%47Nl-9+3^#}W0H zzhq=FNfl*w7T*oWOWr?65&ZvY3Ng+%Gxb!t&GR=W+scHB}r>)Fs#} z$^>u9{~xY&bK2xzd!e-Ul0}9|(R$x8T|KWNS8k=48&dJPM5nco8&s6M%{?l7!aIYa zyLt?S?iS6kNWB*me^%+Y=|{{|`Vl9x z*IiJ0oy7OIok;I_UH|e8@@Slb~m9)z4Kua@4UR-E5Okb zNRQ16*l-S--mFDIp;10JS!nT!dF-d5tTRdK@gi2O>Cmn{_z}7tJU%a$=^)0aAZ1gd zs&2j;`nx5M2VTbab^VQ)LZ84}%NHGIb^~(2@vk)BN;k`Gh-E6< zL)z2%z|cfM-HXD#^#I>idhKMvZfsE5hfc-|K7nhl_wsN_DvjMCffyO8#5U~|)SgdK zma@S?HJfeiRw%zaCrYxO1idHfCO8!YHqj_ssj=IO` zM`x<&EyRF#$(jZk0DGWZ@N1G+bHyFK>6IWFsYj$FX} zkunXicg%Ez*^V0W7|ptqQvPUJcVyvf)@!jL7&ivhIm4mkKDKHz?~99(i?!6X_rKNu E51pZubpQYW literal 0 HcmV?d00001 diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 7b9cf2b34c..5cd8646f75 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -822,9 +822,11 @@ - [Camera Integration/Architecture](camera/camera_architecture.md) - [Computer Vision](advanced/computer_vision.md) - [Motion Capture (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md) - - [Neural Networks](advanced/neural_networks.md) - - [Neural Network Module Utilities](advanced/nn_module_utilities.md) - - [TensorFlow Lite Micro (TFLM)](advanced/tflm.md) + - [Neural Networks](neural_networks/index.md) + - [MC NN Control Module (Generic)](neural_networks/mc_neural_network_control.md) + - [Neural Network Module Utilities](neural_networks/nn_module_utilities.md) + - [TensorFlow Lite Micro (TFLM)](neural_networks/tflm.md) + - [RAPTOR Adaptive RL NN Module](neural_networks/raptor.md) - [Installing driver for Intel RealSense R200](advanced/realsense_intel_driver.md) - [Switching State Estimators](advanced/switching_state_estimators.md) - [Out-of-Tree Modules](advanced/out_of_tree_modules.md) diff --git a/docs/en/advanced/neural_networks.md b/docs/en/advanced/neural_networks.md index 454d60a16a..039259fd5f 100644 --- a/docs/en/advanced/neural_networks.md +++ b/docs/en/advanced/neural_networks.md @@ -1,119 +1 @@ -# Neural Networks - - - -::: warning -This is an experimental module. -Use at your own risk. -::: - -The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4. -It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on. - -The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module. -The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame. -While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle. -Note that after training the network you will need to update and rebuild PX4. - -TLFM is a mature inference library intended for use on embedded devices. -It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use. -If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview). - -This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works. -The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether. - -If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/). - -## Neural Network PX4 Firmware - -::: warning -This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04). -::: - -The module has been tested on a number of configurations, which can be build locally using the commands: - -```sh -make px4_sitl_neural -``` - -```sh -make px4_fmu-v6c_neural -``` - -```sh -make mro_pixracerpro_neural -``` - -You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines: - -```sh -CONFIG_LIB_TFLM=y -CONFIG_MODULES_MC_NN_CONTROL=y -``` - -:::tip -The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV. -::: - -## Example Module Overview - -The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below: - -![neural_control](../../assets/advanced/neural_control.png) - -In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow. -We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow. -We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md) - -### Input - -The input can be changed to whatever you want. -Set up the input you want to use during training and then provide the same input in PX4. -In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order: - -- [3] Local position error. (goal position - current position) -- [6] The first 2 rows of a 3 dimensional rotation matrix. -- [3] Linear velocity -- [3] Angular velocity - -All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function. -PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation. -Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one. - -![ENU-NED](../../assets/advanced/ENU-NED.png) - -ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure. - -### Output - -The output consists of 4 values, the motor forces, one for each motor. -These are transformed in the `RescaleActions()` function. -This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values. -So the output from the network needs to be normalized before they can be sent to the motors in PX4. - -The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic. -The publishing is handled in `PublishOutput(float* command_actions)` function. - -:::tip -If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned. -Decrease it for more thrust. -::: - -## Training your own Network - -The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md). -But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended. - -Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU. -If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/). - -You should do one system identification flight for this and get an approximate inertia matrix for your platform. -On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md). - -Then do the following steps: - -- Do a hover flight -- Read of the logs what RPM is required for the drone to hover. -- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform. -- Insert these values into the Aerial Gym configuration and train your network. -- Convert the network as explained in [TFLM](tflm.md). + diff --git a/docs/en/neural_networks/index.md b/docs/en/neural_networks/index.md new file mode 100644 index 0000000000..4379f079f9 --- /dev/null +++ b/docs/en/neural_networks/index.md @@ -0,0 +1,21 @@ +# Neural Network Control + +PX4 supports the following mechanisms for using neural networks for multirotor control: + +- [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md) — A generic neural network module that you can modify to use different underlying neural network and training models and compile into the firmware. +- [RAPTOR: A Neural Network Module for Adaptive Quadrotor Control](../neural_networks/raptor.md) — An adaptive RL NN module that works well with different Quad configurations without additional training. + +Generally you will select the former if you wish to experiment with custom neural network architectures and train them using PyTorch or TensorFlow, and the latter if you want to use a pre-trained neural-network controller that works out-of-the-box (without training for your particular platform) or if you train your own policies using [RLtools](https://rl.tools). + +Note that both modules are experimental and provided for experimentation. +The table below provides more detail on the differences. + +| Use Case | [`mc_raptor`](../neural_networks/raptor.md) | [`mc_nn_control`](../neural_networks/mc_neural_network_control.md) | +| ---------------------------------------------------------------- | ------------------------------------------- | ------------------------------------------------------------------ | +| Pre-trained policy that adapts to any quadrotor without training | ✓ RAPTOR | ✘ | +| Train policy in PyTorch/TF | ✘ | ✓ TF Lite | +| Train policy in RLtools | ✓ | ✘ | +| Use manual control (remote) with NN policy | ✘ GPS/MoCap | ✓ Manual attitude commands | +| Load policy checkpoints from SD card | ✓ Upload via MAVLink FTP | ✘ Compiled into firmware | +| Offboard setpoints | ✓ MAVLink | ✘ | +| Internal Trajectory Generator | ✓ (Position, Lissajous) | ✘ | diff --git a/docs/en/neural_networks/mc_neural_network_control.md b/docs/en/neural_networks/mc_neural_network_control.md new file mode 100644 index 0000000000..6f83a67cb3 --- /dev/null +++ b/docs/en/neural_networks/mc_neural_network_control.md @@ -0,0 +1,119 @@ +# MC Neural Networks Control + + + +::: warning +This is an experimental module. +Use at your own risk. +::: + +The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4. +It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on. + +The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](./tflm.md) module. +The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame. +While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle. +Note that after training the network you will need to update and rebuild PX4. + +TLFM is a mature inference library intended for use on embedded devices. +It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use. +If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview). + +This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works. +The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether. + +If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/). + +## Neural Network PX4 Firmware + +::: warning +This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04). +::: + +The module has been tested on a number of configurations, which can be build locally using the commands: + +```sh +make px4_sitl_neural +``` + +```sh +make px4_fmu-v6c_neural +``` + +```sh +make mro_pixracerpro_neural +``` + +You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines: + +```sh +CONFIG_LIB_TFLM=y +CONFIG_MODULES_MC_NN_CONTROL=y +``` + +:::tip +The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV. +::: + +## Example Module Overview + +The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below: + +![neural_control](../../assets/advanced/neural_control.png) + +In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow. +We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow. +We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md) + +### Input + +The input can be changed to whatever you want. +Set up the input you want to use during training and then provide the same input in PX4. +In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order: + +- [3] Local position error. (goal position - current position) +- [6] The first 2 rows of a 3 dimensional rotation matrix. +- [3] Linear velocity +- [3] Angular velocity + +All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function. +PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation. +Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one. + +![ENU-NED](../../assets/advanced/ENU-NED.png) + +ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure. + +### Output + +The output consists of 4 values, the motor forces, one for each motor. +These are transformed in the `RescaleActions()` function. +This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values. +So the output from the network needs to be normalized before they can be sent to the motors in PX4. + +The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic. +The publishing is handled in `PublishOutput(float* command_actions)` function. + +:::tip +If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned. +Decrease it for more thrust. +::: + +## Training your own Network + +The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md). +But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended. + +Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU. +If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/). + +You should do one system identification flight for this and get an approximate inertia matrix for your platform. +On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md). + +Then do the following steps: + +- Do a hover flight +- Read of the logs what RPM is required for the drone to hover. +- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform. +- Insert these values into the Aerial Gym configuration and train your network. +- Convert the network as explained in [TFLM](tflm.md). diff --git a/docs/en/advanced/nn_module_utilities.md b/docs/en/neural_networks/nn_module_utilities.md similarity index 97% rename from docs/en/advanced/nn_module_utilities.md rename to docs/en/neural_networks/nn_module_utilities.md index d00f8aff63..b1df217ded 100644 --- a/docs/en/advanced/nn_module_utilities.md +++ b/docs/en/neural_networks/nn_module_utilities.md @@ -2,7 +2,7 @@ The neural control module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) implements an end-to-end controller utilizing neural networks. -The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md). +The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](./tflm.md). This page covers the changes that were made to integrate the module into PX4, both within the module, and in larger system configuration. ::: tip @@ -75,7 +75,7 @@ Which timing library is included and used is based on wether PX4 is built with N ## Changing the setpoint -The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message’s position fields to define its target. +The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message's position fields to define its target. To follow a trajectory, you can send updated setpoints. For an example of how to do this in a PX4 module, see the [mc_nn_testing](https://github.com/SindreMHegre/PX4-Autopilot-public/tree/main/src/modules/mc_nn_testing) module in this fork. Note that this is not included in upstream PX4. diff --git a/docs/en/neural_networks/raptor.md b/docs/en/neural_networks/raptor.md new file mode 100644 index 0000000000..3867908fd8 --- /dev/null +++ b/docs/en/neural_networks/raptor.md @@ -0,0 +1,221 @@ +# RAPTOR: A Neural Network Module for Adaptive Quadrotor Control + + + +::: warning +This is an experimental module. +Use at your own risk. +::: + +RAPTOR is a tiny reinforcement-learning based neural network module for quadrotor control that can be used to control a wide variety of quadrotors without retuning. + +This topic provides an overview of the fundamental concepts, and explains how you can use the module in simulation and real hardware. + +## Overview + +![Visual Abstract](../../assets/advanced/neural_networks/raptor/visual_abstract.jpg) + +RAPTOR is an adaptive policy for end-to-end quadrotor control. +It is motivated by the human ability to adapt learned behaviours to similar situations. +For example, while humans may initially require many hours of driving experience to be able to smoothly control the car and blend into traffic, when faced with a new vehicle they do not need to re-learn how to drive — they only need to experience a few rough braking/acceleration/steering responses to adjust their previously learned behavior. + +Reinforcement Learning (RL) is a machine learning technique that uses trial and error to learn decision making/control behaviors, which is similar to the way that humans learn to drive. +RL is interesting for controlling robots (and particularly UAVs) because it overcomes some fundamental limitations of classic, modular control architectures (information loss at module boundaries, requirement for expert tuning, etc). +RL has been very successful in [high-performance quadrotor flight](https://doi.org/10.1038/s41586-023-06419-4), but previous designs have not been particularly adaptable to new frames and vehicle types. + +RAPTOR fills this gap and demonstrates a single, tiny neural-network control policy that can control a wide variety of quadrotors (tested on real quadrotors from 32 g to 2.4 kg). + +For more details please refer to this video: + + + +The method we developed for training the RAPTOR policy is called Meta-Imitation Learning: + +![Diagram showing the Method Overview](../../assets/advanced/neural_networks/raptor/method.jpg) + +You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here: + + + +For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481). + +## Structure + +The RAPTOR control policy is an end-to-end policy that takes position, orientation, linear velocity and angular velocity as inputs and outputs motor commands (`actuator_motors`). +To integrate it into PX4 we use the external mode registration facilities in PX4 (which also works well for internal modes as demonstrated in `mc_nn_control`). +Because of this architecture the `mc_raptor` module is completely decoupled from all other PX4 logic. + +By default, the RAPTOR module expects setpoints via `trajectory_setpoint` messages. +If no `trajectory_setpoint` messages are received or if no `trajectory_setpoint` is received within 200 ms, the current position and orientation (with zero velocity) is used as the setpoint. +Since feeding setpoints reliably via telemetry is still a challenge, we also implement a simple option to generate internal reference trajectories (controlled through the `MC_RAPTOR_INTREF` parameter) for demonstration and benchmarking purposes. + +## Features + +- Tiny neural network (just 2084 parameters) => minimal CPU usage +- Easily maintainable + - Simple CMake setup + - Self-contained (no interference with other modules) + - Single, simple and well-maintained dependency (RLtools) +- Loading neural network parameters from SD card + - Minimal flash usage (for possible inclusion into default build configurations) + - Easy development: Train new neural network and just upload it via MAVLink FTP without requiring to re-flash the firmware +- Tested on 10+ different real platforms (including flexible frames, brushed motors) +- Actively developed and maintained + +## Usage + +### SITL + +Build PX4 SITL with Raptor, disable QGC requirement, and adjust the `IMU_GYRO_RATEMAX` to match the simulation IMU rate + +```sh +make px4_sitl_raptor gz_x500 +param set NAV_DLL_ACT 0 +param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms +param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs +param set MC_RAPTOR_ENABLE 1 # Enable the mc_raptor module +param save +``` + +Upload the RAPTOR checkpoint to the "SD card": Separate terminal + +```bash +mavproxy.py --master udp:127.0.0.1:14540 +ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor +ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar +``` + +Restart (Ctrl+C) + +```sh +make px4_sitl_raptor gz_x500 +commander takeoff +commander status +``` + +Note the external mode ID of `RAPTOR` in the status report + +```sh +commander mode ext{RAPTOR_MODE_ID} +``` + +#### Internal Reference Trajectory Generation + +In our experience, feeding the `trajectory_setpoint` via MAVLink (even via WiFi telemetry) is unreliable. +But we do not want to constrain this module to only platforms that have a companion board. + +For this reason we have integrated a simple internal reference trajectory generator for testing and benchmarking purposes. +It supports position (constant position and yaw setpoint) as well as configurable [Lissajous trajectories](https://en.wikipedia.org/wiki/Lissajous_curve). + +The Lissajous generator can, for example, generate smooth figure-eight trajectories that contain interesting accelerations for benchmarking and testing purposes. +Please refer to the embedded configurator later in this section to explore the Lissajous parameters and view the resulting trajectories. + +To use the internal reference generator, select the mode: `0`: Off/activation position tracking, `1`: Lissajous + +```sh +param set MC_RAPTOR_INTREF 1 +``` + +Restart (ctrl+c) + +```sh +commander takeoff +commander mode ext{RAPTOR_MODE_ID} +mc_raptor intref lissajous 0.5 1 0 2 1 1 10 3 +``` + +The trajectory is relative to the position and yaw of the vehicle at the point where the RAPTOR mode is activated (or the position and yaw where the parameters are changed if it is already activated). + +You can adjust the parameters of the trajectory with the following tool. +Make sure to copy the generated CLI string at the end: + + + +### Real-World + +#### Setup + +The `mc_raptor` module has been mostly tested with the Holybro X500 V2 but it should also work out-of-the-box with other platforms (see the [Other Platforms](#other-platforms) section). + +```sh +make px4_fmu-v6c_raptor upload +``` + +We recommend initially testing the RAPTOR mode using a dead man's switch. +For this we configure the mode selection to be connected to a push button or a switch with a spring that automatically switches back. +In the default position we configure e.g. `Stabilized Mode` and in the pressed configuration we select `External Mode 1` (since the name of the external mode is only transmitted at runtime). +This allows to take off manually and then just trigger the RAPTOR mode for a split-second to see how it behaves. +In our experiments it has been exceptionally stable (zero crashes) but we still think progressively activating it for longer is the safest way to build confidence. + +::: warning +Make sure that your platform uses the standard PX4 quadrotor motor layout: + +1: front-right, 2: back-left, 3: front-left, 4: back-right +::: + +##### Other Platforms + +To enable the `mc_raptor` module in other platforms, just add `CONFIG_MODULES_MC_RAPTOR=y` and `CONFIG_LIB_RL_TOOLS=y` + +```diff ++++ b/boards/px4/fmu-v6c/raptor.px4board +@@ -35,2 +35,3 @@ + CONFIG_DRIVERS_UAVCAN=y ++CONFIG_LIB_RL_TOOLS=y + CONFIG_MODULES_AIRSPEED_SELECTOR=y +@@ -64,2 +65,3 @@ + CONFIG_MODULES_MC_POS_CONTROL=y ++CONFIG_MODULES_MC_RAPTOR=y + CONFIG_MODULES_MC_RATE_CONTROL=y +``` + +#### Results + +Even though there were moderate winds (~ 5 m/s) during the test, we found good figure-eight tracking performance at velocities up to 12 m/s: + +![Lissajous](../../assets/advanced/neural_networks/raptor/results_figure_eight.svg) + +We also tested the linear velocity in a straight line and found that the RAPTOR policy can reliably fly at > 17 m/s (the wind direction was orthogonal to the line): + +![Linear Oscillation](../../assets/advanced/neural_networks/raptor/results_line.svg) + +### Troubleshooting + +#### Logging + +Use this logging configuration to log all relevant topics at maximum rate: + +```sh +cat > logger_topics.txt << EOF +raptor_status 0 +raptor_input 0 +trajectory_setpoint 0 +vehicle_local_position 0 +vehicle_angular_velocity 0 +vehicle_attitude 0 +vehicle_status 0 +actuator_motors 0 +EOF +``` + +Use mavproxy FTP to upload it: + +```sh +mavproxy.py +``` + +##### Real + +```sh +ftp mkdir /fs/microsd/etc +ftp mkdir /fs/microsd/etc/logging +ftp put logger_topics.txt /fs/microsd/etc/logging/logger_topics.txt +``` + +##### SITL + +```sh +ftp mkdir etc +ftp mkdir logging +ftp put logger_topics.txt etc/logging/logger_topics.txt +``` diff --git a/docs/en/advanced/tflm.md b/docs/en/neural_networks/tflm.md similarity index 90% rename from docs/en/advanced/tflm.md rename to docs/en/neural_networks/tflm.md index 2c30ac5216..57b2847867 100644 --- a/docs/en/advanced/tflm.md +++ b/docs/en/neural_networks/tflm.md @@ -1,6 +1,6 @@ # TensorFlow Lite Micro (TFLM) -The PX4 [Multicopter Neural Network](../advanced/neural_networks.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library. +The PX4 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library. This is a mature inference library intended for use on embedded devices, and is hence a suitable choice for PX4. @@ -68,7 +68,7 @@ The `_input_tensor` is also defined, it is fetched from `_control_interpreter->i The `_input_tensor` is filled in the `PopulateInputTensor()` function. `_input_tensor` works by accessing the `->data.f` member array and fill in the required inputs for your network. -The inputs used in the control network is covered in [Neural Networks](../advanced/neural_networks.md). +The inputs used in the control network is covered in [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md). ### Outputs diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 29b538401a..5d1fb157b6 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -257,6 +257,8 @@ set(msg_files versioned/LongitudinalControlConfiguration.msg versioned/ManualControlSetpoint.msg versioned/ModeCompleted.msg + versioned/RaptorInput.msg + versioned/RaptorStatus.msg versioned/RegisterExtComponentReply.msg versioned/RegisterExtComponentRequest.msg versioned/TrajectorySetpoint.msg diff --git a/msg/versioned/RaptorInput.msg b/msg/versioned/RaptorInput.msg new file mode 100644 index 0000000000..4193397137 --- /dev/null +++ b/msg/versioned/RaptorInput.msg @@ -0,0 +1,18 @@ +# Raptor Input + +# The exact inputs to the Raptor foundation policy. +# Having access to the exact inputs helps with debugging and post-hoc analysis. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +bool active # Signals if the policy is active (aka publishing actuator_motors) +float32[3] position # [m] [@frame FLU] Position of the vehicle_local_position frame +float32[4] orientation # [-] Orientation in the vehicle_attitude frame but using the FLU convention as a unit quaternion (w, x, y, z) +float32[3] linear_velocity # [m/s] [@frame FLU] Linear velocity in the vehicle_local_position frame +float32[3] angular_velocity # [rad/s] [@frame FLU] Angular velocity in the body frame +uint8 ACTION_DIM = 4 # Policy output dimensionality (for quadrotors) +float32[4] previous_action # [@range -1, 1] Previous action. Motor commands normalized to [-1, 1] + +# TOPICS raptor_input diff --git a/msg/versioned/RaptorStatus.msg b/msg/versioned/RaptorStatus.msg new file mode 100644 index 0000000000..25801a0020 --- /dev/null +++ b/msg/versioned/RaptorStatus.msg @@ -0,0 +1,46 @@ +# Raptor Status + +# Diagnostic messages for the Raptor foundation policy. +# This diagnostic data is useful for debugging (e.g. identifying missing input information). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +bool subscription_update_angular_velocity # [bool] Flag signalling if the vehicle_angular_velocity was updated +bool subscription_update_local_position # [bool] Flag signalling if the vehicle_local_position was updated +bool subscription_update_attitude # [bool] Flag signalling if the vehicle_attitude was updated +bool subscription_update_trajectory_setpoint # [bool] Flag signalling if the trajectory_setpoint was updated +bool subscription_update_vehicle_status # [bool] Flag signalling if the vehicle_status was updated + +uint8 exit_reason # [enum] Exit reason identifier. Representing conditions that lead to the Raptor policy not being executed +uint8 EXIT_REASON_NONE = 0 # No exit reason => Raptor control step was executed (actuator_motors should have been published) +uint8 EXIT_REASON_NO_ANGULAR_VELOCITY_UPDATE = 1 # We synchronize the control onto the input observation with the highest update frequency, which is vehicle_angular_velocity. If there was no update, we do not need to execute the policy again +uint8 EXIT_REASON_NOT_ALL_OBSERVATIONS_SET = 2 # We can not execute the policy if not all observations are available +uint8 EXIT_REASON_ANGULAR_VELOCITY_STALE = 3 # If OBSERVATION_TIMEOUT_ANGULAR_VELOCITY is exceeded, we treat the vehicle_angular_velocity as stale and can not run the policy +uint8 EXIT_REASON_LOCAL_POSITION_STALE = 4 # If OBSERVATION_TIMEOUT_LOCAL_POSITION is exceeded, we treat the vehicle_local_position as stale and can not run the policy +uint8 EXIT_REASON_ATTITUDE_STALE = 5 # If OBSERVATION_TIMEOUT_ATTITUDE is exceeded, we treat the vehicle_attitude as stale and can not run the policy +uint8 EXIT_REASON_EXECUTOR_STATUS_SOURCE_NOT_CONTROL = 6 # The executor that runs the policy can run in oversampling mode, where it decides if the policy should be ran based on the timestamp and not based on fixed synchronization onto the vehicle_angular_velocity. In this case the executor can decide to skip running the policy if the interval is too small, in which case this flag is set. + +uint32 timestamp_last_vehicle_angular_velocity # [us] Timestamp of the last received vehicle_angular_velocity message +uint32 timestamp_last_vehicle_local_position # [us] Timestamp of the last received vehicle_local_position message +uint32 timestamp_last_vehicle_attitude # [us] Timestamp of the last received vehicle_attitude message +uint32 timestamp_last_trajectory_setpoint # [us] Timestamp of the last received trajectory_setpoint message + +bool vehicle_angular_velocity_stale # [bool] True if vehicle_angular_velocity data is considered stale (exceeded timeout) +bool vehicle_local_position_stale # [bool] True if vehicle_local_position data is considered stale (exceeded timeout) +bool vehicle_attitude_stale # [bool] True if vehicle_attitude data is considered stale (exceeded timeout) +bool trajectory_setpoint_stale # [bool] True if trajectory_setpoint data is considered stale (exceeded timeout) + +bool active # [bool] True if the Raptor policy is currently active (publishing actuator_motors) +uint8 substep # [-] The policy is trained at a fixed frequency (e.g. 100 Hz) but we might want to use it for control at higher frequencies (e.g. 400 Hz), which leads to a number of intermediate steps before the actual policy state is advanced (in this case 4 = 400 Hz / 100 Hz). This field provides the current substep (e.g. 0-3). +float32 control_interval # [s] Time interval between control updates + +float32 trajectory_setpoint_dt_mean # [us] The average trajectory setpoint arrival time interval (since Raptor mode activation within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) +float32 trajectory_setpoint_dt_max # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation and within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) +float32 trajectory_setpoint_dt_max_since_activation # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation) + +float32[3] internal_reference_position # [m] [@frame FLU] Internal reference position +float32[3] internal_reference_linear_velocity # [m/s] [@frame FLU] Internal reference linear velocity + +# TOPICS raptor_status diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index f732ddbef1..33d58ab640 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -68,6 +68,7 @@ add_subdirectory(pure_pursuit EXCLUDE_FROM_ALL) add_subdirectory(rate_control EXCLUDE_FROM_ALL) add_subdirectory(rc EXCLUDE_FROM_ALL) add_subdirectory(ringbuffer EXCLUDE_FROM_ALL) +add_subdirectory(rl_tools EXCLUDE_FROM_ALL) add_subdirectory(rover_control EXCLUDE_FROM_ALL) add_subdirectory(rtl EXCLUDE_FROM_ALL) add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL) diff --git a/src/lib/rl_tools/CMakeLists.txt b/src/lib/rl_tools/CMakeLists.txt new file mode 100644 index 0000000000..83402f2c45 --- /dev/null +++ b/src/lib/rl_tools/CMakeLists.txt @@ -0,0 +1,15 @@ +if(CONFIG_LIB_RL_TOOLS) + px4_add_git_submodule(TARGET git_rl_tools PATH "rl_tools") + add_library(rl_tools INTERFACE) + target_include_directories(rl_tools INTERFACE + ${CMAKE_CURRENT_SOURCE_DIR}/rl_tools/include + ) + + target_compile_features(rl_tools INTERFACE cxx_std_17) + + target_compile_options(rl_tools INTERFACE + -Wno-unused-parameter + -Wno-unused-variable + -Wno-unused-local-typedefs + ) +endif() diff --git a/src/lib/rl_tools/Kconfig b/src/lib/rl_tools/Kconfig new file mode 100644 index 0000000000..8014b02bcf --- /dev/null +++ b/src/lib/rl_tools/Kconfig @@ -0,0 +1,7 @@ +config LIB_RL_TOOLS + bool "RLtools" + default n + ---help--- + RLtools is a header-only library for reinforcement learning and neural networks. + It enables running trained RL policies on embedded devices. + This library is used for running RL-based controllers on the PX4 autopilot. diff --git a/src/lib/rl_tools/rl_tools b/src/lib/rl_tools/rl_tools new file mode 160000 index 0000000000..15940da2a8 --- /dev/null +++ b/src/lib/rl_tools/rl_tools @@ -0,0 +1 @@ +Subproject commit 15940da2a8334d7532c4a5650ee4e09526206414 diff --git a/src/modules/mc_raptor/CHECKLIST.md b/src/modules/mc_raptor/CHECKLIST.md new file mode 100644 index 0000000000..ce2ca6be47 --- /dev/null +++ b/src/modules/mc_raptor/CHECKLIST.md @@ -0,0 +1,3 @@ +# Checklist +1. Check the `REMAP_CRAZYFLIE` flag (this remaps the Crazyflie outputs to the PX4 SIH inputs) +2. Check the `CONTROL_MULTIPLE` setting (this controls how much faster the control loop is than the simulation/step frequency during training. This is needed to aggregate e.g. 4 steps of action history into one step of the policy input) diff --git a/src/modules/mc_raptor/CMakeLists.txt b/src/modules/mc_raptor/CMakeLists.txt new file mode 100644 index 0000000000..5cde791827 --- /dev/null +++ b/src/modules/mc_raptor/CMakeLists.txt @@ -0,0 +1,21 @@ +include(px4_add_library) + +px4_add_git_submodule(TARGET git_raptor_blob PATH "blob") + +px4_add_module( + MODULE modules__mc_raptor + MAIN mc_raptor + STACK_MAIN 4000 + SRCS + mc_raptor.cpp + MODULE_CONFIG + module.yaml + DEPENDS + px4_work_queue + rl_tools + git_raptor_blob + EXTERNAL + ) + +target_compile_features(modules__mc_raptor PRIVATE cxx_std_17) +target_compile_options(modules__mc_raptor PRIVATE -Wno-unused-result) diff --git a/src/modules/mc_raptor/Kconfig b/src/modules/mc_raptor/Kconfig new file mode 100644 index 0000000000..a99c05db70 --- /dev/null +++ b/src/modules/mc_raptor/Kconfig @@ -0,0 +1,12 @@ +menuconfig MODULES_MC_RAPTOR + bool "mc_raptor" + default n + ---help--- + Enable support for mc_raptor + +menuconfig USER_MC_RAPTOR + bool "mc_raptor running as userspace module" + default n + depends on BOARD_PROTECTED && MODULES_MC_RAPTOR + ---help--- + Put mc_raptor in userspace memory diff --git a/src/modules/mc_raptor/README.md b/src/modules/mc_raptor/README.md new file mode 100644 index 0000000000..753187b43e --- /dev/null +++ b/src/modules/mc_raptor/README.md @@ -0,0 +1,116 @@ +# RAPTOR + + +## SITL +#### Standalone Usage (Without External Trajectory Setpoint) +Build PX4 SITL with Raptor, disable QGC requirement, and adjust the `IMU_GYRO_RATEMAX` to match the simulation IMU rate +```bash +make px4_sitl_raptor gz_x500 +param set NAV_DLL_ACT 0 +param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms +param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs +param set MC_RAPTOR_ENABLE 1 +param set MC_RAPTOR_OFFB 0 +param save +``` +Upload the RAPTOR checkpoint to the "SD card": Separate terminal +```bash +mavproxy.py --master udp:127.0.0.1:14540 +ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor +ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar +``` +restart (ctrl+c) +```bash +make px4_sitl_raptor gz_x500 +commander takeoff +commander status +``` + +Note the external mode ID of `RAPTOR` in the status report + +```bash +commander mode ext{RAPTOR_MODE_ID} +``` + + +#### Usage with External Trajectory Setpoint + + +Send Lissajous setpoints via Mavlink: +```bash +pip install px4 +px4 udp:localhost:14540 track lissajous --A 2.0 --B 1.0 --duration 10 --ramp-duration 5 --takeoff 10.0 --iterations 2 +``` + + +## SIH +```bash +make px4_fmu-v6c_raptor upload +``` +In QGroundControl: +- Airframes => SIH Quadrotor X +- Settings => Comm Links => Disable Pixhawk (disable automatic USB serial connection) +```bash +mavproxy.py --master /dev/serial/by-id/usb-Auterion_PX4_FMU_v6C.x_0-if00 --out udp:localhost:14550 --out udp:localhost:13337 --out udp:localhost:13338 +``` +New terminal (optional): +```bash +./Tools/mavlink_shell.py udp:localhost:13338 +``` + +```bash +param set SIH_IXX 0.005 +param set SIH_IYY 0.005 +param set SIH_IZZ 0.010 +param set IMU_GYRO_RATEMAX 400 +param save +reboot +``` + +New terminal: +```bash +./Tools/simulation/jmavsim/jmavsim_run.sh -u -p 13337 -o +``` + + +## Real World +Using a DroneBridge WiFi telemetry @ 1000000 baud (also set `SER_TEL1_BAUD=1000000`) and maximum packet size = 16. It seems like larger maximum packet sizes can lead to delays in forwarding the `SET_POSITION_TARGET_LOCAL_NED` messages to `trajectory_setpoint`. +```bash +./Tools/mavlink_shell.py tcp:192.168.2.1:5760 +``` +```bash +px4 tcp:192.168.2.1:5760 track lissajous --A 0.5 --B 0.5 --duration 10 --ramp-duration 5 --takeoff 1.0 --iterations 2 +``` + + +## Troubleshooting + + +```bash +cat > logger_topics.txt << EOF +raptor_status 0 +raptor_input 0 +trajectory_setpoint 0 +vehicle_local_position 0 +vehicle_angular_velocity 0 +vehicle_attitude 0 +vehicle_status 0 +actuator_motors 0 +EOF +``` +```bash +mavproxy.py +``` +```bash +ftp mkdir /fs/microsd/etc +ftp mkdir /fs/microsd/etc/logging +ftp put logger_topics.txt /fs/microsd/etc/logging/logger_topics.txt +``` + +For SITL: + +```bash +ftp mkdir etc +ftp mkdir logging +ftp put logger_topics.txt etc/logging/logger_topics.txt +``` diff --git a/src/modules/mc_raptor/blob b/src/modules/mc_raptor/blob new file mode 160000 index 0000000000..4f31fc9736 --- /dev/null +++ b/src/modules/mc_raptor/blob @@ -0,0 +1 @@ +Subproject commit 4f31fc97366487e460e44a43054756a085ab6cb7 diff --git a/src/modules/mc_raptor/mc_raptor.cpp b/src/modules/mc_raptor/mc_raptor.cpp new file mode 100644 index 0000000000..4d3f0d486c --- /dev/null +++ b/src/modules/mc_raptor/mc_raptor.cpp @@ -0,0 +1,1077 @@ +#include "mc_raptor.hpp" +#undef OK + +#include +#include + +#include + +Raptor::Raptor(): ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) +{ + // node state + timestamp_last_angular_velocity_set = false; + timestamp_last_local_position_set = false; + timestamp_last_attitude_set = false; + timestamp_last_trajectory_setpoint_set = false; + timestamp_last_vehicle_status_set = false; + previous_trajectory_setpoint_stale = false; + previous_active = false; + timeout_message_sent = false; + timestamp_last_policy_frequency_check_set = false; + last_intermediate_status_set = false; + last_native_status_set = false; + policy_frequency_check_counter = 0; + flightmode_state = FlightModeState::UNREGISTERED; + can_arm = false; + trajectory_setpoint_dt_index = 0; + trajectory_setpoint_dts_full = false; + trajectory_setpoint_invalid_count = 0; + trajectory_setpoint_dt_max_since_reset = 0; + internal_reference_activation_position[0] = 0.0f; + internal_reference_activation_position[1] = 0.0f; + internal_reference_activation_position[2] = 0.0f; + internal_reference_params_changed = false; + + _actuator_motors_pub.advertise(); + _tune_control_pub.advertise(); +} +void Raptor::reset() +{ + + trajectory_setpoint_dt_index = 0; + trajectory_setpoint_dts_full = false; + trajectory_setpoint_invalid_count = 0; + trajectory_setpoint_dt_max_since_reset = 0; + timestamp_last_trajectory_setpoint_set = false; + + + for (TI action_i = 0; action_i < EXECUTOR_SPEC::OUTPUT_DIM; action_i++) { + this->previous_action[action_i] = RESET_PREVIOUS_ACTION_VALUE; + } + + rlt::reset(device, executor, policy, rng); +} + +Raptor::~Raptor() +{ + perf_free(_loop_perf); + perf_free(_loop_interval_perf); +} + +#ifdef MC_RAPTOR_EMBED_POLICY +bool Raptor::test_policy() +{ +#else +bool Raptor::test_policy(FILE *f, TI input_offset, TI output_offset) +{ +#endif + using namespace rl_tools::inference::applications::l2f; +#ifndef RL_TOOLS_DISABLE_TEST + // This tests the policy using a known input output pair that has been saved into the policy checkpoint to verify that it has been loaded correctly + using POLICY = EXECUTOR_CONFIG::POLICY_TEST; + POLICY::template Buffer buffers_test; + POLICY::State policy_state_test; + rl_tools::Tensor, false>> + test_output; + rl_tools::Mode> mode; + using EXAMPLE_INPUT_SPEC = MC_RAPTOR_EXAMPLE_NAMESPACE::input::SPEC; + using EXAMPLE_OUTPUT_SPEC = MC_RAPTOR_EXAMPLE_NAMESPACE::output::SPEC; + float acc = 0; + uint64_t num_values = 0; + rl_tools::inference::applications::l2f::Action action; + + for (TI batch_i = 0; batch_i < EXECUTOR_CONFIG::TEST_BATCH_SIZE_ACTUAL; batch_i++) { + rl_tools::reset(device, policy, policy_state_test, rng); + + for (TI step_i = 0; step_i < EXECUTOR_CONFIG::TEST_SEQUENCE_LENGTH_ACTUAL; step_i++) { +#ifdef MC_RAPTOR_EMBED_POLICY + const auto step_input = rl_tools::view(device, MC_RAPTOR_EXAMPLE_NAMESPACE::input::container, step_i); + const auto batch_input = rl_tools::view_range(device, step_input, batch_i, rlt::tensor::ViewSpec<0, 1> {}); + const auto step_output_target = rl_tools::view(device, MC_RAPTOR_EXAMPLE_NAMESPACE::output::container, step_i); + const auto batch_output_target = rl_tools::view_range(device, step_output_target, batch_i, rlt::tensor::ViewSpec<0, 1> {}); +#else + rl_tools::Tensor, false>> + batch_input; + rl_tools::Tensor, false>> + batch_output_target; + fseek(f, input_offset + (step_i * EXAMPLE_INPUT_SPEC::STRIDE::FIRST + batch_i * EXAMPLE_INPUT_SPEC::STRIDE::template GET<1>)*sizeof( + EXAMPLE_INPUT_SPEC::T), SEEK_SET); + fread(batch_input._data, sizeof(EXAMPLE_INPUT_SPEC::T), EXAMPLE_INPUT_SPEC::SHAPE::LAST, f); + fseek(f, output_offset + (step_i * EXAMPLE_OUTPUT_SPEC::STRIDE::FIRST + batch_i * EXAMPLE_OUTPUT_SPEC::STRIDE::template GET<1>)*sizeof( + EXAMPLE_OUTPUT_SPEC::T), SEEK_SET); + fread(batch_output_target._data, sizeof(EXAMPLE_OUTPUT_SPEC::T), EXAMPLE_OUTPUT_SPEC::SHAPE::LAST, f); +#endif + rl_tools::utils::assert_exit(device, !rl_tools::is_nan(device, batch_input), "input is nan"); + rl_tools::evaluate_step(device, policy, batch_input, policy_state_test, test_output, buffers_test, rng, mode); + rl_tools::utils::assert_exit(device, !rl_tools::is_nan(device, test_output), "output is nan"); + + for (TI action_i = 0; action_i < EXECUTOR_CONFIG::OUTPUT_DIM; action_i++) { + acc += rl_tools::math::abs(device.math, rl_tools::get(device, test_output, 0, action_i) - rl_tools::get(device, batch_output_target, 0, + action_i)); + num_values += 1; + rl_tools::utils::assert_exit(device, !rl_tools::math::is_nan(device.math, acc), "output is nan"); + + if (batch_i == 0 && step_i == EXECUTOR_CONFIG::TEST_SEQUENCE_LENGTH_ACTUAL - 1) { + action.action[action_i] = rl_tools::get(device, test_output, 0, action_i); + } + } + } + } + + float abs_diff = acc / num_values; + PX4_INFO("Checkpoint test diff: %f", (double)abs_diff); + + for (TI output_i = 0; output_i < EXECUTOR_CONFIG::OUTPUT_DIM; output_i++) { + PX4_INFO("output[%d]: %f", (int)output_i, (double)action.action[output_i]); + } + + constexpr float EPSILON = 1e-5; + + bool healthy = abs_diff < EPSILON; + + if (!healthy) { + PX4_ERR("Checkpoint test failed with diff %.10f", (double)abs_diff); + return false; + + } else { + PX4_INFO("Checkpoint test passed with diff %.10f", (double)abs_diff); + return true; + } + +#else + return 0; +#endif +} + +bool Raptor::init() +{ + this->init_time = hrt_absolute_time(); + + if (!_vehicle_angular_velocity_sub.registerCallback()) { + PX4_ERR("vehicle_angular_velocity_sub callback registration failed"); + return false; + } + +#ifndef MC_RAPTOR_EMBED_POLICY + const char *path = PX4_STORAGEDIR "/raptor/policy.tar"; + + struct stat st; + bool file_exists = (stat(path, &st) == 0); + + if (file_exists) { + PX4_INFO("Policy checkpoint %s exists", path); + FILE *f = fopen(path, "rb"); + + if (!f) { + PX4_ERR("Failed to open %s: %s", path, strerror(errno)); + return false; + } + + if (fseek(f, 0, SEEK_END) != 0) { + PX4_ERR("fseek failed: %s", strerror(errno)); + fclose(f); + return false; + } + + long size = ftell(f); + + if (size < 0) { + PX4_ERR("ftell failed: %s", strerror(errno)); + fclose(f); + return false; + + } else { + rewind(f); + bool successfully_loaded = false; + using SPEC = rlt::persist::backends::tar::ReaderGroupSpecification>; + rlt::persist::backends::tar::ReaderGroup reader_group; + reader_group.data.f = f; + reader_group.data.size = size; + auto actor_group = rlt::get_group(device, reader_group, "actor"); + successfully_loaded = rlt::load(device, policy, actor_group); + constexpr TI METADATA_BUFFER_SIZE = 256; + char metadata_buffer[METADATA_BUFFER_SIZE]; + TI read_size = 0; + rlt::persist::backends::tar::get(device, reader_group.data, "actor/meta", metadata_buffer, METADATA_BUFFER_SIZE, read_size); + TI checkpoint_name_position = 0; + TI checkpoint_name_len = 0; + + if (rlt::persist::backends::tar::seek_in_metadata(device, metadata_buffer, METADATA_BUFFER_SIZE, "checkpoint_name", + checkpoint_name_position, checkpoint_name_len)) { + strncpy(checkpoint_name, metadata_buffer + checkpoint_name_position, CHECKPOINT_NAME_LENGTH); + checkpoint_name[checkpoint_name_len < CHECKPOINT_NAME_LENGTH ? checkpoint_name_len : CHECKPOINT_NAME_LENGTH - 1] = '\0'; + + } else { + PX4_ERR("Failed to get checkpoint name from metadata"); + return false; + } + + if (successfully_loaded) { + PX4_INFO("Policy loaded from file %s", path); + TI input_offset = 0; + TI input_size = 0; + rlt::persist::backends::tar::seek(device, reader_group.data, "example/input/data", input_offset, input_size); + PX4_INFO("Input offset: %d", (int)input_offset); + TI output_offset = 0; + TI output_size = 0; + rlt::persist::backends::tar::seek(device, reader_group.data, "example/output/data", output_offset, output_size); + PX4_INFO("Output offset: %d", (int)output_offset); + + if (!test_policy(f, input_offset, output_offset)) { + PX4_ERR("Checkpoint test failed"); + return false; + } + + } else { + PX4_ERR("Failed to load policy from file %s", path); + return false; + } + + fclose(f); + } + + } else { + PX4_INFO("File %s does not exist", path); + return false; + } + +#else + + strncpy(checkpoint_name, MC_RAPTOR_META_NAMESPACE::name, CHECKPOINT_NAME_LENGTH); + + if (!test_policy()) { + PX4_ERR("Checkpoint test failed"); + return false; + } + +#endif + PX4_INFO("Checkpoint name: %s", checkpoint_name); + + + register_ext_component_request_s register_ext_component_request{}; + register_ext_component_request.timestamp = hrt_absolute_time(); + strncpy(register_ext_component_request.name, "RAPTOR", sizeof(register_ext_component_request.name) - 1); + register_ext_component_request.request_id = Raptor::EXT_COMPONENT_REQUEST_ID; + register_ext_component_request.px4_ros2_api_version = 1; + register_ext_component_request.register_arming_check = true; + register_ext_component_request.register_mode = true; + register_ext_component_request.enable_replace_internal_mode = _param_mc_raptor_offboard.get(); + register_ext_component_request.replace_internal_mode = vehicle_status_s::NAVIGATION_STATE_OFFBOARD; + _register_ext_component_request_pub.publish(register_ext_component_request); + + int32_t imu_gyro_ratemax = _param_imu_gyro_ratemax.get(); + + if (imu_gyro_ratemax % POLICY_CONTROL_FREQUENCY_TRAINING != 0) { + PX4_WARN("IMU_GYRO_RATEMAX=%d Hz is not a multiple of the training frequency (%d Hz)", (int)imu_gyro_ratemax, + (int)POLICY_CONTROL_FREQUENCY_TRAINING); + } + + int32_t force_sync_native = imu_gyro_ratemax / POLICY_CONTROL_FREQUENCY_TRAINING; + executor.executor.force_sync_native = force_sync_native; + executor.executor.force_sync_native_initialized = true; + PX4_INFO("IMU_GYRO_RATEMAX=%d Hz", (int)imu_gyro_ratemax); + PX4_INFO("POLICY_CONTROL_FREQUENCY_TRAINING=%d Hz", (int)POLICY_CONTROL_FREQUENCY_TRAINING); + PX4_INFO("Setting force_sync_native = %d Hz / %d Hz = %d", (int)imu_gyro_ratemax, (int)POLICY_CONTROL_FREQUENCY_TRAINING, + (int)force_sync_native); + + this->use_internal_reference = _param_mc_raptor_intref.get(); + + this->reset(); + + return true; +} +template +T clip(T x, T max, T min) +{ + if (x > max) { + return max; + } + + if (x < min) { + return min; + } + + return x; +} +template +void quaternion_multiplication(T q1[4], T q2[4], T q_res[4]) +{ + q_res[0] = q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2] - q1[3] * q2[3]; + q_res[1] = q1[0] * q2[1] + q1[1] * q2[0] + q1[2] * q2[3] - q1[3] * q2[2]; + q_res[2] = q1[0] * q2[2] - q1[1] * q2[3] + q1[2] * q2[0] + q1[3] * q2[1]; + q_res[3] = q1[0] * q2[3] + q1[1] * q2[2] - q1[2] * q2[1] + q1[3] * q2[0]; +} +template +void quaternion_conjugate(T q[4], T q_res[4]) +{ + q_res[0] = +q[0]; + q_res[1] = -q[1]; + q_res[2] = -q[2]; + q_res[3] = -q[3]; +} +template +void quaternion_to_rotation_matrix(T q[4], T R[9]) +{ + // row-major + T qw = q[0]; + T qx = q[1]; + T qy = q[2]; + T qz = q[3]; + + R[0] = 1 - 2 * qy * qy - 2 * qz * qz; + R[1] = 2 * qx * qy - 2 * qw * qz; + R[2] = 2 * qx * qz + 2 * qw * qy; + R[3] = 2 * qx * qy + 2 * qw * qz; + R[4] = 1 - 2 * qx * qx - 2 * qz * qz; + R[5] = 2 * qy * qz - 2 * qw * qx; + R[6] = 2 * qx * qz - 2 * qw * qy; + R[7] = 2 * qy * qz + 2 * qw * qx; + R[8] = 1 - 2 * qx * qx - 2 * qy * qy; +} + +template +void rotate_vector(T R[9], T v[3], T v_rotated[3]) +{ + v_rotated[0] = R[0] * v[0] + R[1] * v[1] + R[2] * v[2]; + v_rotated[1] = R[3] * v[0] + R[4] * v[1] + R[5] * v[2]; + v_rotated[2] = R[6] * v[0] + R[7] * v[1] + R[8] * v[2]; +} + +void Raptor::observe(rl_tools::inference::applications::l2f::Observation &observation) +{ + // converting from FRD to FLU + T Rt_inv[9]; + + { + // Orientation + // FRD to FLU + T q_target[4]; + q_target[0] = cosf(0.5f * _trajectory_setpoint.yaw); // minus because the setpoint yaw is in NED + q_target[1] = 0; + q_target[2] = 0; + q_target[3] = sinf(0.5f * _trajectory_setpoint.yaw); + + T qt[4], qtc[4], qr[4]; + qt[0] = +q_target[0]; // conjugate to build the difference between setpoint and current + qt[1] = +q_target[1]; + qt[2] = -q_target[2]; + qt[3] = -q_target[3]; + quaternion_conjugate(qt, qtc); + quaternion_to_rotation_matrix(qtc, Rt_inv); + + qr[0] = +_vehicle_attitude.q[0]; + qr[1] = +_vehicle_attitude.q[1]; + qr[2] = -_vehicle_attitude.q[2]; + qr[3] = -_vehicle_attitude.q[3]; + // qr = qt * qd + // qd = qt' * qr + T qd[4]; + quaternion_multiplication(qtc, qr, qd); + + observation.orientation[0] = qd[0]; + observation.orientation[1] = qd[1]; + observation.orientation[2] = qd[2]; + observation.orientation[3] = qd[3]; + } + + { + // Position + T p[3], pt[3]; // FLU + p[0] = +(position[0] - _trajectory_setpoint.position[0]); + p[1] = -(position[1] - _trajectory_setpoint.position[1]); + p[2] = -(position[2] - _trajectory_setpoint.position[2]); + rotate_vector(Rt_inv, p, pt); // The position and velocity error are in the target frame + observation.position[0] = clip(pt[0], max_position_error, -max_position_error); + observation.position[1] = clip(pt[1], max_position_error, -max_position_error); + observation.position[2] = clip(pt[2], max_position_error, -max_position_error); + } + { + // Linear Velocity + T v[3], vt[3]; + v[0] = +(linear_velocity[0] - _trajectory_setpoint.velocity[0]); + v[1] = -(linear_velocity[1] - _trajectory_setpoint.velocity[1]); + v[2] = -(linear_velocity[2] - _trajectory_setpoint.velocity[2]); + rotate_vector(Rt_inv, v, vt); + observation.linear_velocity[0] = clip(vt[0], max_velocity_error, -max_velocity_error); + observation.linear_velocity[1] = clip(vt[1], max_velocity_error, -max_velocity_error); + observation.linear_velocity[2] = clip(vt[2], max_velocity_error, -max_velocity_error); + } + { + // Angular Velocity + observation.angular_velocity[0] = +_vehicle_angular_velocity.xyz[0]; + observation.angular_velocity[1] = -_vehicle_angular_velocity.xyz[1]; + observation.angular_velocity[2] = -_vehicle_angular_velocity.xyz[2]; + } + + for (TI action_i = 0; action_i < EXECUTOR_CONFIG::OUTPUT_DIM; action_i++) { + observation.previous_action[action_i] = this->previous_action[action_i]; + } +} + + +void Raptor::updateArmingCheckReply() +{ + if (flightmode_state == FlightModeState::CONFIGURED) { + if (_arming_check_request_sub.updated()) { + arming_check_request_s arming_check_request; + _arming_check_request_sub.copy(&arming_check_request); + arming_check_reply_s arming_check_reply; + arming_check_reply.timestamp = hrt_absolute_time(); + arming_check_reply.request_id = arming_check_request.request_id; + arming_check_reply.registration_id = ext_component_arming_check_id; + arming_check_reply.health_component_index = arming_check_reply.HEALTH_COMPONENT_INDEX_NONE; + arming_check_reply.num_events = 0; + arming_check_reply.can_arm_and_run = can_arm; + arming_check_reply.mode_req_angular_velocity = true; + arming_check_reply.mode_req_local_position = true; + arming_check_reply.mode_req_attitude = true; + arming_check_reply.mode_req_local_alt = true; + arming_check_reply.mode_req_home_position = false; + arming_check_reply.mode_req_mission = false; + arming_check_reply.mode_req_global_position = false; + arming_check_reply.mode_req_prevent_arming = false; + arming_check_reply.mode_req_manual_control = false; + _arming_check_reply_pub.publish(arming_check_reply); + } + } +} + + +void Raptor::Run() +{ + if (should_exit()) { + _vehicle_angular_velocity_sub.unregisterCallback(); + + if (flightmode_state >= FlightModeState::REGISTERED) { + unregister_ext_component_s unregister_ext_component{}; + unregister_ext_component.timestamp = hrt_absolute_time(); + strncpy(unregister_ext_component.name, "RAPTOR", sizeof(unregister_ext_component.name) - 1); + unregister_ext_component.arming_check_id = ext_component_arming_check_id; + unregister_ext_component.mode_id = ext_component_mode_id; + unregister_ext_component.mode_executor_id = -1; + _unregister_ext_component_pub.publish(unregister_ext_component); + } + + ScheduleClear(); + exit_and_cleanup(); + return; + } + + register_ext_component_reply_s register_ext_component_reply; + + if (_register_ext_component_reply_sub.update(®ister_ext_component_reply)) { + if (register_ext_component_reply.request_id == Raptor::EXT_COMPONENT_REQUEST_ID && register_ext_component_reply.success) { + ext_component_arming_check_id = register_ext_component_reply.arming_check_id; + ext_component_mode_id = register_ext_component_reply.mode_id; + flightmode_state = FlightModeState::REGISTERED; + PX4_INFO("Raptor mode registration successful, arming_check_id: %d, mode_id: %d", ext_component_arming_check_id, ext_component_mode_id); + } + } + + if (flightmode_state == FlightModeState::REGISTERED) { + vehicle_control_mode_s config_control_setpoints{}; + config_control_setpoints.timestamp = hrt_absolute_time(); + config_control_setpoints.source_id = ext_component_mode_id; + config_control_setpoints.flag_multicopter_position_control_enabled = false; + config_control_setpoints.flag_control_manual_enabled = false; + config_control_setpoints.flag_control_offboard_enabled = false; + config_control_setpoints.flag_control_position_enabled = false; + config_control_setpoints.flag_control_climb_rate_enabled = false; + config_control_setpoints.flag_control_allocation_enabled = false; + config_control_setpoints.flag_control_termination_enabled = true; + _config_control_setpoints_pub.publish(config_control_setpoints); + flightmode_state = FlightModeState::CONFIGURED; + PX4_INFO("Raptor mode configuration sent"); + } + + + perf_count(_loop_interval_perf); + + perf_begin(_loop_perf); + hrt_abstime current_time = hrt_absolute_time(); + + raptor_status_s status{}; + status.timestamp = current_time; + status.timestamp_sample = current_time; + status.exit_reason = raptor_status_s::EXIT_REASON_NONE; + status.substep = 0; + status.active = false; + status.control_interval = NAN; + status.trajectory_setpoint_dt_mean = NAN; + status.trajectory_setpoint_dt_max = NAN; + status.trajectory_setpoint_dt_max_since_activation = NAN; + + if (trajectory_setpoint_dts_full || trajectory_setpoint_dt_index > 0) { + float trajectory_setpoint_dt_mean = 0; + float trajectory_setpoint_dt_max = 0; + + for (TI i = 0; i < (trajectory_setpoint_dts_full ? NUM_TRAJECTORY_SETPOINT_DTS : trajectory_setpoint_dt_index); i++) { + TI index = trajectory_setpoint_dts_full ? i : trajectory_setpoint_dt_index - 1 - i; + trajectory_setpoint_dt_mean += trajectory_setpoint_dts[index]; + + if (trajectory_setpoint_dts[index] > trajectory_setpoint_dt_max) { + trajectory_setpoint_dt_max = trajectory_setpoint_dts[index]; + } + } + + if (trajectory_setpoint_dt_max > trajectory_setpoint_dt_max_since_reset) { + trajectory_setpoint_dt_max_since_reset = trajectory_setpoint_dt_max; + } + + trajectory_setpoint_dt_mean /= NUM_TRAJECTORY_SETPOINT_DTS; + status.trajectory_setpoint_dt_mean = trajectory_setpoint_dt_mean; + status.trajectory_setpoint_dt_max = trajectory_setpoint_dt_max; + status.trajectory_setpoint_dt_max_since_activation = trajectory_setpoint_dt_max_since_reset; + } + + status.subscription_update_vehicle_status = _vehicle_status_sub.update(&_vehicle_status); + + if (status.subscription_update_vehicle_status) { + timestamp_last_vehicle_status = current_time; + timestamp_last_vehicle_status_set = true; + } + + bool next_active = timestamp_last_vehicle_status_set && _vehicle_status.nav_state == ext_component_mode_id; + + if (!previous_active && next_active) { + this->reset(); + PX4_INFO("Resetting Inference Executor (Recurrent State)"); + + } else { + if (previous_active && !next_active) { + PX4_INFO("inactive"); + } + } + + bool angular_velocity_update = false; + status.subscription_update_angular_velocity = _vehicle_angular_velocity_sub.update(&_vehicle_angular_velocity); + + if (status.subscription_update_angular_velocity) { + timestamp_last_angular_velocity = current_time; + timestamp_last_angular_velocity_set = true; + angular_velocity_update = true; + } + + status.timestamp_last_vehicle_angular_velocity = current_time; + status.timestamp_sample = _vehicle_angular_velocity.timestamp_sample; + + status.subscription_update_local_position = _vehicle_local_position_sub.update(&_vehicle_local_position); + + if (status.subscription_update_local_position) { + timestamp_last_local_position = current_time; + timestamp_last_local_position_set = true; + } + + status.timestamp_last_vehicle_local_position = current_time; + + status.subscription_update_attitude = _vehicle_attitude_sub.update(&_vehicle_attitude); + + if (status.subscription_update_attitude) { + timestamp_last_attitude = current_time; + timestamp_last_attitude_set = true; + } + + status.timestamp_last_vehicle_attitude = timestamp_last_attitude; + + trajectory_setpoint_s temp_trajectory_setpoint; + bool use_external_reference = !use_internal_reference; + status.subscription_update_trajectory_setpoint = use_external_reference && _trajectory_setpoint_sub.update(&temp_trajectory_setpoint); + + if (status.subscription_update_trajectory_setpoint) { + if ( + PX4_ISFINITE(temp_trajectory_setpoint.position[0]) && + PX4_ISFINITE(temp_trajectory_setpoint.position[1]) && + PX4_ISFINITE(temp_trajectory_setpoint.position[2]) && + PX4_ISFINITE(temp_trajectory_setpoint.yaw) && + PX4_ISFINITE(temp_trajectory_setpoint.velocity[0]) && + PX4_ISFINITE(temp_trajectory_setpoint.velocity[1]) && + PX4_ISFINITE(temp_trajectory_setpoint.velocity[2]) && + PX4_ISFINITE(temp_trajectory_setpoint.yawspeed) + ) { + if (timestamp_last_trajectory_setpoint_set) { + trajectory_setpoint_dts[trajectory_setpoint_dt_index] = current_time - timestamp_last_trajectory_setpoint; + trajectory_setpoint_dt_index++; + + if (trajectory_setpoint_dt_index == NUM_TRAJECTORY_SETPOINT_DTS) { + if (next_active && !trajectory_setpoint_dts_full) { + PX4_INFO("trajectory_setpoint_dts_full"); + } + + trajectory_setpoint_dts_full = true; + trajectory_setpoint_dt_index = 0; + } + } + + timestamp_last_trajectory_setpoint_set = true; + status.timestamp_last_trajectory_setpoint = current_time; + timestamp_last_trajectory_setpoint = current_time; + _trajectory_setpoint = temp_trajectory_setpoint; + + } else { + trajectory_setpoint_invalid_count++; + + if (next_active && trajectory_setpoint_invalid_count % TRAJECTORY_SETPOINT_INVALID_COUNT_WARNING_INTERVAL == 0) { + PX4_WARN("trajectory_setpoint invalid, count: %d", (int)trajectory_setpoint_invalid_count); + } + } + } + + constexpr bool PUBLISH_NON_COMPLETE_STATUS = true; + + if (!angular_velocity_update) { + status.exit_reason = raptor_status_s::EXIT_REASON_NO_ANGULAR_VELOCITY_UPDATE; + + if constexpr(PUBLISH_NON_COMPLETE_STATUS) { + _raptor_status_pub.publish(status); + } + + updateArmingCheckReply(); + return; + } + + if (!timestamp_last_angular_velocity_set || !timestamp_last_local_position_set || !timestamp_last_attitude_set) { + status.exit_reason = raptor_status_s::EXIT_REASON_NOT_ALL_OBSERVATIONS_SET; + status.vehicle_angular_velocity_stale = !timestamp_last_angular_velocity_set; + status.vehicle_local_position_stale = !timestamp_last_local_position_set; + status.vehicle_attitude_stale = !timestamp_last_attitude_set; + + if constexpr(PUBLISH_NON_COMPLETE_STATUS) { + _raptor_status_pub.publish(status); + } + + can_arm = false; + updateArmingCheckReply(); + return; + } + + if ((current_time - timestamp_last_angular_velocity) > OBSERVATION_TIMEOUT_ANGULAR_VELOCITY) { + status.exit_reason = raptor_status_s::EXIT_REASON_ANGULAR_VELOCITY_STALE; + + if constexpr(PUBLISH_NON_COMPLETE_STATUS) { + _raptor_status_pub.publish(status); + } + + if (!timeout_message_sent) { + PX4_ERR("angular velocity timeout"); + timeout_message_sent = true; + } + + can_arm = false; + updateArmingCheckReply(); + return; + } + + if ((current_time - timestamp_last_local_position) > OBSERVATION_TIMEOUT_LOCAL_POSITION) { + status.exit_reason = raptor_status_s::EXIT_REASON_LOCAL_POSITION_STALE; + + if constexpr(PUBLISH_NON_COMPLETE_STATUS) { + _raptor_status_pub.publish(status); + } + + if (!timeout_message_sent) { + PX4_ERR("local position timeout"); + timeout_message_sent = true; + } + + can_arm = false; + updateArmingCheckReply(); + return; + + } else { + position[0] = _vehicle_local_position.x; + position[1] = _vehicle_local_position.y; + position[2] = _vehicle_local_position.z; + linear_velocity[0] = _vehicle_local_position.vx; + linear_velocity[1] = _vehicle_local_position.vy; + linear_velocity[2] = _vehicle_local_position.vz; + } + + // position and linear_velocity are guaranteed to be set after this point + auto previous_internal_reference = internal_reference; + internal_reference = static_cast(_param_mc_raptor_intref.get()); + bool internal_reference_changed = previous_internal_reference != internal_reference; + + if (internal_reference_changed) { + PX4_INFO("internal reference changed from %d to %d", (int)previous_internal_reference, (int)internal_reference); + } + + if (use_internal_reference && internal_reference != InternalReference::NONE) { + if (next_active && (!previous_active || internal_reference_changed || internal_reference_params_changed)) { + internal_reference_activation_position[0] = position[0]; + internal_reference_activation_position[1] = - position[1]; + internal_reference_activation_position[2] = - position[2]; + internal_reference_activation_orientation[0] = _vehicle_attitude.q[0]; + internal_reference_activation_orientation[1] = _vehicle_attitude.q[1]; + internal_reference_activation_orientation[2] = -_vehicle_attitude.q[2]; + internal_reference_activation_orientation[3] = -_vehicle_attitude.q[3]; + internal_reference_activation_time = current_time; + PX4_INFO("internal reference activated at: %f %f %f", (double)internal_reference_activation_position[0], + (double)internal_reference_activation_position[1], (double)internal_reference_activation_position[2]); + internal_reference_params_changed = false; + } + + Setpoint setpoint{}; + + if (internal_reference == InternalReference::LISSAJOUS) { + setpoint = lissajous(static_cast(current_time - internal_reference_activation_time) / 1000000, lissajous_params); + + } else { + PX4_ERR("internal reference type not supported"); + } + + auto &q = internal_reference_activation_orientation; + matrix::Quatf q_activation_frame(q[0], q[1], q[2], q[3]); + matrix::Vector3f position_activation_frame = q_activation_frame.rotateVector(matrix::Vector3f(setpoint.position[0], setpoint.position[1], + setpoint.position[2])); + matrix::Vector3f linear_velocity_activation_frame = q_activation_frame.rotateVector(matrix::Vector3f(setpoint.linear_velocity[0], + setpoint.linear_velocity[1], setpoint.linear_velocity[2])); + + _trajectory_setpoint.position[0] = +(internal_reference_activation_position[0] + position_activation_frame(0)); + _trajectory_setpoint.position[1] = -(internal_reference_activation_position[1] + position_activation_frame(1)); + _trajectory_setpoint.position[2] = -(internal_reference_activation_position[2] + position_activation_frame(2)); + _trajectory_setpoint.yaw = - atan2f(2.0f * (q[1] * q[2] + q[0] * q[3]), 1.0f - 2.0f * (q[2] * q[2] + q[3] * q[3])) - setpoint.yaw; + _trajectory_setpoint.velocity[0] = +linear_velocity_activation_frame(0); + _trajectory_setpoint.velocity[1] = -linear_velocity_activation_frame(1); + _trajectory_setpoint.velocity[2] = -linear_velocity_activation_frame(2); + _trajectory_setpoint.yawspeed = -setpoint.yaw_rate; + timestamp_last_trajectory_setpoint_set = true; + status.timestamp_last_trajectory_setpoint = current_time; + timestamp_last_trajectory_setpoint = current_time; + + status.internal_reference_position[0] = _trajectory_setpoint.position[0]; + status.internal_reference_position[1] = _trajectory_setpoint.position[1]; + status.internal_reference_position[2] = _trajectory_setpoint.position[2]; + status.internal_reference_linear_velocity[0] = _trajectory_setpoint.velocity[0]; + status.internal_reference_linear_velocity[1] = _trajectory_setpoint.velocity[1]; + status.internal_reference_linear_velocity[2] = _trajectory_setpoint.velocity[2]; + } + + if ((current_time - timestamp_last_attitude) > OBSERVATION_TIMEOUT_ATTITUDE) { + status.exit_reason = raptor_status_s::EXIT_REASON_ATTITUDE_STALE; + + if constexpr(PUBLISH_NON_COMPLETE_STATUS) { + _raptor_status_pub.publish(status); + } + + if (!timeout_message_sent) { + PX4_ERR("attitude timeout"); + timeout_message_sent = true; + } + + can_arm = false; + updateArmingCheckReply(); + return; + } + + timeout_message_sent = false; + + // is ready to control at this point + can_arm = true; + updateArmingCheckReply(); + + if (!timestamp_last_trajectory_setpoint_set || use_internal_reference + || (current_time - timestamp_last_trajectory_setpoint) > TRAJECTORY_SETPOINT_TIMEOUT) { + status.trajectory_setpoint_stale = true; + + if (!previous_trajectory_setpoint_stale || (!previous_active && next_active)) { + _trajectory_setpoint.position[0] = position[0]; + _trajectory_setpoint.position[1] = position[1]; + _trajectory_setpoint.position[2] = position[2]; + auto &q = _vehicle_attitude.q; + _trajectory_setpoint.yaw = atan2f(2.0f * (q[1] * q[2] + q[0] * q[3]), 1.0f - 2.0f * (q[2] * q[2] + q[3] * q[3])); + _trajectory_setpoint.velocity[0] = 0; + _trajectory_setpoint.velocity[1] = 0; + _trajectory_setpoint.velocity[2] = 0; + _trajectory_setpoint.yawspeed = 0; + + if (!previous_trajectory_setpoint_stale) { + PX4_WARN("trajectory_setpoint turned stale at: %f %f %f, yaw: %f %llu / %llu us", (double)position[0], (double)position[1], + (double)position[2], + (double)_trajectory_setpoint.yaw, (unsigned long long)(current_time - timestamp_last_trajectory_setpoint), + (unsigned long long)(TRAJECTORY_SETPOINT_TIMEOUT)); + + } else { + PX4_WARN("trajectory_setpoint reset due to activation at: %f %f %f, yaw: %f", (double)position[0], (double)position[1], (double)position[2], + (double)_trajectory_setpoint.yaw); + } + } + + previous_trajectory_setpoint_stale = true; + + } else { + if (previous_trajectory_setpoint_stale) { + PX4_WARN("trajectory_setpoint turned non-stale at: %f %f %f", (double)position[0], (double)position[1], (double)position[2]); + previous_trajectory_setpoint_stale = false; + } + + status.trajectory_setpoint_stale = false; + } + + + + + + rl_tools::inference::applications::l2f::Observation observation; + rl_tools::inference::applications::l2f::Action action; + observe(observation); + hrt_abstime nanoseconds = current_time * 1000; + auto executor_status = rl_tools::control(device, executor, nanoseconds, policy, observation, action, rng); + + if (!executor_status.OK) { + if (executor_status.TIMESTAMP_INVALID) { + PX4_ERR("RLtools executor error: Timestamp invalid"); + } + + if (executor_status.LAST_CONTROL_TIMESTAMP_GREATER_THAN_LAST_OBSERVATION_TIMESTAMP) { + PX4_ERR("RLtools executor error: Last control timestamp %llu greater than last observation timestamp %llu", + (unsigned long long)executor.executor.last_control_timestamp, (unsigned long long)executor.executor.last_observation_timestamp); + } + } + + if (executor_status.source != decltype(executor_status.source)::CONTROL) { + // status.exit_reason = raptor_status_s::EXIT_REASON_EXECUTOR_STATUS_SOURCE_NOT_CONTROL; + // if constexpr(PUBLISH_NON_COMPLETE_STATUS){ + // _raptor_status_pub.publish(status); + // } + // Exit early if it is not time to control + return; + } + + + status.active = next_active; + + + // no return after this point! + + raptor_input_s input_msg; + input_msg.active = status.active; + static_assert(raptor_input_s::ACTION_DIM == EXECUTOR_CONFIG::OUTPUT_DIM); + input_msg.timestamp = current_time; + input_msg.timestamp_sample = _vehicle_angular_velocity.timestamp_sample; + + for (TI dim_i = 0; dim_i < 3; dim_i++) { + input_msg.position[dim_i] = observation.position[dim_i]; + input_msg.orientation[dim_i] = observation.orientation[dim_i]; + input_msg.linear_velocity[dim_i] = observation.linear_velocity[dim_i]; + input_msg.angular_velocity[dim_i] = observation.angular_velocity[dim_i]; + } + + input_msg.orientation[3] = observation.orientation[3]; + + for (TI dim_i = 0; dim_i < EXECUTOR_CONFIG::OUTPUT_DIM; dim_i++) { + input_msg.previous_action[dim_i] = observation.previous_action[dim_i]; + } + + _raptor_input_pub.publish(input_msg); + _raptor_status_pub.publish(status); + + actuator_motors_s actuator_motors{}; + actuator_motors.timestamp = hrt_absolute_time(); + actuator_motors.timestamp_sample = _vehicle_angular_velocity.timestamp_sample; + + for (TI action_i = 0; action_i < actuator_motors_s::NUM_CONTROLS; action_i++) { + if (action_i < EXECUTOR_CONFIG::OUTPUT_DIM) { + T value = action.action[action_i]; + this->previous_action[action_i] = value; + value = (value + 1) / 2; + constexpr T training_min = 0; + constexpr T training_max = 1.0; + T scaled_value = (training_max - training_min) * value + training_min; + actuator_motors.control[action_i] = scaled_value; + + } else { + actuator_motors.control[action_i] = NAN; + } + } + + if constexpr(Raptor::REMAP_FROM_CRAZYFLIE) { + actuator_motors_s temp = actuator_motors; + temp.control[0] = actuator_motors.control[0]; + temp.control[1] = actuator_motors.control[2]; + temp.control[2] = actuator_motors.control[3]; + temp.control[3] = actuator_motors.control[1]; + actuator_motors = temp; + } + + if (status.active) { + _actuator_motors_pub.publish(actuator_motors); + } + + perf_end(_loop_perf); + previous_active = next_active; + + if (executor_status.source == decltype(executor_status.source)::CONTROL) { + if (executor_status.step_type == decltype(executor_status.step_type)::INTERMEDIATE) { + this->last_intermediate_status = executor_status; + this->last_intermediate_status_set = true; + + } else if (executor_status.step_type == decltype(executor_status.step_type)::NATIVE) { + this->last_native_status = executor_status; + this->last_native_status_set = true; + } + } + + if (!this->timestamp_last_policy_frequency_check_set + || (current_time - timestamp_last_policy_frequency_check) > POLICY_FREQUENCY_CHECK_INTERVAL) { + if (this->timestamp_last_policy_frequency_check_set) { + if (last_intermediate_status_set) { + if (!this->last_intermediate_status.timing_bias.OK || !this->last_intermediate_status.timing_jitter.OK) { + PX4_WARN("Raptor: INTERMEDIATE: BIAS %fx JITTER %fx", (double)this->last_intermediate_status.timing_bias.MAGNITUDE, + (double)this->last_intermediate_status.timing_jitter.MAGNITUDE); + + } else { + if (ENABLE_CONTROL_FREQUENCY_INFO && this->policy_frequency_check_counter % POLICY_FREQUENCY_INFO_INTERVAL == 0) { + PX4_INFO("Raptor: INTERMEDIATE: BIAS %fx JITTER %fx", (double)this->last_intermediate_status.timing_bias.MAGNITUDE, + (double)this->last_intermediate_status.timing_jitter.MAGNITUDE); + } + } + } + + if (last_native_status_set) { + if (!this->last_native_status.timing_bias.OK || !this->last_native_status.timing_jitter.OK) { + PX4_WARN("Raptor: NATIVE: BIAS %fx JITTER %fx", (double)this->last_native_status.timing_bias.MAGNITUDE, + (double)this->last_native_status.timing_jitter.MAGNITUDE); + + } else { + if (ENABLE_CONTROL_FREQUENCY_INFO && this->policy_frequency_check_counter % POLICY_FREQUENCY_INFO_INTERVAL == 0) { + PX4_INFO("Raptor: NATIVE: BIAS %fx JITTER %fx", (double)this->last_native_status.timing_bias.MAGNITUDE, + (double)this->last_native_status.timing_jitter.MAGNITUDE); + } + } + } + } + + this->num_healthy_executor_statii_intermediate = 0; + this->num_non_healthy_executor_statii_intermediate = 0; + this->num_healthy_executor_statii_native = 0; + this->num_non_healthy_executor_statii_native = 0; + this->num_statii = 0; + this->timestamp_last_policy_frequency_check = current_time; + this->timestamp_last_policy_frequency_check_set = true; + this->policy_frequency_check_counter++; + } + + this->num_statii++; + this->num_healthy_executor_statii_intermediate += executor_status.OK && executor_status.source == decltype(executor_status.source)::CONTROL + && executor_status.step_type == decltype(executor_status.step_type)::INTERMEDIATE; + this->num_non_healthy_executor_statii_intermediate += (!executor_status.OK) + && executor_status.source == decltype(executor_status.source)::CONTROL + && executor_status.step_type == decltype(executor_status.step_type)::INTERMEDIATE; + this->num_healthy_executor_statii_native += executor_status.OK && executor_status.source == decltype(executor_status.source)::CONTROL + && executor_status.step_type == decltype(executor_status.step_type)::NATIVE; + this->num_non_healthy_executor_statii_native += (!executor_status.OK) + && executor_status.source == decltype(executor_status.source)::CONTROL + && executor_status.step_type == decltype(executor_status.step_type)::NATIVE; +} + +int Raptor::task_spawn(int argc, char *argv[]) +{ + Raptor *instance = new Raptor(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + if (instance->init()) { + return PX4_OK; + } + + } else { + PX4_ERR("alloc failed"); + } + + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; +} + +int Raptor::print_status() +{ + perf_print_counter(_loop_perf); + perf_print_counter(_loop_interval_perf); + perf_print_counter(_loop_interval_policy_perf); + PX4_INFO_RAW("Checkpoint: %s\n", checkpoint_name); + return 0; +} + +int Raptor::custom_command(int argc, char *argv[]) +{ + if (argc >= 2 && strcmp(argv[0], "intref") == 0) { + if (strcmp(argv[1], "lissajous") == 0) { + // Usage: mc_raptor intref lissajous + if (argc != 10) { + PX4_ERR("Usage: mc_raptor intref lissajous "); + return PX4_ERROR; + } + + Raptor *instance = get_instance(); + + if (instance == nullptr) { + PX4_ERR("mc_raptor is not running"); + return PX4_ERROR; + } + + instance->lissajous_params.A = strtof(argv[2], nullptr); + instance->lissajous_params.B = strtof(argv[3], nullptr); + instance->lissajous_params.C = strtof(argv[4], nullptr); + instance->lissajous_params.a = strtof(argv[5], nullptr); + instance->lissajous_params.b = strtof(argv[6], nullptr); + instance->lissajous_params.c = strtof(argv[7], nullptr); + instance->lissajous_params.duration = strtof(argv[8], nullptr); + instance->lissajous_params.ramp_duration = strtof(argv[9], nullptr); + instance->internal_reference_params_changed = true; + + PX4_INFO("Lissajous params set: A=%.2f B=%.2f C=%.2f fa=%.2f fb=%.2f fc=%.2f duration=%.2f ramp=%.2f \n", + (double)instance->lissajous_params.A, + (double)instance->lissajous_params.B, + (double)instance->lissajous_params.C, + (double)instance->lissajous_params.a, + (double)instance->lissajous_params.b, + (double)instance->lissajous_params.c, + (double)instance->lissajous_params.duration, + (double)instance->lissajous_params.ramp_duration); + + + return PX4_OK; + } + } + + return print_usage("unknown command"); +} + +int Raptor::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +RAPTOR Policy Flight Mode + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("mc_raptor", "template"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_COMMAND_DESCR("intref", "Modify internal reference"); + PRINT_MODULE_USAGE_ARG("lissajous", "Set Lissajous trajectory parameters", false); + PRINT_MODULE_USAGE_ARG("", "Amplitude X [m]", false); + PRINT_MODULE_USAGE_ARG("", "Amplitude Y [m]", false); + PRINT_MODULE_USAGE_ARG("", "Amplitude Z [m]", false); + PRINT_MODULE_USAGE_ARG("", "Frequency a", false); + PRINT_MODULE_USAGE_ARG("", "Frequency b", false); + PRINT_MODULE_USAGE_ARG("", "Frequency c", false); + PRINT_MODULE_USAGE_ARG("", "Total duration [s]", false); + PRINT_MODULE_USAGE_ARG("", "Ramp duration [s]", false); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int mc_raptor_main(int argc, char *argv[]) +{ + return Raptor::main(argc, argv); +} diff --git a/src/modules/mc_raptor/mc_raptor.hpp b/src/modules/mc_raptor/mc_raptor.hpp new file mode 100644 index 0000000000..0ffb8e6d01 --- /dev/null +++ b/src/modules/mc_raptor/mc_raptor.hpp @@ -0,0 +1,283 @@ +#pragma once + +#include "trajectories/lissajous.hpp" + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#undef OK + +#ifdef __PX4_POSIX +#include +#else +#include +#endif + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "blob/policy.h" + +#include +#include +#include +#include +#include + +namespace rlt = rl_tools; + +#define MC_RAPTOR_POLICY_NAMESPACE rlt::checkpoint::actor +#define MC_RAPTOR_EXAMPLE_NAMESPACE rlt::checkpoint::example +#define MC_RAPTOR_META_NAMESPACE rlt::checkpoint::meta +// #define MC_RAPTOR_EMBED_POLICY // you can use this to directly embed the policy into the firmware instead of loading it from the sd card. To fit into the flash you might need to disable some unnecessary features in the .px4board config. + + + + + +using namespace time_literals; + +class Raptor : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + Raptor(); + ~Raptor() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + bool init(); + + int print_status() override; + +private: +#ifdef __PX4_POSIX + using DEVICE = rlt::devices::DefaultCPU; +#else + using DEV_SPEC = rlt::devices::DefaultARMSpecification; + using DEVICE = rlt::devices::arm::OPT; +#endif + using TI = typename DEVICE::index_t; + using RNG = DEVICE::SPEC::RANDOM::ENGINE<>; + using T = float; + static constexpr uint64_t EXT_COMPONENT_REQUEST_ID = 1337; + DEVICE device; + RNG rng; + hrt_abstime init_time; + // node constants + static constexpr TI OBSERVATION_TIMEOUT_ANGULAR_VELOCITY = 10 * 1000; + static constexpr TI OBSERVATION_TIMEOUT_LOCAL_POSITION = 100 * 1000; + static constexpr TI OBSERVATION_TIMEOUT_ATTITUDE = 50 * 1000; + static constexpr TI TRAJECTORY_SETPOINT_TIMEOUT = 200 * 1000; + static constexpr T RESET_PREVIOUS_ACTION_VALUE = 0; // -1 to 1 + static constexpr bool ENABLE_CONTROL_FREQUENCY_INFO = false; + + T max_position_error = 0.5; + T max_velocity_error = 1.0; + + void Run() override; + + decltype(register_ext_component_reply_s::mode_id) ext_component_mode_id; + decltype(register_ext_component_reply_s::arming_check_id) ext_component_arming_check_id; + + enum class FlightModeState : TI { + UNREGISTERED = 0, + REGISTERED = 1, + CONFIGURED = 2 + }; + FlightModeState flightmode_state = FlightModeState::UNREGISTERED; + bool can_arm = false; + void updateArmingCheckReply(); + + // node state + vehicle_local_position_s _vehicle_local_position{}; + vehicle_angular_velocity_s _vehicle_angular_velocity{}; + vehicle_attitude_s _vehicle_attitude{}; + vehicle_status_s _vehicle_status{}; + trajectory_setpoint_s _trajectory_setpoint{}; + hrt_abstime timestamp_last_local_position, timestamp_last_angular_velocity, timestamp_last_attitude, timestamp_last_trajectory_setpoint, + timestamp_last_manual_control_input, timestamp_last_vehicle_status; + bool timestamp_last_local_position_set = false, timestamp_last_angular_velocity_set = false, timestamp_last_attitude_set = false, + timestamp_last_trajectory_setpoint_set = false, timestamp_last_manual_control_input_set = false, timestamp_last_vehicle_status_set = false; + bool timeout_message_sent = false; + bool previous_trajectory_setpoint_stale = false; + bool previous_active = false; + + T position[3]; + T linear_velocity[3]; + + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _register_ext_component_reply_sub{ORB_ID(register_ext_component_reply)}; + uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; + uORB::Subscription _arming_check_request_sub{ORB_ID(arming_check_request)}; + uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)}; + uORB::Publication _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _raptor_status_pub{ORB_ID(raptor_status)}; + uORB::Publication _raptor_input_pub{ORB_ID(raptor_input)}; + uORB::Publication _tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication _register_ext_component_request_pub{ORB_ID(register_ext_component_request)}; + uORB::Publication _unregister_ext_component_pub{ORB_ID(unregister_ext_component)}; + uORB::Publication _config_control_setpoints_pub{ORB_ID(config_control_setpoints)}; + uORB::Publication _arming_check_reply_pub{ORB_ID(arming_check_reply)}; + // Performance (perf) counters + perf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; + perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": interval")}; + perf_counter_t _loop_interval_policy_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": interval_policy")}; + + struct EXECUTOR_CONFIG { + static constexpr TI ACTION_HISTORY_LENGTH = 1; + static constexpr TI CONTROL_INTERVAL_INTERMEDIATE_NS = 2.5 * 1000 * 1000; // Inference is at 500hz + static constexpr TI CONTROL_INTERVAL_NATIVE_NS = 10 * 1000 * 1000; // Training is 100hz + static constexpr TI TIMING_STATS_NUM_STEPS = 100; + static constexpr bool FORCE_SYNC_INTERMEDIATE = true; + static constexpr bool FORCE_SYNC_NATIVE_RUNTIME = true; + static constexpr TI FORCE_SYNC_NATIVE = 8; + static constexpr bool DYNAMIC_ALLOCATION = false; + + using ACTOR_TYPE_ORIGINAL = MC_RAPTOR_POLICY_NAMESPACE ::TYPE; + using POLICY_TEST = MC_RAPTOR_POLICY_NAMESPACE ::TYPE::template CHANGE_BATCH_SIZE::template CHANGE_SEQUENCE_LENGTH; + using POLICY_BATCH_SIZE = ACTOR_TYPE_ORIGINAL::template CHANGE_BATCH_SIZE; +#ifdef MC_RAPTOR_EMBED_POLICY + using POLICY = POLICY_BATCH_SIZE; +#else + using POLICY = POLICY_BATCH_SIZE::template CHANGE_CAPABILITY>; +#endif + using TYPE_POLICY = typename POLICY::TYPE_POLICY; + +#if defined(__PX4_POSIX) + // Relax warning levels for Gazebo sitl. Because Gazebo SITL runs at 250Hz IMU rate, it is not a clean multiple of the training frequency (100hz), hence if the thresholds are set too strict, warnings will be triggered all the time. Generally, Raptor is quite robuts agains control frequency deviations. + struct WARNING_LEVELS: rlt::inference::executor::WarningLevelsDefault { + using T = typename TYPE_POLICY::DEFAULT; + static constexpr T INTERMEDIATE_TIMING_JITTER_HIGH_THRESHOLD = 2.0; + static constexpr T INTERMEDIATE_TIMING_JITTER_LOW_THRESHOLD = 0.5; + static constexpr T INTERMEDIATE_TIMING_BIAS_HIGH_THRESHOLD = 2.0; + static constexpr T INTERMEDIATE_TIMING_BIAS_LOW_THRESHOLD = 0.5; + static constexpr T NATIVE_TIMING_JITTER_HIGH_THRESHOLD = 2.0; + static constexpr T NATIVE_TIMING_JITTER_LOW_THRESHOLD = 0.5; + static constexpr T NATIVE_TIMING_BIAS_HIGH_THRESHOLD = 2.0; + static constexpr T NATIVE_TIMING_BIAS_LOW_THRESHOLD = 0.5; + }; +#else + struct WARNING_LEVELS: rlt::inference::executor::WarningLevelsDefault { + using T = typename TYPE_POLICY::DEFAULT; + static constexpr T NATIVE_TIMING_JITTER_HIGH_THRESHOLD = 1.5; + static constexpr T NATIVE_TIMING_JITTER_LOW_THRESHOLD = 0.5; + }; +#endif + using TIMESTAMP = hrt_abstime; + static constexpr TI OUTPUT_DIM = 4; + static constexpr TI TEST_SEQUENCE_LENGTH_ACTUAL = 5; + static constexpr TI TEST_BATCH_SIZE_ACTUAL = 2; + + using EXECUTOR_SPEC = + rl_tools::inference::applications::l2f::Specification; + using EXECUTOR_STATUS = rlt::inference::executor::Status; + }; + using EXECUTOR_SPEC = EXECUTOR_CONFIG::EXECUTOR_SPEC; + rl_tools::inference::applications::L2F executor; +#ifdef MC_RAPTOR_EMBED_POLICY + const decltype(MC_RAPTOR_POLICY_NAMESPACE ::module) &policy = MC_RAPTOR_POLICY_NAMESPACE::module; +#else + EXECUTOR_CONFIG::POLICY policy; +#endif + static constexpr TI CHECKPOINT_NAME_LENGTH = 100; + char checkpoint_name[CHECKPOINT_NAME_LENGTH] = "n/a"; + +#ifdef MC_RAPTOR_EMBED_POLICY + bool test_policy(); +#else + bool test_policy(FILE *f, TI input_offset, TI output_offset); +#endif + + void reset(); + void observe(rl_tools::inference::applications::l2f::Observation &observation); + + static constexpr bool REMAP_FROM_CRAZYFLIE = + true; // Policy (Crazyflie assignment) => Quadrotor (PX4 Quadrotor X assignment) PX4 SIH assumes the Quadrotor X configuration, which assumes different rotor positions than the crazyflie mapping (from crazyflie outputs to PX4): 1=>1, 2=>4, 3=>2, 4=>3 + // controller state + + // messaging state + static constexpr TI POLICY_INTERVAL_WARNING_THRESHOLD = 100; // us + static constexpr TI POLICY_FREQUENCY_CHECK_INTERVAL = 1000 * 1000; // 1s + static constexpr TI POLICY_FREQUENCY_INFO_INTERVAL = 10; // 10 x POLICY_FREQUENCY_CHECK_INTERVAL = 10x + static constexpr TI POLICY_CONTROL_FREQUENCY_TRAINING = 100; + + TI num_statii; + TI num_healthy_executor_statii_intermediate, num_non_healthy_executor_statii_intermediate, num_healthy_executor_statii_native, + num_non_healthy_executor_statii_native; + EXECUTOR_CONFIG::EXECUTOR_STATUS last_intermediate_status, last_native_status; + bool last_intermediate_status_set, last_native_status_set; + + TI policy_frequency_check_counter; + hrt_abstime timestamp_last_policy_frequency_check; + bool timestamp_last_policy_frequency_check_set = false; + + static constexpr TI NUM_TRAJECTORY_SETPOINT_DTS = 100; + int32_t trajectory_setpoint_dts[NUM_TRAJECTORY_SETPOINT_DTS]; + TI trajectory_setpoint_dt_index = 0; + TI trajectory_setpoint_dt_max_since_reset = 0; + bool trajectory_setpoint_dts_full = false; + + static constexpr TI TRAJECTORY_SETPOINT_INVALID_COUNT_WARNING_INTERVAL = 100; + TI trajectory_setpoint_invalid_count = 0; + + float previous_action[EXECUTOR_SPEC::OUTPUT_DIM]; + bool use_internal_reference = false; + bool internal_reference_params_changed = false; + T internal_reference_activation_position[3]; + T internal_reference_activation_orientation[4]; + hrt_abstime internal_reference_activation_time; + enum class InternalReference : TI { // make sure this corresponds to the enum values for MC_RAPTOR_INTREF in module.yaml + NONE = 0, + LISSAJOUS = 1 + }; + InternalReference internal_reference = InternalReference::NONE; + LissajousParameters lissajous_params{}; // Set via 'mc_raptor intref lissajous ...' command + DEFINE_PARAMETERS( + (ParamInt) _param_imu_gyro_ratemax, + (ParamBool) _param_mc_raptor_offboard, + (ParamInt) _param_mc_raptor_intref + ) + + +}; diff --git a/src/modules/mc_raptor/module.yaml b/src/modules/mc_raptor/module.yaml new file mode 100644 index 0000000000..ff036b05ea --- /dev/null +++ b/src/modules/mc_raptor/module.yaml @@ -0,0 +1,43 @@ +module_name: mc_raptor +parameters: + - group: Multicopter Raptor + definitions: + MC_RAPTOR_ENABLE: + description: + short: Enable Raptor flight mode + long: | + When enabled, the Raptor flight mode will be available. Please set MC_RAPTOR_OFFB according to your use case. + type: boolean + default: false + category: System + MC_RAPTOR_VERBOS: + description: + short: Enable verbose output + long: | + When enabled, the Raptor flight mode will print verbose output to the console. + type: boolean + default: false + category: System + + MC_RAPTOR_OFFB: + description: + short: Enable Offboard mode replacement + long: | + When enabled, the Raptor mode will replace the Offboard mode. + If disabled, the Raptor mode will be available as a separate external mode. In the latter case, Raptor will just hold the position, without requiring external setpoints. When Raptor replaces the Offboard mode, it requires external setpoints to be activated. + type: boolean + default: false + category: System + + MC_RAPTOR_INTREF: + description: + short: Use internal reference instead of trajectory_setpoint + long: | + When enabled, instead of using the trajectory_setpoint, the position and yaw of the vehicle at the point when the Raptor mode is activated will be used as reference. + Use 'mc_raptor intref lissajous ' to configure the trajectory. + type: enum + values: + 0: None + 1: Lissajous + default: 0 + category: System diff --git a/src/modules/mc_raptor/trajectories/lissajous.hpp b/src/modules/mc_raptor/trajectories/lissajous.hpp new file mode 100644 index 0000000000..340ead01bf --- /dev/null +++ b/src/modules/mc_raptor/trajectories/lissajous.hpp @@ -0,0 +1,38 @@ +#pragma once + +#include "trajectory.hpp" +#include + +struct LissajousParameters { + float A = 0.5f; // amplitude a + float B = 1.0f; // amplitude b + float C = 0.0f; // amplitude c + float a = 2.0f; // frequency a + float b = 1.0f; // frequency b + float c = 1.0f; // frequency c + float duration = 10.0f; + float ramp_duration = 3.0f; +}; + +inline Setpoint lissajous(float time, const LissajousParameters ¶ms) +{ + float time_velocity = (params.ramp_duration > 0.0f) + ? fminf(time, params.ramp_duration) / params.ramp_duration + : 1.0f; + + float ramp_time = time_velocity * fminf(time, params.ramp_duration) / 2.0f; + float progress = (ramp_time + fmaxf(0.0f, time - params.ramp_duration)) * 2.0f * static_cast(M_PI) / params.duration; + float d_progress = 2.0f * static_cast(M_PI) * time_velocity / params.duration; + + Setpoint setpoint{}; + setpoint.position[0] = params.A * sinf(params.a * progress); + setpoint.position[1] = params.B * sinf(params.b * progress); + setpoint.position[2] = params.C * sinf(params.c * progress); + setpoint.yaw = 0.0f; + setpoint.linear_velocity[0] = params.A * cosf(params.a * progress) * params.a * d_progress; + setpoint.linear_velocity[1] = params.B * cosf(params.b * progress) * params.b * d_progress; + setpoint.linear_velocity[2] = params.C * cosf(params.c * progress) * params.c * d_progress; + setpoint.yaw_rate = 0.0f; + + return setpoint; +} diff --git a/src/modules/mc_raptor/trajectories/trajectory.hpp b/src/modules/mc_raptor/trajectories/trajectory.hpp new file mode 100644 index 0000000000..fcdf405701 --- /dev/null +++ b/src/modules/mc_raptor/trajectories/trajectory.hpp @@ -0,0 +1,6 @@ +struct Setpoint { + float position[3]; + float yaw; + float linear_velocity[3]; + float yaw_rate; +};